diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000000..d832750163 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,97 @@ +cmake_minimum_required(VERSION 2.8) +project(ORB_SLAM2) + +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF() + +MESSAGE("Build type: " ${CMAKE_BUILD_TYPE}) + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") + +# Check C++11 or C++0x support +include(CheckCXXCompilerFlag) +CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + add_definitions(-DCOMPILEDWITHC11) + message(STATUS "Using flag -std=c++11.") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") + add_definitions(-DCOMPILEDWITHC0X) + message(STATUS "Using flag -std=c++0x.") +else() + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") +endif() + +LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules) + +find_package(OpenCV 2.4.3 REQUIRED) +find_package(Eigen3 3.1.0 REQUIRED) +find_package(Pangolin REQUIRED) + +include_directories( +${PROJECT_SOURCE_DIR} +${PROJECT_SOURCE_DIR}/include +${EIGEN3_INCLUDE_DIR} +${Pangolin_INCLUDE_DIRS} +) + +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/lib) + +add_library(${PROJECT_NAME} SHARED +src/System.cc +src/Tracking.cc +src/LocalMapping.cc +src/LoopClosing.cc +src/ORBextractor.cc +src/ORBmatcher.cc +src/FrameDrawer.cc +src/Converter.cc +src/MapPoint.cc +src/KeyFrame.cc +src/Map.cc +src/MapDrawer.cc +src/Optimizer.cc +src/PnPsolver.cc +src/Frame.cc +src/KeyFrameDatabase.cc +src/Sim3Solver.cc +src/Initializer.cc +src/Viewer.cc +) + +target_link_libraries(${PROJECT_NAME} +${OpenCV_LIBS} +${EIGEN3_LIBS} +${Pangolin_LIBRARIES} +${PROJECT_SOURCE_DIR}/Thirdparty/DBoW2/lib/libDBoW2.so +${PROJECT_SOURCE_DIR}/Thirdparty/g2o/lib/libg2o.so +) + +# Build examples + +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/RGB-D) + +add_executable(rgbd_tum +Examples/RGB-D/rgbd_tum.cc) +target_link_libraries(rgbd_tum ${PROJECT_NAME}) + +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Stereo) + +add_executable(stereo_kitti +Examples/Stereo/stereo_kitti.cc) +target_link_libraries(stereo_kitti ${PROJECT_NAME}) + +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${PROJECT_SOURCE_DIR}/Examples/Monocular) + +add_executable(mono_tum +Examples/Monocular/mono_tum.cc) +target_link_libraries(mono_tum ${PROJECT_NAME}) + +add_executable(mono_kitti +Examples/Monocular/mono_kitti.cc) +target_link_libraries(mono_kitti ${PROJECT_NAME}) + diff --git a/Dependencies.md b/Dependencies.md new file mode 100644 index 0000000000..315f4963b5 --- /dev/null +++ b/Dependencies.md @@ -0,0 +1,50 @@ +##List of Known Dependencies +###ORB-SLAM2 version 1.0 + +In this document we list all the pieces of code included by ORB-SLAM2 and linked libraries which are not property of the authors of ORB-SLAM2. + + +#####Code in **src** and **include** folders + +* *ORBextractor.cc*. +This is a modified version of orb.cpp of OpenCV library. The original code is BSD licensed. + +* *PnPsolver.h, PnPsolver.cc*. +This is a modified version of the epnp.h and epnp.cc of Vincent Lepetit. +This code can be found in popular BSD licensed computer vision libraries as [OpenCV](https://github.com/Itseez/opencv/blob/master/modules/calib3d/src/epnp.cpp) and [OpenGV](https://github.com/laurentkneip/opengv/blob/master/src/absolute_pose/modules/Epnp.cpp). The original code is FreeBSD. + +* Function *ORBmatcher::DescriptorDistance* in *ORBmatcher.cc*. +The code is from: http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel. +The code is in the public domain. + +#####Code in Thirdparty folder + +* All code in **DBoW2** folder. +This is a modified version of [DBoW2](https://github.com/dorian3d/DBoW2) and [DLib](https://github.com/dorian3d/DLib) library. All files included are BSD licensed. + +* All code in **g2o** folder. +This is a modified version of [g2o](https://github.com/RainerKuemmerle/g2o). All files included are BSD licensed. + +#####Library dependencies + +* **Pangolin (visualization and user interface)**. +https://github.com/stevenlovegrove/Pangolin + +* **OpenCV**. +BSD licensed. + +* **Eigen3**. +For versions greater than 3.1.1 is MPL2, earlier versions are LGPLv3. + +* **BLAS** (required by g2o). +[Freely-available software](http://www.netlib.org/blas/#_licensing). + +* **LAPACK**(required by g2o). +BSD licensed. + +* **ROS (Optional, only if you build Examples/ROS)**. +BSD licensed. In the manifest.xml the only declared package dependencies are roscpp, tf, sensor_msgs, image_transport, cv_bridge, which are all BSD licensed. + + + +Updated: 23/01/2016 Raúl Mur Artal diff --git a/Examples/Monocular/KITTI00-02.yaml b/Examples/Monocular/KITTI00-02.yaml new file mode 100644 index 0000000000..e4faba1633 --- /dev/null +++ b/Examples/Monocular/KITTI00-02.yaml @@ -0,0 +1,57 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 718.856 +Camera.fy: 718.856 +Camera.cx: 607.1928 +Camera.cy: 185.2157 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +# Camera frames per second +Camera.fps: 10.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 2000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.1 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 1 +Viewer.PointSize:2 +Viewer.CameraSize: 0.15 +Viewer.CameraLineWidth: 2 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -10 +Viewer.ViewpointZ: -0.1 +Viewer.ViewpointF: 2000 + diff --git a/Examples/Monocular/KITTI03.yaml b/Examples/Monocular/KITTI03.yaml new file mode 100644 index 0000000000..b081bd08a2 --- /dev/null +++ b/Examples/Monocular/KITTI03.yaml @@ -0,0 +1,57 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 721.5377 +Camera.fy: 721.5377 +Camera.cx: 609.5593 +Camera.cy: 172.854 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +# Camera frames per second +Camera.fps: 10.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 2000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.1 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 1 +Viewer.PointSize:2 +Viewer.CameraSize: 0.15 +Viewer.CameraLineWidth: 2 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -10 +Viewer.ViewpointZ: -0.1 +Viewer.ViewpointF: 2000 + diff --git a/Examples/Monocular/KITTI04-12.yaml b/Examples/Monocular/KITTI04-12.yaml new file mode 100644 index 0000000000..e0e18c7b7e --- /dev/null +++ b/Examples/Monocular/KITTI04-12.yaml @@ -0,0 +1,57 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 707.0912 +Camera.fy: 707.0912 +Camera.cx: 601.8873 +Camera.cy: 183.1104 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +# Camera frames per second +Camera.fps: 10.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 2000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.1 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 1 +Viewer.PointSize:2 +Viewer.CameraSize: 0.15 +Viewer.CameraLineWidth: 2 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -10 +Viewer.ViewpointZ: -0.1 +Viewer.ViewpointF: 2000 + diff --git a/Examples/Monocular/TUM1.yaml b/Examples/Monocular/TUM1.yaml new file mode 100644 index 0000000000..145f792f43 --- /dev/null +++ b/Examples/Monocular/TUM1.yaml @@ -0,0 +1,58 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 517.306408 +Camera.fy: 516.469215 +Camera.cx: 318.643040 +Camera.cy: 255.313989 + +Camera.k1: 0.262383 +Camera.k2: -0.953104 +Camera.p1: -0.005358 +Camera.p2: 0.002628 +Camera.k3: 1.163314 + +# Camera frames per second +Camera.fps: 30.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/Monocular/TUM2.yaml b/Examples/Monocular/TUM2.yaml new file mode 100644 index 0000000000..914fbcf652 --- /dev/null +++ b/Examples/Monocular/TUM2.yaml @@ -0,0 +1,58 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 520.908620 +Camera.fy: 521.007327 +Camera.cx: 325.141442 +Camera.cy: 249.701764 + +Camera.k1: 0.231222 +Camera.k2: -0.784899 +Camera.p1: -0.003257 +Camera.p2: -0.000105 +Camera.k3: 0.917205 + +# Camera frames per second +Camera.fps: 30.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/Monocular/TUM3.yaml b/Examples/Monocular/TUM3.yaml new file mode 100644 index 0000000000..e08c8e6c25 --- /dev/null +++ b/Examples/Monocular/TUM3.yaml @@ -0,0 +1,57 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 535.4 +Camera.fy: 539.2 +Camera.cx: 320.1 +Camera.cy: 247.6 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +# Camera frames per second +Camera.fps: 30.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/Monocular/mono_kitti.cc b/Examples/Monocular/mono_kitti.cc new file mode 100644 index 0000000000..28e5de57f4 --- /dev/null +++ b/Examples/Monocular/mono_kitti.cc @@ -0,0 +1,156 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include +#include +#include +#include + +#include + +#include"System.h" + +using namespace std; + +void LoadImages(const string &strSequence, vector &vstrImageFilenames, + vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 4) + { + cerr << endl << "Usage: ./mono_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageFilenames; + vector vTimestamps; + LoadImages(string(argv[3]), vstrImageFilenames, vTimestamps); + + int nImages = vstrImageFilenames.size(); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + cout << endl << "-------" << endl; + cout << "Start processing sequence ..." << endl; + cout << "Images in the sequence: " << nImages << endl << endl; + + // Main loop + cv::Mat im; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageFilenames, vector &vTimestamps) +{ + ifstream fTimes; + string strPathTimeFile = strPathToSequence + "/times.txt"; + fTimes.open(strPathTimeFile.c_str()); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + double t; + ss >> t; + vTimestamps.push_back(t); + } + } + + string strPrefixLeft = strPathToSequence + "/image_0/"; + + const int nTimes = vTimestamps.size(); + vstrImageFilenames.resize(nTimes); + + for(int i=0; i (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strFile, vector &vstrImageFilenames, + vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 4) + { + cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_sequence" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageFilenames; + vector vTimestamps; + string strFile = string(argv[3])+"/rgb.txt"; + LoadImages(strFile, vstrImageFilenames, vTimestamps); + + int nImages = vstrImageFilenames.size(); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + cout << endl << "-------" << endl; + cout << "Start processing sequence ..." << endl; + cout << "Images in the sequence: " << nImages << endl << endl; + + // Main loop + cv::Mat im; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageFilenames, vector &vTimestamps) +{ + ifstream f; + f.open(strFile.c_str()); + + // skip first three lines + string s0; + getline(f,s0); + getline(f,s0); + getline(f,s0); + + while(!f.eof()) + { + string s; + getline(f,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + double t; + string sRGB; + ss >> t; + vTimestamps.push_back(t); + ss >> sRGB; + vstrImageFilenames.push_back(sRGB); + } + } +} diff --git a/Examples/RGB-D/TUM1.yaml b/Examples/RGB-D/TUM1.yaml new file mode 100644 index 0000000000..189e9889f0 --- /dev/null +++ b/Examples/RGB-D/TUM1.yaml @@ -0,0 +1,70 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 517.306408 +Camera.fy: 516.469215 +Camera.cx: 318.643040 +Camera.cy: 255.313989 + +Camera.k1: 0.262383 +Camera.k2: -0.953104 +Camera.p1: -0.005358 +Camera.p2: 0.002628 +Camera.k3: 1.163314 + +Camera.width: 640 +Camera.height: 480 + +# Camera frames per second +Camera.fps: 30.0 + +# IR projector baseline times fx (aprox.) +Camera.bf: 40.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 50.0 + +# Deptmap values factor +DepthMapFactor: 5000.0 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/RGB-D/TUM2.yaml b/Examples/RGB-D/TUM2.yaml new file mode 100644 index 0000000000..bd7c6fa102 --- /dev/null +++ b/Examples/RGB-D/TUM2.yaml @@ -0,0 +1,70 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 520.908620 +Camera.fy: 521.007327 +Camera.cx: 325.141442 +Camera.cy: 249.701764 + +Camera.k1: 0.231222 +Camera.k2: -0.784899 +Camera.p1: -0.003257 +Camera.p2: -0.000105 +Camera.k3: 0.917205 + +Camera.width: 640 +Camera.height: 480 + +# Camera frames per second +Camera.fps: 30.0 + +# IR projector baseline times fx (aprox.) +Camera.bf: 40.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 50.0 + +# Deptmap values factor +DepthMapFactor: 5208.0 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/RGB-D/TUM3.yaml b/Examples/RGB-D/TUM3.yaml new file mode 100644 index 0000000000..3875230fcf --- /dev/null +++ b/Examples/RGB-D/TUM3.yaml @@ -0,0 +1,69 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 535.4 +Camera.fy: 539.2 +Camera.cx: 320.1 +Camera.cy: 247.6 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +Camera.width: 640 +Camera.height: 480 + +# Camera frames per second +Camera.fps: 30.0 + +# IR projector baseline times fx (aprox.) +Camera.bf: 40.0 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 50.0 + +# Deptmap values factor +DepthMapFactor: 5000.0 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 1000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.05 +Viewer.KeyFrameLineWidth: 1 +Viewer.GraphLineWidth: 0.9 +Viewer.PointSize:2 +Viewer.CameraSize: 0.08 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -0.7 +Viewer.ViewpointZ: -1.8 +Viewer.ViewpointF: 500 + diff --git a/Examples/RGB-D/associations/fr1_desk.txt b/Examples/RGB-D/associations/fr1_desk.txt new file mode 100644 index 0000000000..ebe7df9028 --- /dev/null +++ b/Examples/RGB-D/associations/fr1_desk.txt @@ -0,0 +1,573 @@ +1305031453.359684 rgb/1305031453.359684.png 1305031453.374112 depth/1305031453.374112.png +1305031453.391690 rgb/1305031453.391690.png 1305031453.404816 depth/1305031453.404816.png +1305031453.423683 rgb/1305031453.423683.png 1305031453.436941 depth/1305031453.436941.png +1305031453.459685 rgb/1305031453.459685.png 1305031453.473352 depth/1305031453.473352.png +1305031453.491698 rgb/1305031453.491698.png 1305031453.505218 depth/1305031453.505218.png +1305031453.523684 rgb/1305031453.523684.png 1305031453.538301 depth/1305031453.538301.png +1305031453.559753 rgb/1305031453.559753.png 1305031453.574074 depth/1305031453.574074.png +1305031453.591640 rgb/1305031453.591640.png 1305031453.605314 depth/1305031453.605314.png +1305031453.627706 rgb/1305031453.627706.png 1305031453.636951 depth/1305031453.636951.png +1305031453.659600 rgb/1305031453.659600.png 1305031453.673185 depth/1305031453.673185.png +1305031453.691678 rgb/1305031453.691678.png 1305031453.705487 depth/1305031453.705487.png +1305031453.727652 rgb/1305031453.727652.png 1305031453.736856 depth/1305031453.736856.png +1305031453.759694 rgb/1305031453.759694.png 1305031453.773786 depth/1305031453.773786.png +1305031453.791716 rgb/1305031453.791716.png 1305031453.805041 depth/1305031453.805041.png +1305031453.827773 rgb/1305031453.827773.png 1305031453.840352 depth/1305031453.840352.png +1305031453.859705 rgb/1305031453.859705.png 1305031453.869618 depth/1305031453.869618.png +1305031453.891710 rgb/1305031453.891710.png 1305031453.905519 depth/1305031453.905519.png +1305031453.927723 rgb/1305031453.927723.png 1305031453.940012 depth/1305031453.940012.png +1305031453.959641 rgb/1305031453.959641.png 1305031453.972592 depth/1305031453.972592.png +1305031453.991624 rgb/1305031453.991624.png 1305031454.003179 depth/1305031454.003179.png +1305031454.027662 rgb/1305031454.027662.png 1305031454.040976 depth/1305031454.040976.png +1305031454.059654 rgb/1305031454.059654.png 1305031454.072690 depth/1305031454.072690.png +1305031454.091651 rgb/1305031454.091651.png 1305031454.104619 depth/1305031454.104619.png +1305031454.127701 rgb/1305031454.127701.png 1305031454.141030 depth/1305031454.141030.png +1305031454.159672 rgb/1305031454.159672.png 1305031454.172688 depth/1305031454.172688.png +1305031454.191658 rgb/1305031454.191658.png 1305031454.204626 depth/1305031454.204626.png +1305031454.227671 rgb/1305031454.227671.png 1305031454.240858 depth/1305031454.240858.png +1305031454.259627 rgb/1305031454.259627.png 1305031454.273489 depth/1305031454.273489.png +1305031454.291639 rgb/1305031454.291639.png 1305031454.304744 depth/1305031454.304744.png +1305031454.327699 rgb/1305031454.327699.png 1305031454.340806 depth/1305031454.340806.png +1305031454.359636 rgb/1305031454.359636.png 1305031454.372652 depth/1305031454.372652.png +1305031454.391677 rgb/1305031454.391677.png 1305031454.401962 depth/1305031454.401962.png +1305031454.427465 rgb/1305031454.427465.png 1305031454.437248 depth/1305031454.437248.png +1305031454.459913 rgb/1305031454.459913.png 1305031454.470741 depth/1305031454.470741.png +1305031454.491617 rgb/1305031454.491617.png 1305031454.503859 depth/1305031454.503859.png +1305031454.527700 rgb/1305031454.527700.png 1305031454.538424 depth/1305031454.538424.png +1305031454.559575 rgb/1305031454.559575.png 1305031454.570323 depth/1305031454.570323.png +1305031454.591635 rgb/1305031454.591635.png 1305031454.602019 depth/1305031454.602019.png +1305031454.627580 rgb/1305031454.627580.png 1305031454.639284 depth/1305031454.639284.png +1305031454.659528 rgb/1305031454.659528.png 1305031454.669573 depth/1305031454.669573.png +1305031454.691884 rgb/1305031454.691884.png 1305031454.702030 depth/1305031454.702030.png +1305031454.727659 rgb/1305031454.727659.png 1305031454.740764 depth/1305031454.740764.png +1305031454.759732 rgb/1305031454.759732.png 1305031454.772865 depth/1305031454.772865.png +1305031454.791641 rgb/1305031454.791641.png 1305031454.802574 depth/1305031454.802574.png +1305031454.827570 rgb/1305031454.827570.png 1305031454.840500 depth/1305031454.840500.png +1305031454.859620 rgb/1305031454.859620.png 1305031454.870269 depth/1305031454.870269.png +1305031454.891764 rgb/1305031454.891764.png 1305031454.901065 depth/1305031454.901065.png +1305031454.927567 rgb/1305031454.927567.png 1305031454.940240 depth/1305031454.940240.png +1305031454.959648 rgb/1305031454.959648.png 1305031454.973081 depth/1305031454.973081.png +1305031454.991937 rgb/1305031454.991937.png 1305031455.010759 depth/1305031455.010759.png +1305031455.027799 rgb/1305031455.027799.png 1305031455.040446 depth/1305031455.040446.png +1305031455.059636 rgb/1305031455.059636.png 1305031455.074282 depth/1305031455.074282.png +1305031455.091700 rgb/1305031455.091700.png 1305031455.110340 depth/1305031455.110340.png +1305031455.127695 rgb/1305031455.127695.png 1305031455.142700 depth/1305031455.142700.png +1305031455.159720 rgb/1305031455.159720.png 1305031455.172771 depth/1305031455.172771.png +1305031455.191655 rgb/1305031455.191655.png 1305031455.210307 depth/1305031455.210307.png +1305031455.227581 rgb/1305031455.227581.png 1305031455.240960 depth/1305031455.240960.png +1305031455.259631 rgb/1305031455.259631.png 1305031455.273001 depth/1305031455.273001.png +1305031455.291831 rgb/1305031455.291831.png 1305031455.310303 depth/1305031455.310303.png +1305031455.327766 rgb/1305031455.327766.png 1305031455.342381 depth/1305031455.342381.png +1305031455.359630 rgb/1305031455.359630.png 1305031455.374120 depth/1305031455.374120.png +1305031455.391665 rgb/1305031455.391665.png 1305031455.409213 depth/1305031455.409213.png +1305031455.427642 rgb/1305031455.427642.png 1305031455.442380 depth/1305031455.442380.png +1305031455.459589 rgb/1305031455.459589.png 1305031455.473168 depth/1305031455.473168.png +1305031455.491637 rgb/1305031455.491637.png 1305031455.509397 depth/1305031455.509397.png +1305031455.527610 rgb/1305031455.527610.png 1305031455.540835 depth/1305031455.540835.png +1305031455.559669 rgb/1305031455.559669.png 1305031455.572996 depth/1305031455.572996.png +1305031455.591645 rgb/1305031455.591645.png 1305031455.608802 depth/1305031455.608802.png +1305031455.627617 rgb/1305031455.627617.png 1305031455.641333 depth/1305031455.641333.png +1305031455.659615 rgb/1305031455.659615.png 1305031455.672887 depth/1305031455.672887.png +1305031455.691605 rgb/1305031455.691605.png 1305031455.707680 depth/1305031455.707680.png +1305031455.727628 rgb/1305031455.727628.png 1305031455.742005 depth/1305031455.742005.png +1305031455.759683 rgb/1305031455.759683.png 1305031455.773667 depth/1305031455.773667.png +1305031455.791666 rgb/1305031455.791666.png 1305031455.809109 depth/1305031455.809109.png +1305031455.827590 rgb/1305031455.827590.png 1305031455.838364 depth/1305031455.838364.png +1305031455.859526 rgb/1305031455.859526.png 1305031455.872220 depth/1305031455.872220.png +1305031455.891657 rgb/1305031455.891657.png 1305031455.908418 depth/1305031455.908418.png +1305031455.927955 rgb/1305031455.927955.png 1305031455.939606 depth/1305031455.939606.png +1305031455.959716 rgb/1305031455.959716.png 1305031455.973594 depth/1305031455.973594.png +1305031455.991694 rgb/1305031455.991694.png 1305031456.008998 depth/1305031456.008998.png +1305031456.027770 rgb/1305031456.027770.png 1305031456.041930 depth/1305031456.041930.png +1305031456.059713 rgb/1305031456.059713.png 1305031456.073846 depth/1305031456.073846.png +1305031456.091707 rgb/1305031456.091707.png 1305031456.108963 depth/1305031456.108963.png +1305031456.127645 rgb/1305031456.127645.png 1305031456.140836 depth/1305031456.140836.png +1305031456.159731 rgb/1305031456.159731.png 1305031456.173198 depth/1305031456.173198.png +1305031456.191658 rgb/1305031456.191658.png 1305031456.208934 depth/1305031456.208934.png +1305031456.227678 rgb/1305031456.227678.png 1305031456.240996 depth/1305031456.240996.png +1305031456.291675 rgb/1305031456.291675.png 1305031456.277928 depth/1305031456.277928.png +1305031456.327718 rgb/1305031456.327718.png 1305031456.341659 depth/1305031456.341659.png +1305031456.391619 rgb/1305031456.391619.png 1305031456.377115 depth/1305031456.377115.png +1305031456.427662 rgb/1305031456.427662.png 1305031456.440717 depth/1305031456.440717.png +1305031456.491677 rgb/1305031456.491677.png 1305031456.476027 depth/1305031456.476027.png +1305031456.527641 rgb/1305031456.527641.png 1305031456.541832 depth/1305031456.541832.png +1305031456.591651 rgb/1305031456.591651.png 1305031456.576087 depth/1305031456.576087.png +1305031456.627612 rgb/1305031456.627612.png 1305031456.640699 depth/1305031456.640699.png +1305031456.691612 rgb/1305031456.691612.png 1305031456.675835 depth/1305031456.675835.png +1305031456.727693 rgb/1305031456.727693.png 1305031456.740863 depth/1305031456.740863.png +1305031456.791649 rgb/1305031456.791649.png 1305031456.777218 depth/1305031456.777218.png +1305031456.827603 rgb/1305031456.827603.png 1305031456.841050 depth/1305031456.841050.png +1305031456.891672 rgb/1305031456.891672.png 1305031456.878006 depth/1305031456.878006.png +1305031456.927690 rgb/1305031456.927690.png 1305031456.942298 depth/1305031456.942298.png +1305031456.959667 rgb/1305031456.959667.png 1305031456.977139 depth/1305031456.977139.png +1305031456.991709 rgb/1305031456.991709.png 1305031457.006193 depth/1305031457.006193.png +1305031457.027648 rgb/1305031457.027648.png 1305031457.042512 depth/1305031457.042512.png +1305031457.091655 rgb/1305031457.091655.png 1305031457.076011 depth/1305031457.076011.png +1305031457.127632 rgb/1305031457.127632.png 1305031457.142120 depth/1305031457.142120.png +1305031457.191735 rgb/1305031457.191735.png 1305031457.177463 depth/1305031457.177463.png +1305031457.227543 rgb/1305031457.227543.png 1305031457.240792 depth/1305031457.240792.png +1305031457.291656 rgb/1305031457.291656.png 1305031457.277247 depth/1305031457.277247.png +1305031457.327548 rgb/1305031457.327548.png 1305031457.342954 depth/1305031457.342954.png +1305031457.391684 rgb/1305031457.391684.png 1305031457.376037 depth/1305031457.376037.png +1305031457.427641 rgb/1305031457.427641.png 1305031457.441357 depth/1305031457.441357.png +1305031457.491705 rgb/1305031457.491705.png 1305031457.476577 depth/1305031457.476577.png +1305031457.527638 rgb/1305031457.527638.png 1305031457.508603 depth/1305031457.508603.png +1305031457.559685 rgb/1305031457.559685.png 1305031457.543946 depth/1305031457.543946.png +1305031457.591678 rgb/1305031457.591678.png 1305031457.576581 depth/1305031457.576581.png +1305031457.627526 rgb/1305031457.627526.png 1305031457.643534 depth/1305031457.643534.png +1305031457.659632 rgb/1305031457.659632.png 1305031457.675414 depth/1305031457.675414.png +1305031457.691570 rgb/1305031457.691570.png 1305031457.707739 depth/1305031457.707739.png +1305031457.727669 rgb/1305031457.727669.png 1305031457.745071 depth/1305031457.745071.png +1305031457.759556 rgb/1305031457.759556.png 1305031457.773518 depth/1305031457.773518.png +1305031457.791567 rgb/1305031457.791567.png 1305031457.807824 depth/1305031457.807824.png +1305031457.827699 rgb/1305031457.827699.png 1305031457.842853 depth/1305031457.842853.png +1305031457.859623 rgb/1305031457.859623.png 1305031457.875920 depth/1305031457.875920.png +1305031457.891593 rgb/1305031457.891593.png 1305031457.906126 depth/1305031457.906126.png +1305031457.927633 rgb/1305031457.927633.png 1305031457.942604 depth/1305031457.942604.png +1305031457.991644 rgb/1305031457.991644.png 1305031457.976744 depth/1305031457.976744.png +1305031458.027845 rgb/1305031458.027845.png 1305031458.009019 depth/1305031458.009019.png +1305031458.059689 rgb/1305031458.059689.png 1305031458.046303 depth/1305031458.046303.png +1305031458.091690 rgb/1305031458.091690.png 1305031458.077315 depth/1305031458.077315.png +1305031458.127605 rgb/1305031458.127605.png 1305031458.108896 depth/1305031458.108896.png +1305031458.159638 rgb/1305031458.159638.png 1305031458.144808 depth/1305031458.144808.png +1305031458.191646 rgb/1305031458.191646.png 1305031458.178039 depth/1305031458.178039.png +1305031458.227611 rgb/1305031458.227611.png 1305031458.209384 depth/1305031458.209384.png +1305031458.259934 rgb/1305031458.259934.png 1305031458.245729 depth/1305031458.245729.png +1305031458.291664 rgb/1305031458.291664.png 1305031458.277447 depth/1305031458.277447.png +1305031458.327628 rgb/1305031458.327628.png 1305031458.308343 depth/1305031458.308343.png +1305031458.359590 rgb/1305031458.359590.png 1305031458.343898 depth/1305031458.343898.png +1305031458.391626 rgb/1305031458.391626.png 1305031458.376213 depth/1305031458.376213.png +1305031458.427598 rgb/1305031458.427598.png 1305031458.407856 depth/1305031458.407856.png +1305031458.459637 rgb/1305031458.459637.png 1305031458.443957 depth/1305031458.443957.png +1305031458.491696 rgb/1305031458.491696.png 1305031458.476034 depth/1305031458.476034.png +1305031458.527737 rgb/1305031458.527737.png 1305031458.508869 depth/1305031458.508869.png +1305031458.559628 rgb/1305031458.559628.png 1305031458.544401 depth/1305031458.544401.png +1305031458.591641 rgb/1305031458.591641.png 1305031458.576178 depth/1305031458.576178.png +1305031458.627659 rgb/1305031458.627659.png 1305031458.608421 depth/1305031458.608421.png +1305031458.659623 rgb/1305031458.659623.png 1305031458.643659 depth/1305031458.643659.png +1305031458.691674 rgb/1305031458.691674.png 1305031458.676991 depth/1305031458.676991.png +1305031458.727650 rgb/1305031458.727650.png 1305031458.744924 depth/1305031458.744924.png +1305031458.759945 rgb/1305031458.759945.png 1305031458.773802 depth/1305031458.773802.png +1305031458.791632 rgb/1305031458.791632.png 1305031458.810621 depth/1305031458.810621.png +1305031458.827564 rgb/1305031458.827564.png 1305031458.842919 depth/1305031458.842919.png +1305031458.891665 rgb/1305031458.891665.png 1305031458.875889 depth/1305031458.875889.png +1305031458.927621 rgb/1305031458.927621.png 1305031458.910599 depth/1305031458.910599.png +1305031458.959617 rgb/1305031458.959617.png 1305031458.943997 depth/1305031458.943997.png +1305031458.991647 rgb/1305031458.991647.png 1305031458.976007 depth/1305031458.976007.png +1305031459.027665 rgb/1305031459.027665.png 1305031459.012560 depth/1305031459.012560.png +1305031459.059631 rgb/1305031459.059631.png 1305031459.073657 depth/1305031459.073657.png +1305031459.127618 rgb/1305031459.127618.png 1305031459.112711 depth/1305031459.112711.png +1305031459.159639 rgb/1305031459.159639.png 1305031459.144497 depth/1305031459.144497.png +1305031459.191674 rgb/1305031459.191674.png 1305031459.176463 depth/1305031459.176463.png +1305031459.227607 rgb/1305031459.227607.png 1305031459.244159 depth/1305031459.244159.png +1305031459.259760 rgb/1305031459.259760.png 1305031459.274941 depth/1305031459.274941.png +1305031459.327632 rgb/1305031459.327632.png 1305031459.311921 depth/1305031459.311921.png +1305031459.359651 rgb/1305031459.359651.png 1305031459.374084 depth/1305031459.374084.png +1305031459.391667 rgb/1305031459.391667.png 1305031459.408831 depth/1305031459.408831.png +1305031459.427646 rgb/1305031459.427646.png 1305031459.443181 depth/1305031459.443181.png +1305031459.459679 rgb/1305031459.459679.png 1305031459.473401 depth/1305031459.473401.png +1305031459.527594 rgb/1305031459.527594.png 1305031459.510267 depth/1305031459.510267.png +1305031459.559647 rgb/1305031459.559647.png 1305031459.544431 depth/1305031459.544431.png +1305031459.591695 rgb/1305031459.591695.png 1305031459.576817 depth/1305031459.576817.png +1305031459.627608 rgb/1305031459.627608.png 1305031459.611939 depth/1305031459.611939.png +1305031459.659641 rgb/1305031459.659641.png 1305031459.643453 depth/1305031459.643453.png +1305031459.691604 rgb/1305031459.691604.png 1305031459.675678 depth/1305031459.675678.png +1305031459.727551 rgb/1305031459.727551.png 1305031459.743425 depth/1305031459.743425.png +1305031459.791650 rgb/1305031459.791650.png 1305031459.776577 depth/1305031459.776577.png +1305031459.827664 rgb/1305031459.827664.png 1305031459.812562 depth/1305031459.812562.png +1305031459.859660 rgb/1305031459.859660.png 1305031459.844736 depth/1305031459.844736.png +1305031459.891596 rgb/1305031459.891596.png 1305031459.877006 depth/1305031459.877006.png +1305031459.927607 rgb/1305031459.927607.png 1305031459.943616 depth/1305031459.943616.png +1305031459.991725 rgb/1305031459.991725.png 1305031459.979430 depth/1305031459.979430.png +1305031460.027565 rgb/1305031460.027565.png 1305031460.011909 depth/1305031460.011909.png +1305031460.059659 rgb/1305031460.059659.png 1305031460.043717 depth/1305031460.043717.png +1305031460.091717 rgb/1305031460.091717.png 1305031460.079449 depth/1305031460.079449.png +1305031460.127690 rgb/1305031460.127690.png 1305031460.111951 depth/1305031460.111951.png +1305031460.159678 rgb/1305031460.159678.png 1305031460.144204 depth/1305031460.144204.png +1305031460.191559 rgb/1305031460.191559.png 1305031460.178730 depth/1305031460.178730.png +1305031460.227761 rgb/1305031460.227761.png 1305031460.243467 depth/1305031460.243467.png +1305031460.291689 rgb/1305031460.291689.png 1305031460.279164 depth/1305031460.279164.png +1305031460.327512 rgb/1305031460.327512.png 1305031460.342879 depth/1305031460.342879.png +1305031460.391611 rgb/1305031460.391611.png 1305031460.377806 depth/1305031460.377806.png +1305031460.427477 rgb/1305031460.427477.png 1305031460.409883 depth/1305031460.409883.png +1305031460.459620 rgb/1305031460.459620.png 1305031460.444036 depth/1305031460.444036.png +1305031460.491504 rgb/1305031460.491504.png 1305031460.479856 depth/1305031460.479856.png +1305031460.527570 rgb/1305031460.527570.png 1305031460.508966 depth/1305031460.508966.png +1305031460.559647 rgb/1305031460.559647.png 1305031460.544245 depth/1305031460.544245.png +1305031460.591855 rgb/1305031460.591855.png 1305031460.579561 depth/1305031460.579561.png +1305031460.627625 rgb/1305031460.627625.png 1305031460.612190 depth/1305031460.612190.png +1305031460.659764 rgb/1305031460.659764.png 1305031460.644011 depth/1305031460.644011.png +1305031460.691671 rgb/1305031460.691671.png 1305031460.679350 depth/1305031460.679350.png +1305031460.727675 rgb/1305031460.727675.png 1305031460.711684 depth/1305031460.711684.png +1305031460.759667 rgb/1305031460.759667.png 1305031460.743767 depth/1305031460.743767.png +1305031460.791660 rgb/1305031460.791660.png 1305031460.779201 depth/1305031460.779201.png +1305031460.827660 rgb/1305031460.827660.png 1305031460.811318 depth/1305031460.811318.png +1305031460.859714 rgb/1305031460.859714.png 1305031460.843836 depth/1305031460.843836.png +1305031460.891774 rgb/1305031460.891774.png 1305031460.879093 depth/1305031460.879093.png +1305031460.927562 rgb/1305031460.927562.png 1305031460.943375 depth/1305031460.943375.png +1305031460.991668 rgb/1305031460.991668.png 1305031460.979083 depth/1305031460.979083.png +1305031461.027620 rgb/1305031461.027620.png 1305031461.043398 depth/1305031461.043398.png +1305031461.091728 rgb/1305031461.091728.png 1305031461.079602 depth/1305031461.079602.png +1305031461.127586 rgb/1305031461.127586.png 1305031461.111961 depth/1305031461.111961.png +1305031461.159720 rgb/1305031461.159720.png 1305031461.144098 depth/1305031461.144098.png +1305031461.192013 rgb/1305031461.192013.png 1305031461.179883 depth/1305031461.179883.png +1305031461.227607 rgb/1305031461.227607.png 1305031461.211180 depth/1305031461.211180.png +1305031461.259642 rgb/1305031461.259642.png 1305031461.246864 depth/1305031461.246864.png +1305031461.291656 rgb/1305031461.291656.png 1305031461.278888 depth/1305031461.278888.png +1305031461.327751 rgb/1305031461.327751.png 1305031461.311240 depth/1305031461.311240.png +1305031461.359709 rgb/1305031461.359709.png 1305031461.346875 depth/1305031461.346875.png +1305031461.391708 rgb/1305031461.391708.png 1305031461.378850 depth/1305031461.378850.png +1305031461.427624 rgb/1305031461.427624.png 1305031461.411130 depth/1305031461.411130.png +1305031461.459781 rgb/1305031461.459781.png 1305031461.447015 depth/1305031461.447015.png +1305031461.491677 rgb/1305031461.491677.png 1305031461.478901 depth/1305031461.478901.png +1305031461.527705 rgb/1305031461.527705.png 1305031461.512120 depth/1305031461.512120.png +1305031461.559677 rgb/1305031461.559677.png 1305031461.547338 depth/1305031461.547338.png +1305031461.591690 rgb/1305031461.591690.png 1305031461.578847 depth/1305031461.578847.png +1305031461.627541 rgb/1305031461.627541.png 1305031461.609662 depth/1305031461.609662.png +1305031461.659622 rgb/1305031461.659622.png 1305031461.646970 depth/1305031461.646970.png +1305031461.691563 rgb/1305031461.691563.png 1305031461.676203 depth/1305031461.676203.png +1305031461.727602 rgb/1305031461.727602.png 1305031461.711212 depth/1305031461.711212.png +1305031461.759684 rgb/1305031461.759684.png 1305031461.746919 depth/1305031461.746919.png +1305031461.791612 rgb/1305031461.791612.png 1305031461.778616 depth/1305031461.778616.png +1305031461.827615 rgb/1305031461.827615.png 1305031461.811319 depth/1305031461.811319.png +1305031461.859767 rgb/1305031461.859767.png 1305031461.847090 depth/1305031461.847090.png +1305031461.891723 rgb/1305031461.891723.png 1305031461.879162 depth/1305031461.879162.png +1305031461.927758 rgb/1305031461.927758.png 1305031461.911121 depth/1305031461.911121.png +1305031461.959703 rgb/1305031461.959703.png 1305031461.947264 depth/1305031461.947264.png +1305031461.991590 rgb/1305031461.991590.png 1305031461.979223 depth/1305031461.979223.png +1305031462.027675 rgb/1305031462.027675.png 1305031462.011791 depth/1305031462.011791.png +1305031462.059837 rgb/1305031462.059837.png 1305031462.047463 depth/1305031462.047463.png +1305031462.091777 rgb/1305031462.091777.png 1305031462.079285 depth/1305031462.079285.png +1305031462.127739 rgb/1305031462.127739.png 1305031462.112081 depth/1305031462.112081.png +1305031462.159646 rgb/1305031462.159646.png 1305031462.147634 depth/1305031462.147634.png +1305031462.191641 rgb/1305031462.191641.png 1305031462.179358 depth/1305031462.179358.png +1305031462.227633 rgb/1305031462.227633.png 1305031462.212836 depth/1305031462.212836.png +1305031462.259765 rgb/1305031462.259765.png 1305031462.248986 depth/1305031462.248986.png +1305031462.291629 rgb/1305031462.291629.png 1305031462.280774 depth/1305031462.280774.png +1305031462.327540 rgb/1305031462.327540.png 1305031462.311931 depth/1305031462.311931.png +1305031462.359732 rgb/1305031462.359732.png 1305031462.347816 depth/1305031462.347816.png +1305031462.391695 rgb/1305031462.391695.png 1305031462.379950 depth/1305031462.379950.png +1305031462.427635 rgb/1305031462.427635.png 1305031462.413016 depth/1305031462.413016.png +1305031462.459897 rgb/1305031462.459897.png 1305031462.448295 depth/1305031462.448295.png +1305031462.492008 rgb/1305031462.492008.png 1305031462.480843 depth/1305031462.480843.png +1305031462.527670 rgb/1305031462.527670.png 1305031462.517041 depth/1305031462.517041.png +1305031462.559862 rgb/1305031462.559862.png 1305031462.548959 depth/1305031462.548959.png +1305031462.591862 rgb/1305031462.591862.png 1305031462.581088 depth/1305031462.581088.png +1305031462.627851 rgb/1305031462.627851.png 1305031462.617123 depth/1305031462.617123.png +1305031462.659660 rgb/1305031462.659660.png 1305031462.648708 depth/1305031462.648708.png +1305031462.692548 rgb/1305031462.692548.png 1305031462.680788 depth/1305031462.680788.png +1305031462.727652 rgb/1305031462.727652.png 1305031462.716812 depth/1305031462.716812.png +1305031462.759782 rgb/1305031462.759782.png 1305031462.748732 depth/1305031462.748732.png +1305031462.791943 rgb/1305031462.791943.png 1305031462.780885 depth/1305031462.780885.png +1305031462.827816 rgb/1305031462.827816.png 1305031462.816821 depth/1305031462.816821.png +1305031462.859782 rgb/1305031462.859782.png 1305031462.848525 depth/1305031462.848525.png +1305031462.891847 rgb/1305031462.891847.png 1305031462.880471 depth/1305031462.880471.png +1305031462.927607 rgb/1305031462.927607.png 1305031462.916800 depth/1305031462.916800.png +1305031462.959676 rgb/1305031462.959676.png 1305031462.947939 depth/1305031462.947939.png +1305031462.995550 rgb/1305031462.995550.png 1305031462.979943 depth/1305031462.979943.png +1305031463.027667 rgb/1305031463.027667.png 1305031463.016121 depth/1305031463.016121.png +1305031463.059810 rgb/1305031463.059810.png 1305031463.050783 depth/1305031463.050783.png +1305031463.095809 rgb/1305031463.095809.png 1305031463.076870 depth/1305031463.076870.png +1305031463.127550 rgb/1305031463.127550.png 1305031463.116806 depth/1305031463.116806.png +1305031463.159787 rgb/1305031463.159787.png 1305031463.148565 depth/1305031463.148565.png +1305031463.195657 rgb/1305031463.195657.png 1305031463.180505 depth/1305031463.180505.png +1305031463.227784 rgb/1305031463.227784.png 1305031463.217123 depth/1305031463.217123.png +1305031463.260034 rgb/1305031463.260034.png 1305031463.248719 depth/1305031463.248719.png +1305031463.295737 rgb/1305031463.295737.png 1305031463.278737 depth/1305031463.278737.png +1305031463.327739 rgb/1305031463.327739.png 1305031463.317110 depth/1305031463.317110.png +1305031463.359750 rgb/1305031463.359750.png 1305031463.348740 depth/1305031463.348740.png +1305031463.395630 rgb/1305031463.395630.png 1305031463.380514 depth/1305031463.380514.png +1305031463.427716 rgb/1305031463.427716.png 1305031463.416326 depth/1305031463.416326.png +1305031463.459756 rgb/1305031463.459756.png 1305031463.444773 depth/1305031463.444773.png +1305031463.495629 rgb/1305031463.495629.png 1305031463.480415 depth/1305031463.480415.png +1305031463.527670 rgb/1305031463.527670.png 1305031463.516994 depth/1305031463.516994.png +1305031463.559751 rgb/1305031463.559751.png 1305031463.548505 depth/1305031463.548505.png +1305031463.595600 rgb/1305031463.595600.png 1305031463.580684 depth/1305031463.580684.png +1305031463.627588 rgb/1305031463.627588.png 1305031463.616671 depth/1305031463.616671.png +1305031463.659766 rgb/1305031463.659766.png 1305031463.646147 depth/1305031463.646147.png +1305031463.695640 rgb/1305031463.695640.png 1305031463.683908 depth/1305031463.683908.png +1305031463.727588 rgb/1305031463.727588.png 1305031463.716110 depth/1305031463.716110.png +1305031463.759674 rgb/1305031463.759674.png 1305031463.747849 depth/1305031463.747849.png +1305031463.795647 rgb/1305031463.795647.png 1305031463.783912 depth/1305031463.783912.png +1305031463.827761 rgb/1305031463.827761.png 1305031463.815883 depth/1305031463.815883.png +1305031463.859910 rgb/1305031463.859910.png 1305031463.848094 depth/1305031463.848094.png +1305031463.895648 rgb/1305031463.895648.png 1305031463.883817 depth/1305031463.883817.png +1305031463.927664 rgb/1305031463.927664.png 1305031463.917433 depth/1305031463.917433.png +1305031463.959680 rgb/1305031463.959680.png 1305031463.944435 depth/1305031463.944435.png +1305031463.995821 rgb/1305031463.995821.png 1305031463.983748 depth/1305031463.983748.png +1305031464.027703 rgb/1305031464.027703.png 1305031464.015867 depth/1305031464.015867.png +1305031464.059652 rgb/1305031464.059652.png 1305031464.047778 depth/1305031464.047778.png +1305031464.095634 rgb/1305031464.095634.png 1305031464.083152 depth/1305031464.083152.png +1305031464.127681 rgb/1305031464.127681.png 1305031464.115837 depth/1305031464.115837.png +1305031464.159817 rgb/1305031464.159817.png 1305031464.147663 depth/1305031464.147663.png +1305031464.195585 rgb/1305031464.195585.png 1305031464.183566 depth/1305031464.183566.png +1305031464.227624 rgb/1305031464.227624.png 1305031464.212447 depth/1305031464.212447.png +1305031464.259644 rgb/1305031464.259644.png 1305031464.247602 depth/1305031464.247602.png +1305031464.295667 rgb/1305031464.295667.png 1305031464.283694 depth/1305031464.283694.png +1305031464.327866 rgb/1305031464.327866.png 1305031464.315699 depth/1305031464.315699.png +1305031464.359684 rgb/1305031464.359684.png 1305031464.347553 depth/1305031464.347553.png +1305031464.395611 rgb/1305031464.395611.png 1305031464.383465 depth/1305031464.383465.png +1305031464.427634 rgb/1305031464.427634.png 1305031464.415539 depth/1305031464.415539.png +1305031464.459689 rgb/1305031464.459689.png 1305031464.444269 depth/1305031464.444269.png +1305031464.495633 rgb/1305031464.495633.png 1305031464.487561 depth/1305031464.487561.png +1305031464.527574 rgb/1305031464.527574.png 1305031464.513688 depth/1305031464.513688.png +1305031464.559703 rgb/1305031464.559703.png 1305031464.548007 depth/1305031464.548007.png +1305031464.595698 rgb/1305031464.595698.png 1305031464.584260 depth/1305031464.584260.png +1305031464.627672 rgb/1305031464.627672.png 1305031464.615688 depth/1305031464.615688.png +1305031464.659749 rgb/1305031464.659749.png 1305031464.648851 depth/1305031464.648851.png +1305031464.695663 rgb/1305031464.695663.png 1305031464.684318 depth/1305031464.684318.png +1305031464.727652 rgb/1305031464.727652.png 1305031464.716305 depth/1305031464.716305.png +1305031464.759740 rgb/1305031464.759740.png 1305031464.748588 depth/1305031464.748588.png +1305031464.796021 rgb/1305031464.796021.png 1305031464.784268 depth/1305031464.784268.png +1305031464.827759 rgb/1305031464.827759.png 1305031464.816195 depth/1305031464.816195.png +1305031464.859654 rgb/1305031464.859654.png 1305031464.848283 depth/1305031464.848283.png +1305031464.895817 rgb/1305031464.895817.png 1305031464.884177 depth/1305031464.884177.png +1305031464.927799 rgb/1305031464.927799.png 1305031464.916391 depth/1305031464.916391.png +1305031464.959763 rgb/1305031464.959763.png 1305031464.952471 depth/1305031464.952471.png +1305031464.995687 rgb/1305031464.995687.png 1305031464.984257 depth/1305031464.984257.png +1305031465.027823 rgb/1305031465.027823.png 1305031465.015390 depth/1305031465.015390.png +1305031465.059749 rgb/1305031465.059749.png 1305031465.048430 depth/1305031465.048430.png +1305031465.095700 rgb/1305031465.095700.png 1305031465.083338 depth/1305031465.083338.png +1305031465.127664 rgb/1305031465.127664.png 1305031465.115475 depth/1305031465.115475.png +1305031465.159842 rgb/1305031465.159842.png 1305031465.151558 depth/1305031465.151558.png +1305031465.195564 rgb/1305031465.195564.png 1305031465.183558 depth/1305031465.183558.png +1305031465.227907 rgb/1305031465.227907.png 1305031465.215832 depth/1305031465.215832.png +1305031465.259807 rgb/1305031465.259807.png 1305031465.251788 depth/1305031465.251788.png +1305031465.295623 rgb/1305031465.295623.png 1305031465.283737 depth/1305031465.283737.png +1305031465.327674 rgb/1305031465.327674.png 1305031465.315985 depth/1305031465.315985.png +1305031465.359948 rgb/1305031465.359948.png 1305031465.351729 depth/1305031465.351729.png +1305031465.395586 rgb/1305031465.395586.png 1305031465.383701 depth/1305031465.383701.png +1305031465.427697 rgb/1305031465.427697.png 1305031465.416543 depth/1305031465.416543.png +1305031465.460125 rgb/1305031465.460125.png 1305031465.452401 depth/1305031465.452401.png +1305031465.495703 rgb/1305031465.495703.png 1305031465.483803 depth/1305031465.483803.png +1305031465.527622 rgb/1305031465.527622.png 1305031465.516043 depth/1305031465.516043.png +1305031465.559812 rgb/1305031465.559812.png 1305031465.551838 depth/1305031465.551838.png +1305031465.595599 rgb/1305031465.595599.png 1305031465.583570 depth/1305031465.583570.png +1305031465.627688 rgb/1305031465.627688.png 1305031465.615685 depth/1305031465.615685.png +1305031465.660060 rgb/1305031465.660060.png 1305031465.651645 depth/1305031465.651645.png +1305031465.695668 rgb/1305031465.695668.png 1305031465.684759 depth/1305031465.684759.png +1305031465.727682 rgb/1305031465.727682.png 1305031465.716279 depth/1305031465.716279.png +1305031465.759766 rgb/1305031465.759766.png 1305031465.753153 depth/1305031465.753153.png +1305031465.795937 rgb/1305031465.795937.png 1305031465.784387 depth/1305031465.784387.png +1305031465.827996 rgb/1305031465.827996.png 1305031465.816591 depth/1305031465.816591.png +1305031465.859861 rgb/1305031465.859861.png 1305031465.852860 depth/1305031465.852860.png +1305031465.895494 rgb/1305031465.895494.png 1305031465.884370 depth/1305031465.884370.png +1305031465.927495 rgb/1305031465.927495.png 1305031465.912828 depth/1305031465.912828.png +1305031465.959710 rgb/1305031465.959710.png 1305031465.952840 depth/1305031465.952840.png +1305031465.995753 rgb/1305031465.995753.png 1305031465.984183 depth/1305031465.984183.png +1305031466.027644 rgb/1305031466.027644.png 1305031466.016599 depth/1305031466.016599.png +1305031466.059757 rgb/1305031466.059757.png 1305031466.052655 depth/1305031466.052655.png +1305031466.095840 rgb/1305031466.095840.png 1305031466.083913 depth/1305031466.083913.png +1305031466.127640 rgb/1305031466.127640.png 1305031466.116400 depth/1305031466.116400.png +1305031466.160428 rgb/1305031466.160428.png 1305031466.152540 depth/1305031466.152540.png +1305031466.195833 rgb/1305031466.195833.png 1305031466.184186 depth/1305031466.184186.png +1305031466.227951 rgb/1305031466.227951.png 1305031466.220477 depth/1305031466.220477.png +1305031466.259815 rgb/1305031466.259815.png 1305031466.252491 depth/1305031466.252491.png +1305031466.295737 rgb/1305031466.295737.png 1305031466.284389 depth/1305031466.284389.png +1305031466.327702 rgb/1305031466.327702.png 1305031466.320055 depth/1305031466.320055.png +1305031466.359829 rgb/1305031466.359829.png 1305031466.352082 depth/1305031466.352082.png +1305031466.395784 rgb/1305031466.395784.png 1305031466.384479 depth/1305031466.384479.png +1305031466.427819 rgb/1305031466.427819.png 1305031466.420844 depth/1305031466.420844.png +1305031466.459790 rgb/1305031466.459790.png 1305031466.452369 depth/1305031466.452369.png +1305031466.495809 rgb/1305031466.495809.png 1305031466.483315 depth/1305031466.483315.png +1305031466.527538 rgb/1305031466.527538.png 1305031466.519548 depth/1305031466.519548.png +1305031466.560353 rgb/1305031466.560353.png 1305031466.552219 depth/1305031466.552219.png +1305031466.595936 rgb/1305031466.595936.png 1305031466.584438 depth/1305031466.584438.png +1305031466.627549 rgb/1305031466.627549.png 1305031466.620424 depth/1305031466.620424.png +1305031466.659688 rgb/1305031466.659688.png 1305031466.648654 depth/1305031466.648654.png +1305031466.695822 rgb/1305031466.695822.png 1305031466.684412 depth/1305031466.684412.png +1305031466.728074 rgb/1305031466.728074.png 1305031466.719744 depth/1305031466.719744.png +1305031466.759637 rgb/1305031466.759637.png 1305031466.748734 depth/1305031466.748734.png +1305031466.795604 rgb/1305031466.795604.png 1305031466.784300 depth/1305031466.784300.png +1305031466.827879 rgb/1305031466.827879.png 1305031466.819502 depth/1305031466.819502.png +1305031466.859665 rgb/1305031466.859665.png 1305031466.851527 depth/1305031466.851527.png +1305031466.895694 rgb/1305031466.895694.png 1305031466.883430 depth/1305031466.883430.png +1305031466.927756 rgb/1305031466.927756.png 1305031466.919411 depth/1305031466.919411.png +1305031466.959728 rgb/1305031466.959728.png 1305031466.952451 depth/1305031466.952451.png +1305031466.995712 rgb/1305031466.995712.png 1305031466.984027 depth/1305031466.984027.png +1305031467.027843 rgb/1305031467.027843.png 1305031467.020424 depth/1305031467.020424.png +1305031467.059700 rgb/1305031467.059700.png 1305031467.052391 depth/1305031467.052391.png +1305031467.095687 rgb/1305031467.095687.png 1305031467.084130 depth/1305031467.084130.png +1305031467.128974 rgb/1305031467.128974.png 1305031467.120528 depth/1305031467.120528.png +1305031467.159660 rgb/1305031467.159660.png 1305031467.152363 depth/1305031467.152363.png +1305031467.195663 rgb/1305031467.195663.png 1305031467.184216 depth/1305031467.184216.png +1305031467.227704 rgb/1305031467.227704.png 1305031467.220466 depth/1305031467.220466.png +1305031467.259694 rgb/1305031467.259694.png 1305031467.252275 depth/1305031467.252275.png +1305031467.295846 rgb/1305031467.295846.png 1305031467.284258 depth/1305031467.284258.png +1305031467.328008 rgb/1305031467.328008.png 1305031467.318028 depth/1305031467.318028.png +1305031467.359654 rgb/1305031467.359654.png 1305031467.349355 depth/1305031467.349355.png +1305031467.395756 rgb/1305031467.395756.png 1305031467.383844 depth/1305031467.383844.png +1305031467.427783 rgb/1305031467.427783.png 1305031467.420160 depth/1305031467.420160.png +1305031467.459692 rgb/1305031467.459692.png 1305031467.452057 depth/1305031467.452057.png +1305031467.496058 rgb/1305031467.496058.png 1305031467.484357 depth/1305031467.484357.png +1305031467.527663 rgb/1305031467.527663.png 1305031467.520535 depth/1305031467.520535.png +1305031467.559763 rgb/1305031467.559763.png 1305031467.552164 depth/1305031467.552164.png +1305031467.595989 rgb/1305031467.595989.png 1305031467.584354 depth/1305031467.584354.png +1305031467.627532 rgb/1305031467.627532.png 1305031467.618680 depth/1305031467.618680.png +1305031467.659626 rgb/1305031467.659626.png 1305031467.651977 depth/1305031467.651977.png +1305031467.695886 rgb/1305031467.695886.png 1305031467.686044 depth/1305031467.686044.png +1305031467.727535 rgb/1305031467.727535.png 1305031467.718326 depth/1305031467.718326.png +1305031467.759907 rgb/1305031467.759907.png 1305031467.752580 depth/1305031467.752580.png +1305031467.796075 rgb/1305031467.796075.png 1305031467.788562 depth/1305031467.788562.png +1305031467.827800 rgb/1305031467.827800.png 1305031467.820454 depth/1305031467.820454.png +1305031467.859729 rgb/1305031467.859729.png 1305031467.852678 depth/1305031467.852678.png +1305031467.895947 rgb/1305031467.895947.png 1305031467.888472 depth/1305031467.888472.png +1305031467.927754 rgb/1305031467.927754.png 1305031467.920800 depth/1305031467.920800.png +1305031467.959826 rgb/1305031467.959826.png 1305031467.952485 depth/1305031467.952485.png +1305031467.995754 rgb/1305031467.995754.png 1305031467.988523 depth/1305031467.988523.png +1305031468.028107 rgb/1305031468.028107.png 1305031468.020491 depth/1305031468.020491.png +1305031468.059850 rgb/1305031468.059850.png 1305031468.052668 depth/1305031468.052668.png +1305031468.095867 rgb/1305031468.095867.png 1305031468.088379 depth/1305031468.088379.png +1305031468.127816 rgb/1305031468.127816.png 1305031468.120522 depth/1305031468.120522.png +1305031468.159864 rgb/1305031468.159864.png 1305031468.152356 depth/1305031468.152356.png +1305031468.195985 rgb/1305031468.195985.png 1305031468.188327 depth/1305031468.188327.png +1305031468.228158 rgb/1305031468.228158.png 1305031468.220648 depth/1305031468.220648.png +1305031468.259754 rgb/1305031468.259754.png 1305031468.252517 depth/1305031468.252517.png +1305031468.295830 rgb/1305031468.295830.png 1305031468.288361 depth/1305031468.288361.png +1305031468.327847 rgb/1305031468.327847.png 1305031468.320522 depth/1305031468.320522.png +1305031468.359787 rgb/1305031468.359787.png 1305031468.352594 depth/1305031468.352594.png +1305031468.395860 rgb/1305031468.395860.png 1305031468.384700 depth/1305031468.384700.png +1305031468.428025 rgb/1305031468.428025.png 1305031468.420595 depth/1305031468.420595.png +1305031468.459759 rgb/1305031468.459759.png 1305031468.452605 depth/1305031468.452605.png +1305031468.495809 rgb/1305031468.495809.png 1305031468.488646 depth/1305031468.488646.png +1305031468.527756 rgb/1305031468.527756.png 1305031468.520786 depth/1305031468.520786.png +1305031468.559739 rgb/1305031468.559739.png 1305031468.552701 depth/1305031468.552701.png +1305031468.595768 rgb/1305031468.595768.png 1305031468.588614 depth/1305031468.588614.png +1305031468.627626 rgb/1305031468.627626.png 1305031468.620590 depth/1305031468.620590.png +1305031468.659579 rgb/1305031468.659579.png 1305031468.656644 depth/1305031468.656644.png +1305031468.695835 rgb/1305031468.695835.png 1305031468.688643 depth/1305031468.688643.png +1305031468.727785 rgb/1305031468.727785.png 1305031468.720560 depth/1305031468.720560.png +1305031468.759628 rgb/1305031468.759628.png 1305031468.756725 depth/1305031468.756725.png +1305031468.795796 rgb/1305031468.795796.png 1305031468.788562 depth/1305031468.788562.png +1305031468.829247 rgb/1305031468.829247.png 1305031468.817997 depth/1305031468.817997.png +1305031468.859659 rgb/1305031468.859659.png 1305031468.854887 depth/1305031468.854887.png +1305031468.895873 rgb/1305031468.895873.png 1305031468.889220 depth/1305031468.889220.png +1305031468.928141 rgb/1305031468.928141.png 1305031468.920539 depth/1305031468.920539.png +1305031468.959594 rgb/1305031468.959594.png 1305031468.956482 depth/1305031468.956482.png +1305031468.995711 rgb/1305031468.995711.png 1305031468.986011 depth/1305031468.986011.png +1305031469.027699 rgb/1305031469.027699.png 1305031469.020731 depth/1305031469.020731.png +1305031469.059832 rgb/1305031469.059832.png 1305031469.056318 depth/1305031469.056318.png +1305031469.095723 rgb/1305031469.095723.png 1305031469.088069 depth/1305031469.088069.png +1305031469.127679 rgb/1305031469.127679.png 1305031469.119984 depth/1305031469.119984.png +1305031469.159703 rgb/1305031469.159703.png 1305031469.155046 depth/1305031469.155046.png +1305031469.195540 rgb/1305031469.195540.png 1305031469.184648 depth/1305031469.184648.png +1305031469.227754 rgb/1305031469.227754.png 1305031469.219541 depth/1305031469.219541.png +1305031469.259586 rgb/1305031469.259586.png 1305031469.256002 depth/1305031469.256002.png +1305031469.296754 rgb/1305031469.296754.png 1305031469.288263 depth/1305031469.288263.png +1305031469.327618 rgb/1305031469.327618.png 1305031469.319772 depth/1305031469.319772.png +1305031469.359592 rgb/1305031469.359592.png 1305031469.356116 depth/1305031469.356116.png +1305031469.395695 rgb/1305031469.395695.png 1305031469.388556 depth/1305031469.388556.png +1305031469.427651 rgb/1305031469.427651.png 1305031469.420278 depth/1305031469.420278.png +1305031469.459668 rgb/1305031469.459668.png 1305031469.456563 depth/1305031469.456563.png +1305031469.495744 rgb/1305031469.495744.png 1305031469.488520 depth/1305031469.488520.png +1305031469.527622 rgb/1305031469.527622.png 1305031469.520417 depth/1305031469.520417.png +1305031469.559645 rgb/1305031469.559645.png 1305031469.556139 depth/1305031469.556139.png +1305031469.595755 rgb/1305031469.595755.png 1305031469.588500 depth/1305031469.588500.png +1305031469.627752 rgb/1305031469.627752.png 1305031469.620563 depth/1305031469.620563.png +1305031469.659590 rgb/1305031469.659590.png 1305031469.656279 depth/1305031469.656279.png +1305031469.695613 rgb/1305031469.695613.png 1305031469.687925 depth/1305031469.687925.png +1305031469.727679 rgb/1305031469.727679.png 1305031469.718943 depth/1305031469.718943.png +1305031469.759599 rgb/1305031469.759599.png 1305031469.756754 depth/1305031469.756754.png +1305031469.795621 rgb/1305031469.795621.png 1305031469.784733 depth/1305031469.784733.png +1305031469.827526 rgb/1305031469.827526.png 1305031469.820544 depth/1305031469.820544.png +1305031469.859574 rgb/1305031469.859574.png 1305031469.854359 depth/1305031469.854359.png +1305031469.895755 rgb/1305031469.895755.png 1305031469.885343 depth/1305031469.885343.png +1305031469.927854 rgb/1305031469.927854.png 1305031469.921773 depth/1305031469.921773.png +1305031469.959805 rgb/1305031469.959805.png 1305031469.953180 depth/1305031469.953180.png +1305031469.995551 rgb/1305031469.995551.png 1305031469.985327 depth/1305031469.985327.png +1305031470.027694 rgb/1305031470.027694.png 1305031470.024714 depth/1305031470.024714.png +1305031470.059638 rgb/1305031470.059638.png 1305031470.057400 depth/1305031470.057400.png +1305031470.095944 rgb/1305031470.095944.png 1305031470.088874 depth/1305031470.088874.png +1305031470.127633 rgb/1305031470.127633.png 1305031470.124820 depth/1305031470.124820.png +1305031470.159626 rgb/1305031470.159626.png 1305031470.156744 depth/1305031470.156744.png +1305031470.196092 rgb/1305031470.196092.png 1305031470.188876 depth/1305031470.188876.png +1305031470.227618 rgb/1305031470.227618.png 1305031470.224776 depth/1305031470.224776.png +1305031470.259965 rgb/1305031470.259965.png 1305031470.253015 depth/1305031470.253015.png +1305031470.295718 rgb/1305031470.295718.png 1305031470.287867 depth/1305031470.287867.png +1305031470.327644 rgb/1305031470.327644.png 1305031470.324266 depth/1305031470.324266.png +1305031470.359624 rgb/1305031470.359624.png 1305031470.356871 depth/1305031470.356871.png +1305031470.395823 rgb/1305031470.395823.png 1305031470.388056 depth/1305031470.388056.png +1305031470.427641 rgb/1305031470.427641.png 1305031470.424090 depth/1305031470.424090.png +1305031470.459721 rgb/1305031470.459721.png 1305031470.455875 depth/1305031470.455875.png +1305031470.495686 rgb/1305031470.495686.png 1305031470.487958 depth/1305031470.487958.png +1305031470.527689 rgb/1305031470.527689.png 1305031470.524431 depth/1305031470.524431.png +1305031470.559677 rgb/1305031470.559677.png 1305031470.556484 depth/1305031470.556484.png +1305031470.595760 rgb/1305031470.595760.png 1305031470.588797 depth/1305031470.588797.png +1305031470.627729 rgb/1305031470.627729.png 1305031470.624535 depth/1305031470.624535.png +1305031470.659690 rgb/1305031470.659690.png 1305031470.656787 depth/1305031470.656787.png +1305031470.695630 rgb/1305031470.695630.png 1305031470.688640 depth/1305031470.688640.png +1305031470.727654 rgb/1305031470.727654.png 1305031470.724461 depth/1305031470.724461.png +1305031470.759682 rgb/1305031470.759682.png 1305031470.755944 depth/1305031470.755944.png +1305031470.795615 rgb/1305031470.795615.png 1305031470.788407 depth/1305031470.788407.png +1305031470.827831 rgb/1305031470.827831.png 1305031470.820633 depth/1305031470.820633.png +1305031470.859645 rgb/1305031470.859645.png 1305031470.855509 depth/1305031470.855509.png +1305031470.895722 rgb/1305031470.895722.png 1305031470.886079 depth/1305031470.886079.png +1305031470.927684 rgb/1305031470.927684.png 1305031470.924410 depth/1305031470.924410.png +1305031470.959647 rgb/1305031470.959647.png 1305031470.956439 depth/1305031470.956439.png +1305031470.995996 rgb/1305031470.995996.png 1305031470.988276 depth/1305031470.988276.png +1305031471.027644 rgb/1305031471.027644.png 1305031471.024309 depth/1305031471.024309.png +1305031471.059636 rgb/1305031471.059636.png 1305031471.056616 depth/1305031471.056616.png +1305031471.095777 rgb/1305031471.095777.png 1305031471.088440 depth/1305031471.088440.png +1305031471.127663 rgb/1305031471.127663.png 1305031471.123837 depth/1305031471.123837.png +1305031471.159649 rgb/1305031471.159649.png 1305031471.155886 depth/1305031471.155886.png +1305031471.195703 rgb/1305031471.195703.png 1305031471.192698 depth/1305031471.192698.png +1305031471.227569 rgb/1305031471.227569.png 1305031471.224404 depth/1305031471.224404.png +1305031471.259722 rgb/1305031471.259722.png 1305031471.256397 depth/1305031471.256397.png +1305031471.296068 rgb/1305031471.296068.png 1305031471.288603 depth/1305031471.288603.png +1305031471.327642 rgb/1305031471.327642.png 1305031471.324440 depth/1305031471.324440.png +1305031471.359615 rgb/1305031471.359615.png 1305031471.356569 depth/1305031471.356569.png +1305031471.395730 rgb/1305031471.395730.png 1305031471.392751 depth/1305031471.392751.png +1305031471.427704 rgb/1305031471.427704.png 1305031471.424494 depth/1305031471.424494.png +1305031471.459647 rgb/1305031471.459647.png 1305031471.456975 depth/1305031471.456975.png +1305031471.496491 rgb/1305031471.496491.png 1305031471.492705 depth/1305031471.492705.png +1305031471.527624 rgb/1305031471.527624.png 1305031471.524343 depth/1305031471.524343.png +1305031471.559671 rgb/1305031471.559671.png 1305031471.556561 depth/1305031471.556561.png +1305031471.595702 rgb/1305031471.595702.png 1305031471.592606 depth/1305031471.592606.png +1305031471.627621 rgb/1305031471.627621.png 1305031471.624486 depth/1305031471.624486.png +1305031471.659642 rgb/1305031471.659642.png 1305031471.656831 depth/1305031471.656831.png +1305031471.695609 rgb/1305031471.695609.png 1305031471.693182 depth/1305031471.693182.png +1305031471.727501 rgb/1305031471.727501.png 1305031471.724753 depth/1305031471.724753.png +1305031471.759702 rgb/1305031471.759702.png 1305031471.753002 depth/1305031471.753002.png +1305031471.795801 rgb/1305031471.795801.png 1305031471.792706 depth/1305031471.792706.png +1305031471.827639 rgb/1305031471.827639.png 1305031471.823821 depth/1305031471.823821.png +1305031471.859665 rgb/1305031471.859665.png 1305031471.855793 depth/1305031471.855793.png +1305031471.895604 rgb/1305031471.895604.png 1305031471.892838 depth/1305031471.892838.png +1305031471.927651 rgb/1305031471.927651.png 1305031471.924928 depth/1305031471.924928.png +1305031471.959643 rgb/1305031471.959643.png 1305031471.957162 depth/1305031471.957162.png +1305031471.995573 rgb/1305031471.995573.png 1305031471.993177 depth/1305031471.993177.png +1305031472.027638 rgb/1305031472.027638.png 1305031472.024660 depth/1305031472.024660.png +1305031472.059668 rgb/1305031472.059668.png 1305031472.058063 depth/1305031472.058063.png +1305031472.095601 rgb/1305031472.095601.png 1305031472.092883 depth/1305031472.092883.png +1305031472.127594 rgb/1305031472.127594.png 1305031472.124760 depth/1305031472.124760.png +1305031472.159645 rgb/1305031472.159645.png 1305031472.156982 depth/1305031472.156982.png +1305031472.195682 rgb/1305031472.195682.png 1305031472.192890 depth/1305031472.192890.png +1305031472.227626 rgb/1305031472.227626.png 1305031472.224678 depth/1305031472.224678.png +1305031472.263840 rgb/1305031472.263840.png 1305031472.256642 depth/1305031472.256642.png +1305031472.295671 rgb/1305031472.295671.png 1305031472.293139 depth/1305031472.293139.png +1305031472.327678 rgb/1305031472.327678.png 1305031472.324844 depth/1305031472.324844.png +1305031472.363577 rgb/1305031472.363577.png 1305031472.360912 depth/1305031472.360912.png +1305031472.395599 rgb/1305031472.395599.png 1305031472.392956 depth/1305031472.392956.png +1305031472.427686 rgb/1305031472.427686.png 1305031472.424694 depth/1305031472.424694.png +1305031472.463603 rgb/1305031472.463603.png 1305031472.460919 depth/1305031472.460919.png +1305031472.495626 rgb/1305031472.495626.png 1305031472.492972 depth/1305031472.492972.png +1305031472.527625 rgb/1305031472.527625.png 1305031472.524781 depth/1305031472.524781.png +1305031472.563587 rgb/1305031472.563587.png 1305031472.561296 depth/1305031472.561296.png +1305031472.595675 rgb/1305031472.595675.png 1305031472.592968 depth/1305031472.592968.png +1305031472.627701 rgb/1305031472.627701.png 1305031472.624647 depth/1305031472.624647.png +1305031472.663575 rgb/1305031472.663575.png 1305031472.660836 depth/1305031472.660836.png +1305031472.695755 rgb/1305031472.695755.png 1305031472.693008 depth/1305031472.693008.png +1305031472.727628 rgb/1305031472.727628.png 1305031472.724752 depth/1305031472.724752.png +1305031472.763578 rgb/1305031472.763578.png 1305031472.760654 depth/1305031472.760654.png +1305031472.795640 rgb/1305031472.795640.png 1305031472.792775 depth/1305031472.792775.png +1305031472.827627 rgb/1305031472.827627.png 1305031472.824692 depth/1305031472.824692.png +1305031472.863598 rgb/1305031472.863598.png 1305031472.860936 depth/1305031472.860936.png +1305031472.895713 rgb/1305031472.895713.png 1305031472.892944 depth/1305031472.892944.png +1305031472.927685 rgb/1305031472.927685.png 1305031472.924814 depth/1305031472.924814.png +1305031472.963756 rgb/1305031472.963756.png 1305031472.961213 depth/1305031472.961213.png +1305031472.995704 rgb/1305031472.995704.png 1305031472.992815 depth/1305031472.992815.png +1305031473.027638 rgb/1305031473.027638.png 1305031473.024564 depth/1305031473.024564.png +1305031473.063684 rgb/1305031473.063684.png 1305031473.060795 depth/1305031473.060795.png +1305031473.095695 rgb/1305031473.095695.png 1305031473.092012 depth/1305031473.092012.png +1305031473.127744 rgb/1305031473.127744.png 1305031473.124072 depth/1305031473.124072.png +1305031473.167060 rgb/1305031473.167060.png 1305031473.158420 depth/1305031473.158420.png +1305031473.196069 rgb/1305031473.196069.png 1305031473.190828 depth/1305031473.190828.png diff --git a/Examples/RGB-D/associations/fr1_desk2.txt b/Examples/RGB-D/associations/fr1_desk2.txt new file mode 100644 index 0000000000..0f68a55806 --- /dev/null +++ b/Examples/RGB-D/associations/fr1_desk2.txt @@ -0,0 +1,620 @@ +1305031526.671473 rgb/1305031526.671473.png 1305031526.688356 depth/1305031526.688356.png +1305031526.707547 rgb/1305031526.707547.png 1305031526.721587 depth/1305031526.721587.png +1305031526.771481 rgb/1305031526.771481.png 1305031526.755957 depth/1305031526.755957.png +1305031526.807455 rgb/1305031526.807455.png 1305031526.822643 depth/1305031526.822643.png +1305031526.871446 rgb/1305031526.871446.png 1305031526.856844 depth/1305031526.856844.png +1305031526.907484 rgb/1305031526.907484.png 1305031526.920578 depth/1305031526.920578.png +1305031526.939618 rgb/1305031526.939618.png 1305031526.955033 depth/1305031526.955033.png +1305031526.971510 rgb/1305031526.971510.png 1305031526.987606 depth/1305031526.987606.png +1305031527.007595 rgb/1305031527.007595.png 1305031527.020791 depth/1305031527.020791.png +1305031527.039512 rgb/1305031527.039512.png 1305031527.055070 depth/1305031527.055070.png +1305031527.071487 rgb/1305031527.071487.png 1305031527.086965 depth/1305031527.086965.png +1305031527.107498 rgb/1305031527.107498.png 1305031527.119854 depth/1305031527.119854.png +1305031527.139473 rgb/1305031527.139473.png 1305031527.155465 depth/1305031527.155465.png +1305031527.171540 rgb/1305031527.171540.png 1305031527.186447 depth/1305031527.186447.png +1305031527.207588 rgb/1305031527.207588.png 1305031527.222219 depth/1305031527.222219.png +1305031527.271501 rgb/1305031527.271501.png 1305031527.256275 depth/1305031527.256275.png +1305031527.307472 rgb/1305031527.307472.png 1305031527.323213 depth/1305031527.323213.png +1305031527.339636 rgb/1305031527.339636.png 1305031527.355197 depth/1305031527.355197.png +1305031527.371505 rgb/1305031527.371505.png 1305031527.388471 depth/1305031527.388471.png +1305031527.407412 rgb/1305031527.407412.png 1305031527.422926 depth/1305031527.422926.png +1305031527.439476 rgb/1305031527.439476.png 1305031527.455773 depth/1305031527.455773.png +1305031527.471497 rgb/1305031527.471497.png 1305031527.486055 depth/1305031527.486055.png +1305031527.507487 rgb/1305031527.507487.png 1305031527.522397 depth/1305031527.522397.png +1305031527.539741 rgb/1305031527.539741.png 1305031527.554573 depth/1305031527.554573.png +1305031527.571506 rgb/1305031527.571506.png 1305031527.586987 depth/1305031527.586987.png +1305031527.607559 rgb/1305031527.607559.png 1305031527.622793 depth/1305031527.622793.png +1305031527.671547 rgb/1305031527.671547.png 1305031527.656028 depth/1305031527.656028.png +1305031527.707520 rgb/1305031527.707520.png 1305031527.721751 depth/1305031527.721751.png +1305031527.771461 rgb/1305031527.771461.png 1305031527.756472 depth/1305031527.756472.png +1305031527.807581 rgb/1305031527.807581.png 1305031527.789333 depth/1305031527.789333.png +1305031527.839601 rgb/1305031527.839601.png 1305031527.825562 depth/1305031527.825562.png +1305031527.871464 rgb/1305031527.871464.png 1305031527.857855 depth/1305031527.857855.png +1305031527.907477 rgb/1305031527.907477.png 1305031527.922214 depth/1305031527.922214.png +1305031527.939566 rgb/1305031527.939566.png 1305031527.954490 depth/1305031527.954490.png +1305031527.971502 rgb/1305031527.971502.png 1305031527.987977 depth/1305031527.987977.png +1305031528.039560 rgb/1305031528.039560.png 1305031528.025614 depth/1305031528.025614.png +1305031528.071546 rgb/1305031528.071546.png 1305031528.085297 depth/1305031528.085297.png +1305031528.107513 rgb/1305031528.107513.png 1305031528.124333 depth/1305031528.124333.png +1305031528.139513 rgb/1305031528.139513.png 1305031528.151873 depth/1305031528.151873.png +1305031528.171523 rgb/1305031528.171523.png 1305031528.186872 depth/1305031528.186872.png +1305031528.207527 rgb/1305031528.207527.png 1305031528.220887 depth/1305031528.220887.png +1305031528.239493 rgb/1305031528.239493.png 1305031528.251953 depth/1305031528.251953.png +1305031528.275450 rgb/1305031528.275450.png 1305031528.284263 depth/1305031528.284263.png +1305031528.307665 rgb/1305031528.307665.png 1305031528.321639 depth/1305031528.321639.png +1305031528.339593 rgb/1305031528.339593.png 1305031528.355032 depth/1305031528.355032.png +1305031528.375435 rgb/1305031528.375435.png 1305031528.384839 depth/1305031528.384839.png +1305031528.407459 rgb/1305031528.407459.png 1305031528.424006 depth/1305031528.424006.png +1305031528.439469 rgb/1305031528.439469.png 1305031528.453962 depth/1305031528.453962.png +1305031528.475342 rgb/1305031528.475342.png 1305031528.490720 depth/1305031528.490720.png +1305031528.539626 rgb/1305031528.539626.png 1305031528.524649 depth/1305031528.524649.png +1305031528.575449 rgb/1305031528.575449.png 1305031528.557069 depth/1305031528.557069.png +1305031528.607841 rgb/1305031528.607841.png 1305031528.592924 depth/1305031528.592924.png +1305031528.639487 rgb/1305031528.639487.png 1305031528.654033 depth/1305031528.654033.png +1305031528.707447 rgb/1305031528.707447.png 1305031528.692143 depth/1305031528.692143.png +1305031528.739609 rgb/1305031528.739609.png 1305031528.725000 depth/1305031528.725000.png +1305031528.775443 rgb/1305031528.775443.png 1305031528.756620 depth/1305031528.756620.png +1305031528.807559 rgb/1305031528.807559.png 1305031528.792160 depth/1305031528.792160.png +1305031528.839572 rgb/1305031528.839572.png 1305031528.824057 depth/1305031528.824057.png +1305031528.875433 rgb/1305031528.875433.png 1305031528.856114 depth/1305031528.856114.png +1305031528.907519 rgb/1305031528.907519.png 1305031528.892684 depth/1305031528.892684.png +1305031528.939602 rgb/1305031528.939602.png 1305031528.924061 depth/1305031528.924061.png +1305031528.975465 rgb/1305031528.975465.png 1305031528.956027 depth/1305031528.956027.png +1305031529.007487 rgb/1305031529.007487.png 1305031528.991870 depth/1305031528.991870.png +1305031529.039494 rgb/1305031529.039494.png 1305031529.024164 depth/1305031529.024164.png +1305031529.075422 rgb/1305031529.075422.png 1305031529.057246 depth/1305031529.057246.png +1305031529.107523 rgb/1305031529.107523.png 1305031529.092696 depth/1305031529.092696.png +1305031529.139597 rgb/1305031529.139597.png 1305031529.124051 depth/1305031529.124051.png +1305031529.175411 rgb/1305031529.175411.png 1305031529.156187 depth/1305031529.156187.png +1305031529.207466 rgb/1305031529.207466.png 1305031529.192085 depth/1305031529.192085.png +1305031529.239515 rgb/1305031529.239515.png 1305031529.224200 depth/1305031529.224200.png +1305031529.275389 rgb/1305031529.275389.png 1305031529.291235 depth/1305031529.291235.png +1305031529.307413 rgb/1305031529.307413.png 1305031529.323356 depth/1305031529.323356.png +1305031529.339486 rgb/1305031529.339486.png 1305031529.355813 depth/1305031529.355813.png +1305031529.375399 rgb/1305031529.375399.png 1305031529.388855 depth/1305031529.388855.png +1305031529.407513 rgb/1305031529.407513.png 1305031529.423010 depth/1305031529.423010.png +1305031529.439502 rgb/1305031529.439502.png 1305031529.457448 depth/1305031529.457448.png +1305031529.475403 rgb/1305031529.475403.png 1305031529.491343 depth/1305031529.491343.png +1305031529.507485 rgb/1305031529.507485.png 1305031529.522171 depth/1305031529.522171.png +1305031529.539489 rgb/1305031529.539489.png 1305031529.556350 depth/1305031529.556350.png +1305031529.607479 rgb/1305031529.607479.png 1305031529.593324 depth/1305031529.593324.png +1305031529.639746 rgb/1305031529.639746.png 1305031529.623772 depth/1305031529.623772.png +1305031529.675618 rgb/1305031529.675618.png 1305031529.657753 depth/1305031529.657753.png +1305031529.707557 rgb/1305031529.707557.png 1305031529.692840 depth/1305031529.692840.png +1305031529.739568 rgb/1305031529.739568.png 1305031529.725566 depth/1305031529.725566.png +1305031529.775501 rgb/1305031529.775501.png 1305031529.759598 depth/1305031529.759598.png +1305031529.807516 rgb/1305031529.807516.png 1305031529.792805 depth/1305031529.792805.png +1305031529.839505 rgb/1305031529.839505.png 1305031529.825293 depth/1305031529.825293.png +1305031529.875495 rgb/1305031529.875495.png 1305031529.891119 depth/1305031529.891119.png +1305031529.939498 rgb/1305031529.939498.png 1305031529.925850 depth/1305031529.925850.png +1305031529.975501 rgb/1305031529.975501.png 1305031529.960102 depth/1305031529.960102.png +1305031530.007409 rgb/1305031530.007409.png 1305031529.992331 depth/1305031529.992331.png +1305031530.039454 rgb/1305031530.039454.png 1305031530.024225 depth/1305031530.024225.png +1305031530.075443 rgb/1305031530.075443.png 1305031530.059982 depth/1305031530.059982.png +1305031530.107445 rgb/1305031530.107445.png 1305031530.091203 depth/1305031530.091203.png +1305031530.139497 rgb/1305031530.139497.png 1305031530.125990 depth/1305031530.125990.png +1305031530.175410 rgb/1305031530.175410.png 1305031530.159636 depth/1305031530.159636.png +1305031530.207486 rgb/1305031530.207486.png 1305031530.191494 depth/1305031530.191494.png +1305031530.239446 rgb/1305031530.239446.png 1305031530.224007 depth/1305031530.224007.png +1305031530.275407 rgb/1305031530.275407.png 1305031530.259074 depth/1305031530.259074.png +1305031530.307544 rgb/1305031530.307544.png 1305031530.292738 depth/1305031530.292738.png +1305031530.339724 rgb/1305031530.339724.png 1305031530.324398 depth/1305031530.324398.png +1305031530.375386 rgb/1305031530.375386.png 1305031530.355958 depth/1305031530.355958.png +1305031530.407465 rgb/1305031530.407465.png 1305031530.391987 depth/1305031530.391987.png +1305031530.439553 rgb/1305031530.439553.png 1305031530.423101 depth/1305031530.423101.png +1305031530.475439 rgb/1305031530.475439.png 1305031530.458850 depth/1305031530.458850.png +1305031530.507461 rgb/1305031530.507461.png 1305031530.492200 depth/1305031530.492200.png +1305031530.539532 rgb/1305031530.539532.png 1305031530.524323 depth/1305031530.524323.png +1305031530.575433 rgb/1305031530.575433.png 1305031530.591301 depth/1305031530.591301.png +1305031530.607559 rgb/1305031530.607559.png 1305031530.623002 depth/1305031530.623002.png +1305031530.639507 rgb/1305031530.639507.png 1305031530.656445 depth/1305031530.656445.png +1305031530.675401 rgb/1305031530.675401.png 1305031530.691015 depth/1305031530.691015.png +1305031530.739522 rgb/1305031530.739522.png 1305031530.723869 depth/1305031530.723869.png +1305031530.775437 rgb/1305031530.775437.png 1305031530.790818 depth/1305031530.790818.png +1305031530.807467 rgb/1305031530.807467.png 1305031530.822584 depth/1305031530.822584.png +1305031530.839463 rgb/1305031530.839463.png 1305031530.858371 depth/1305031530.858371.png +1305031530.875401 rgb/1305031530.875401.png 1305031530.890688 depth/1305031530.890688.png +1305031530.939462 rgb/1305031530.939462.png 1305031530.923878 depth/1305031530.923878.png +1305031530.975286 rgb/1305031530.975286.png 1305031530.988081 depth/1305031530.988081.png +1305031531.039689 rgb/1305031531.039689.png 1305031531.027310 depth/1305031531.027310.png +1305031531.075325 rgb/1305031531.075325.png 1305031531.091208 depth/1305031531.091208.png +1305031531.139581 rgb/1305031531.139581.png 1305031531.126140 depth/1305031531.126140.png +1305031531.175355 rgb/1305031531.175355.png 1305031531.190137 depth/1305031531.190137.png +1305031531.239619 rgb/1305031531.239619.png 1305031531.228127 depth/1305031531.228127.png +1305031531.275515 rgb/1305031531.275515.png 1305031531.290185 depth/1305031531.290185.png +1305031531.339595 rgb/1305031531.339595.png 1305031531.327763 depth/1305031531.327763.png +1305031531.375434 rgb/1305031531.375434.png 1305031531.389868 depth/1305031531.389868.png +1305031531.439644 rgb/1305031531.439644.png 1305031531.427177 depth/1305031531.427177.png +1305031531.475324 rgb/1305031531.475324.png 1305031531.459698 depth/1305031531.459698.png +1305031531.507602 rgb/1305031531.507602.png 1305031531.492107 depth/1305031531.492107.png +1305031531.539487 rgb/1305031531.539487.png 1305031531.527542 depth/1305031531.527542.png +1305031531.575392 rgb/1305031531.575392.png 1305031531.560506 depth/1305031531.560506.png +1305031531.607419 rgb/1305031531.607419.png 1305031531.592018 depth/1305031531.592018.png +1305031531.639521 rgb/1305031531.639521.png 1305031531.628037 depth/1305031531.628037.png +1305031531.675444 rgb/1305031531.675444.png 1305031531.659769 depth/1305031531.659769.png +1305031531.707498 rgb/1305031531.707498.png 1305031531.693140 depth/1305031531.693140.png +1305031531.739657 rgb/1305031531.739657.png 1305031531.727762 depth/1305031531.727762.png +1305031531.775442 rgb/1305031531.775442.png 1305031531.790528 depth/1305031531.790528.png +1305031531.839545 rgb/1305031531.839545.png 1305031531.826931 depth/1305031531.826931.png +1305031531.875426 rgb/1305031531.875426.png 1305031531.858402 depth/1305031531.858402.png +1305031531.907427 rgb/1305031531.907427.png 1305031531.893291 depth/1305031531.893291.png +1305031531.939564 rgb/1305031531.939564.png 1305031531.925080 depth/1305031531.925080.png +1305031531.975488 rgb/1305031531.975488.png 1305031531.990634 depth/1305031531.990634.png +1305031532.039675 rgb/1305031532.039675.png 1305031532.027524 depth/1305031532.027524.png +1305031532.075525 rgb/1305031532.075525.png 1305031532.059872 depth/1305031532.059872.png +1305031532.107398 rgb/1305031532.107398.png 1305031532.092096 depth/1305031532.092096.png +1305031532.139520 rgb/1305031532.139520.png 1305031532.126073 depth/1305031532.126073.png +1305031532.175563 rgb/1305031532.175563.png 1305031532.159926 depth/1305031532.159926.png +1305031532.207465 rgb/1305031532.207465.png 1305031532.195623 depth/1305031532.195623.png +1305031532.239966 rgb/1305031532.239966.png 1305031532.227800 depth/1305031532.227800.png +1305031532.275514 rgb/1305031532.275514.png 1305031532.260079 depth/1305031532.260079.png +1305031532.307481 rgb/1305031532.307481.png 1305031532.295824 depth/1305031532.295824.png +1305031532.339777 rgb/1305031532.339777.png 1305031532.327833 depth/1305031532.327833.png +1305031532.375496 rgb/1305031532.375496.png 1305031532.356687 depth/1305031532.356687.png +1305031532.407448 rgb/1305031532.407448.png 1305031532.396584 depth/1305031532.396584.png +1305031532.439533 rgb/1305031532.439533.png 1305031532.424572 depth/1305031532.424572.png +1305031532.475428 rgb/1305031532.475428.png 1305031532.461447 depth/1305031532.461447.png +1305031532.507415 rgb/1305031532.507415.png 1305031532.494758 depth/1305031532.494758.png +1305031532.539458 rgb/1305031532.539458.png 1305031532.523363 depth/1305031532.523363.png +1305031532.575435 rgb/1305031532.575435.png 1305031532.558750 depth/1305031532.558750.png +1305031532.607434 rgb/1305031532.607434.png 1305031532.594713 depth/1305031532.594713.png +1305031532.639592 rgb/1305031532.639592.png 1305031532.626577 depth/1305031532.626577.png +1305031532.707308 rgb/1305031532.707308.png 1305031532.692281 depth/1305031532.692281.png +1305031532.740052 rgb/1305031532.740052.png 1305031532.725142 depth/1305031532.725142.png +1305031532.775761 rgb/1305031532.775761.png 1305031532.756518 depth/1305031532.756518.png +1305031532.807429 rgb/1305031532.807429.png 1305031532.793593 depth/1305031532.793593.png +1305031532.839717 rgb/1305031532.839717.png 1305031532.827589 depth/1305031532.827589.png +1305031532.875476 rgb/1305031532.875476.png 1305031532.860360 depth/1305031532.860360.png +1305031532.907577 rgb/1305031532.907577.png 1305031532.894951 depth/1305031532.894951.png +1305031532.939523 rgb/1305031532.939523.png 1305031532.927108 depth/1305031532.927108.png +1305031532.975424 rgb/1305031532.975424.png 1305031532.958860 depth/1305031532.958860.png +1305031533.007402 rgb/1305031533.007402.png 1305031532.994889 depth/1305031532.994889.png +1305031533.039505 rgb/1305031533.039505.png 1305031533.027007 depth/1305031533.027007.png +1305031533.075500 rgb/1305031533.075500.png 1305031533.059895 depth/1305031533.059895.png +1305031533.107480 rgb/1305031533.107480.png 1305031533.095707 depth/1305031533.095707.png +1305031533.139514 rgb/1305031533.139514.png 1305031533.127261 depth/1305031533.127261.png +1305031533.175459 rgb/1305031533.175459.png 1305031533.158865 depth/1305031533.158865.png +1305031533.207507 rgb/1305031533.207507.png 1305031533.194665 depth/1305031533.194665.png +1305031533.239511 rgb/1305031533.239511.png 1305031533.226596 depth/1305031533.226596.png +1305031533.275405 rgb/1305031533.275405.png 1305031533.258719 depth/1305031533.258719.png +1305031533.307502 rgb/1305031533.307502.png 1305031533.294892 depth/1305031533.294892.png +1305031533.339522 rgb/1305031533.339522.png 1305031533.326747 depth/1305031533.326747.png +1305031533.375654 rgb/1305031533.375654.png 1305031533.358749 depth/1305031533.358749.png +1305031533.407483 rgb/1305031533.407483.png 1305031533.394869 depth/1305031533.394869.png +1305031533.439774 rgb/1305031533.439774.png 1305031533.428282 depth/1305031533.428282.png +1305031533.475654 rgb/1305031533.475654.png 1305031533.463804 depth/1305031533.463804.png +1305031533.507463 rgb/1305031533.507463.png 1305031533.495077 depth/1305031533.495077.png +1305031533.539640 rgb/1305031533.539640.png 1305031533.523787 depth/1305031533.523787.png +1305031533.575643 rgb/1305031533.575643.png 1305031533.563866 depth/1305031533.563866.png +1305031533.607639 rgb/1305031533.607639.png 1305031533.596729 depth/1305031533.596729.png +1305031533.639561 rgb/1305031533.639561.png 1305031533.623714 depth/1305031533.623714.png +1305031533.675446 rgb/1305031533.675446.png 1305031533.662973 depth/1305031533.662973.png +1305031533.707501 rgb/1305031533.707501.png 1305031533.695127 depth/1305031533.695127.png +1305031533.739555 rgb/1305031533.739555.png 1305031533.727956 depth/1305031533.727956.png +1305031533.775530 rgb/1305031533.775530.png 1305031533.763534 depth/1305031533.763534.png +1305031533.807707 rgb/1305031533.807707.png 1305031533.795519 depth/1305031533.795519.png +1305031533.839329 rgb/1305031533.839329.png 1305031533.827015 depth/1305031533.827015.png +1305031533.875471 rgb/1305031533.875471.png 1305031533.859819 depth/1305031533.859819.png +1305031533.907441 rgb/1305031533.907441.png 1305031533.895161 depth/1305031533.895161.png +1305031533.939530 rgb/1305031533.939530.png 1305031533.926857 depth/1305031533.926857.png +1305031533.975439 rgb/1305031533.975439.png 1305031533.961985 depth/1305031533.961985.png +1305031534.007323 rgb/1305031534.007323.png 1305031533.994392 depth/1305031533.994392.png +1305031534.039458 rgb/1305031534.039458.png 1305031534.026608 depth/1305031534.026608.png +1305031534.075484 rgb/1305031534.075484.png 1305031534.062247 depth/1305031534.062247.png +1305031534.107442 rgb/1305031534.107442.png 1305031534.094417 depth/1305031534.094417.png +1305031534.139529 rgb/1305031534.139529.png 1305031534.126412 depth/1305031534.126412.png +1305031534.175381 rgb/1305031534.175381.png 1305031534.162210 depth/1305031534.162210.png +1305031534.207436 rgb/1305031534.207436.png 1305031534.191161 depth/1305031534.191161.png +1305031534.239529 rgb/1305031534.239529.png 1305031534.225977 depth/1305031534.225977.png +1305031534.275475 rgb/1305031534.275475.png 1305031534.262752 depth/1305031534.262752.png +1305031534.307945 rgb/1305031534.307945.png 1305031534.295276 depth/1305031534.295276.png +1305031534.339859 rgb/1305031534.339859.png 1305031534.327593 depth/1305031534.327593.png +1305031534.375478 rgb/1305031534.375478.png 1305031534.362839 depth/1305031534.362839.png +1305031534.407595 rgb/1305031534.407595.png 1305031534.395128 depth/1305031534.395128.png +1305031534.439543 rgb/1305031534.439543.png 1305031534.427890 depth/1305031534.427890.png +1305031534.475605 rgb/1305031534.475605.png 1305031534.462407 depth/1305031534.462407.png +1305031534.507525 rgb/1305031534.507525.png 1305031534.494488 depth/1305031534.494488.png +1305031534.539582 rgb/1305031534.539582.png 1305031534.526222 depth/1305031534.526222.png +1305031534.575414 rgb/1305031534.575414.png 1305031534.562364 depth/1305031534.562364.png +1305031534.607494 rgb/1305031534.607494.png 1305031534.594279 depth/1305031534.594279.png +1305031534.639696 rgb/1305031534.639696.png 1305031534.627133 depth/1305031534.627133.png +1305031534.675511 rgb/1305031534.675511.png 1305031534.662781 depth/1305031534.662781.png +1305031534.707481 rgb/1305031534.707481.png 1305031534.694710 depth/1305031534.694710.png +1305031534.739665 rgb/1305031534.739665.png 1305031534.730855 depth/1305031534.730855.png +1305031534.775491 rgb/1305031534.775491.png 1305031534.763129 depth/1305031534.763129.png +1305031534.807516 rgb/1305031534.807516.png 1305031534.795824 depth/1305031534.795824.png +1305031534.839569 rgb/1305031534.839569.png 1305031534.831135 depth/1305031534.831135.png +1305031534.875499 rgb/1305031534.875499.png 1305031534.862751 depth/1305031534.862751.png +1305031534.907458 rgb/1305031534.907458.png 1305031534.894919 depth/1305031534.894919.png +1305031534.939556 rgb/1305031534.939556.png 1305031534.930974 depth/1305031534.930974.png +1305031534.975464 rgb/1305031534.975464.png 1305031534.962776 depth/1305031534.962776.png +1305031535.007643 rgb/1305031535.007643.png 1305031534.994599 depth/1305031534.994599.png +1305031535.039655 rgb/1305031535.039655.png 1305031535.030642 depth/1305031535.030642.png +1305031535.075490 rgb/1305031535.075490.png 1305031535.062210 depth/1305031535.062210.png +1305031535.107796 rgb/1305031535.107796.png 1305031535.094542 depth/1305031535.094542.png +1305031535.139465 rgb/1305031535.139465.png 1305031535.129807 depth/1305031535.129807.png +1305031535.175406 rgb/1305031535.175406.png 1305031535.158853 depth/1305031535.158853.png +1305031535.207514 rgb/1305031535.207514.png 1305031535.193991 depth/1305031535.193991.png +1305031535.239511 rgb/1305031535.239511.png 1305031535.230011 depth/1305031535.230011.png +1305031535.275537 rgb/1305031535.275537.png 1305031535.261725 depth/1305031535.261725.png +1305031535.307409 rgb/1305031535.307409.png 1305031535.295784 depth/1305031535.295784.png +1305031535.339468 rgb/1305031535.339468.png 1305031535.329773 depth/1305031535.329773.png +1305031535.375492 rgb/1305031535.375492.png 1305031535.361759 depth/1305031535.361759.png +1305031535.407712 rgb/1305031535.407712.png 1305031535.392026 depth/1305031535.392026.png +1305031535.439618 rgb/1305031535.439618.png 1305031535.431010 depth/1305031535.431010.png +1305031535.475595 rgb/1305031535.475595.png 1305031535.462732 depth/1305031535.462732.png +1305031535.507701 rgb/1305031535.507701.png 1305031535.495467 depth/1305031535.495467.png +1305031535.539515 rgb/1305031535.539515.png 1305031535.530835 depth/1305031535.530835.png +1305031535.575567 rgb/1305031535.575567.png 1305031535.562308 depth/1305031535.562308.png +1305031535.607524 rgb/1305031535.607524.png 1305031535.594713 depth/1305031535.594713.png +1305031535.639591 rgb/1305031535.639591.png 1305031535.630819 depth/1305031535.630819.png +1305031535.675500 rgb/1305031535.675500.png 1305031535.662546 depth/1305031535.662546.png +1305031535.707524 rgb/1305031535.707524.png 1305031535.694763 depth/1305031535.694763.png +1305031535.739708 rgb/1305031535.739708.png 1305031535.730877 depth/1305031535.730877.png +1305031535.775437 rgb/1305031535.775437.png 1305031535.759227 depth/1305031535.759227.png +1305031535.807496 rgb/1305031535.807496.png 1305031535.794599 depth/1305031535.794599.png +1305031535.840053 rgb/1305031535.840053.png 1305031535.831105 depth/1305031535.831105.png +1305031535.875502 rgb/1305031535.875502.png 1305031535.859528 depth/1305031535.859528.png +1305031535.907487 rgb/1305031535.907487.png 1305031535.898883 depth/1305031535.898883.png +1305031535.939747 rgb/1305031535.939747.png 1305031535.930685 depth/1305031535.930685.png +1305031535.975512 rgb/1305031535.975512.png 1305031535.959567 depth/1305031535.959567.png +1305031536.007462 rgb/1305031536.007462.png 1305031535.998988 depth/1305031535.998988.png +1305031536.039667 rgb/1305031536.039667.png 1305031536.031463 depth/1305031536.031463.png +1305031536.075538 rgb/1305031536.075538.png 1305031536.062243 depth/1305031536.062243.png +1305031536.107579 rgb/1305031536.107579.png 1305031536.099404 depth/1305031536.099404.png +1305031536.139540 rgb/1305031536.139540.png 1305031536.131440 depth/1305031536.131440.png +1305031536.175699 rgb/1305031536.175699.png 1305031536.163367 depth/1305031536.163367.png +1305031536.207474 rgb/1305031536.207474.png 1305031536.199777 depth/1305031536.199777.png +1305031536.239482 rgb/1305031536.239482.png 1305031536.231583 depth/1305031536.231583.png +1305031536.275618 rgb/1305031536.275618.png 1305031536.263219 depth/1305031536.263219.png +1305031536.307472 rgb/1305031536.307472.png 1305031536.299512 depth/1305031536.299512.png +1305031536.339530 rgb/1305031536.339530.png 1305031536.331390 depth/1305031536.331390.png +1305031536.375786 rgb/1305031536.375786.png 1305031536.363006 depth/1305031536.363006.png +1305031536.407665 rgb/1305031536.407665.png 1305031536.399605 depth/1305031536.399605.png +1305031536.439546 rgb/1305031536.439546.png 1305031536.431590 depth/1305031536.431590.png +1305031536.475492 rgb/1305031536.475492.png 1305031536.463554 depth/1305031536.463554.png +1305031536.507648 rgb/1305031536.507648.png 1305031536.499647 depth/1305031536.499647.png +1305031536.539583 rgb/1305031536.539583.png 1305031536.531617 depth/1305031536.531617.png +1305031536.575660 rgb/1305031536.575660.png 1305031536.563087 depth/1305031536.563087.png +1305031536.607624 rgb/1305031536.607624.png 1305031536.599164 depth/1305031536.599164.png +1305031536.639838 rgb/1305031536.639838.png 1305031536.631797 depth/1305031536.631797.png +1305031536.675456 rgb/1305031536.675456.png 1305031536.663533 depth/1305031536.663533.png +1305031536.707472 rgb/1305031536.707472.png 1305031536.699497 depth/1305031536.699497.png +1305031536.739722 rgb/1305031536.739722.png 1305031536.731424 depth/1305031536.731424.png +1305031536.775321 rgb/1305031536.775321.png 1305031536.761478 depth/1305031536.761478.png +1305031536.807301 rgb/1305031536.807301.png 1305031536.796242 depth/1305031536.796242.png +1305031536.839527 rgb/1305031536.839527.png 1305031536.828016 depth/1305031536.828016.png +1305031536.875419 rgb/1305031536.875419.png 1305031536.859596 depth/1305031536.859596.png +1305031536.907491 rgb/1305031536.907491.png 1305031536.895830 depth/1305031536.895830.png +1305031536.939530 rgb/1305031536.939530.png 1305031536.927579 depth/1305031536.927579.png +1305031536.975375 rgb/1305031536.975375.png 1305031536.962880 depth/1305031536.962880.png +1305031537.007412 rgb/1305031537.007412.png 1305031536.996766 depth/1305031536.996766.png +1305031537.039427 rgb/1305031537.039427.png 1305031537.028058 depth/1305031537.028058.png +1305031537.075341 rgb/1305031537.075341.png 1305031537.060447 depth/1305031537.060447.png +1305031537.107337 rgb/1305031537.107337.png 1305031537.095829 depth/1305031537.095829.png +1305031537.140656 rgb/1305031537.140656.png 1305031537.129621 depth/1305031537.129621.png +1305031537.175377 rgb/1305031537.175377.png 1305031537.167541 depth/1305031537.167541.png +1305031537.207445 rgb/1305031537.207445.png 1305031537.195643 depth/1305031537.195643.png +1305031537.239415 rgb/1305031537.239415.png 1305031537.230153 depth/1305031537.230153.png +1305031537.275504 rgb/1305031537.275504.png 1305031537.265688 depth/1305031537.265688.png +1305031537.307646 rgb/1305031537.307646.png 1305031537.298861 depth/1305031537.298861.png +1305031537.339718 rgb/1305031537.339718.png 1305031537.330994 depth/1305031537.330994.png +1305031537.375388 rgb/1305031537.375388.png 1305031537.365736 depth/1305031537.365736.png +1305031537.407396 rgb/1305031537.407396.png 1305031537.395624 depth/1305031537.395624.png +1305031537.439649 rgb/1305031537.439649.png 1305031537.429641 depth/1305031537.429641.png +1305031537.475520 rgb/1305031537.475520.png 1305031537.464312 depth/1305031537.464312.png +1305031537.507492 rgb/1305031537.507492.png 1305031537.497527 depth/1305031537.497527.png +1305031537.539497 rgb/1305031537.539497.png 1305031537.530263 depth/1305031537.530263.png +1305031537.575529 rgb/1305031537.575529.png 1305031537.564476 depth/1305031537.564476.png +1305031537.607507 rgb/1305031537.607507.png 1305031537.598276 depth/1305031537.598276.png +1305031537.643442 rgb/1305031537.643442.png 1305031537.630389 depth/1305031537.630389.png +1305031537.675306 rgb/1305031537.675306.png 1305031537.664114 depth/1305031537.664114.png +1305031537.707483 rgb/1305031537.707483.png 1305031537.695278 depth/1305031537.695278.png +1305031537.743426 rgb/1305031537.743426.png 1305031537.728342 depth/1305031537.728342.png +1305031537.775469 rgb/1305031537.775469.png 1305031537.766378 depth/1305031537.766378.png +1305031537.807576 rgb/1305031537.807576.png 1305031537.798725 depth/1305031537.798725.png +1305031537.843458 rgb/1305031537.843458.png 1305031537.830287 depth/1305031537.830287.png +1305031537.875571 rgb/1305031537.875571.png 1305031537.866662 depth/1305031537.866662.png +1305031537.907514 rgb/1305031537.907514.png 1305031537.898536 depth/1305031537.898536.png +1305031537.943469 rgb/1305031537.943469.png 1305031537.930243 depth/1305031537.930243.png +1305031537.975426 rgb/1305031537.975426.png 1305031537.966300 depth/1305031537.966300.png +1305031538.007529 rgb/1305031538.007529.png 1305031537.998327 depth/1305031537.998327.png +1305031538.043452 rgb/1305031538.043452.png 1305031538.030606 depth/1305031538.030606.png +1305031538.075565 rgb/1305031538.075565.png 1305031538.066420 depth/1305031538.066420.png +1305031538.107629 rgb/1305031538.107629.png 1305031538.099117 depth/1305031538.099117.png +1305031538.143487 rgb/1305031538.143487.png 1305031538.130778 depth/1305031538.130778.png +1305031538.175565 rgb/1305031538.175565.png 1305031538.167361 depth/1305031538.167361.png +1305031538.207697 rgb/1305031538.207697.png 1305031538.198836 depth/1305031538.198836.png +1305031538.243517 rgb/1305031538.243517.png 1305031538.231674 depth/1305031538.231674.png +1305031538.275489 rgb/1305031538.275489.png 1305031538.267245 depth/1305031538.267245.png +1305031538.307386 rgb/1305031538.307386.png 1305031538.297169 depth/1305031538.297169.png +1305031538.343413 rgb/1305031538.343413.png 1305031538.329631 depth/1305031538.329631.png +1305031538.375553 rgb/1305031538.375553.png 1305031538.366671 depth/1305031538.366671.png +1305031538.407511 rgb/1305031538.407511.png 1305031538.395653 depth/1305031538.395653.png +1305031538.443598 rgb/1305031538.443598.png 1305031538.434273 depth/1305031538.434273.png +1305031538.475570 rgb/1305031538.475570.png 1305031538.468114 depth/1305031538.468114.png +1305031538.507548 rgb/1305031538.507548.png 1305031538.498490 depth/1305031538.498490.png +1305031538.543450 rgb/1305031538.543450.png 1305031538.534659 depth/1305031538.534659.png +1305031538.575524 rgb/1305031538.575524.png 1305031538.566473 depth/1305031538.566473.png +1305031538.607517 rgb/1305031538.607517.png 1305031538.598497 depth/1305031538.598497.png +1305031538.643479 rgb/1305031538.643479.png 1305031538.634075 depth/1305031538.634075.png +1305031538.675433 rgb/1305031538.675433.png 1305031538.666052 depth/1305031538.666052.png +1305031538.707490 rgb/1305031538.707490.png 1305031538.698387 depth/1305031538.698387.png +1305031538.743572 rgb/1305031538.743572.png 1305031538.734584 depth/1305031538.734584.png +1305031538.775491 rgb/1305031538.775491.png 1305031538.766510 depth/1305031538.766510.png +1305031538.808089 rgb/1305031538.808089.png 1305031538.798755 depth/1305031538.798755.png +1305031538.843518 rgb/1305031538.843518.png 1305031538.832497 depth/1305031538.832497.png +1305031538.875656 rgb/1305031538.875656.png 1305031538.867193 depth/1305031538.867193.png +1305031538.907498 rgb/1305031538.907498.png 1305031538.899432 depth/1305031538.899432.png +1305031538.943414 rgb/1305031538.943414.png 1305031538.936017 depth/1305031538.936017.png +1305031538.975507 rgb/1305031538.975507.png 1305031538.967667 depth/1305031538.967667.png +1305031539.007520 rgb/1305031539.007520.png 1305031538.999448 depth/1305031538.999448.png +1305031539.043445 rgb/1305031539.043445.png 1305031539.034977 depth/1305031539.034977.png +1305031539.075515 rgb/1305031539.075515.png 1305031539.067603 depth/1305031539.067603.png +1305031539.107503 rgb/1305031539.107503.png 1305031539.099360 depth/1305031539.099360.png +1305031539.143607 rgb/1305031539.143607.png 1305031539.135768 depth/1305031539.135768.png +1305031539.175587 rgb/1305031539.175587.png 1305031539.167546 depth/1305031539.167546.png +1305031539.207601 rgb/1305031539.207601.png 1305031539.199492 depth/1305031539.199492.png +1305031539.243449 rgb/1305031539.243449.png 1305031539.235629 depth/1305031539.235629.png +1305031539.275652 rgb/1305031539.275652.png 1305031539.267760 depth/1305031539.267760.png +1305031539.307521 rgb/1305031539.307521.png 1305031539.299592 depth/1305031539.299592.png +1305031539.343842 rgb/1305031539.343842.png 1305031539.335706 depth/1305031539.335706.png +1305031539.375556 rgb/1305031539.375556.png 1305031539.367585 depth/1305031539.367585.png +1305031539.407846 rgb/1305031539.407846.png 1305031539.399501 depth/1305031539.399501.png +1305031539.443431 rgb/1305031539.443431.png 1305031539.435549 depth/1305031539.435549.png +1305031539.475605 rgb/1305031539.475605.png 1305031539.467525 depth/1305031539.467525.png +1305031539.507506 rgb/1305031539.507506.png 1305031539.499639 depth/1305031539.499639.png +1305031539.543459 rgb/1305031539.543459.png 1305031539.535499 depth/1305031539.535499.png +1305031539.575448 rgb/1305031539.575448.png 1305031539.567517 depth/1305031539.567517.png +1305031539.607559 rgb/1305031539.607559.png 1305031539.599060 depth/1305031539.599060.png +1305031539.643437 rgb/1305031539.643437.png 1305031539.635592 depth/1305031539.635592.png +1305031539.675458 rgb/1305031539.675458.png 1305031539.667412 depth/1305031539.667412.png +1305031539.707426 rgb/1305031539.707426.png 1305031539.703794 depth/1305031539.703794.png +1305031539.743465 rgb/1305031539.743465.png 1305031539.735675 depth/1305031539.735675.png +1305031539.775488 rgb/1305031539.775488.png 1305031539.767637 depth/1305031539.767637.png +1305031539.807653 rgb/1305031539.807653.png 1305031539.803605 depth/1305031539.803605.png +1305031539.843466 rgb/1305031539.843466.png 1305031539.832088 depth/1305031539.832088.png +1305031539.875593 rgb/1305031539.875593.png 1305031539.867127 depth/1305031539.867127.png +1305031539.907642 rgb/1305031539.907642.png 1305031539.903594 depth/1305031539.903594.png +1305031539.943541 rgb/1305031539.943541.png 1305031539.935437 depth/1305031539.935437.png +1305031539.975883 rgb/1305031539.975883.png 1305031539.967652 depth/1305031539.967652.png +1305031540.007422 rgb/1305031540.007422.png 1305031540.003691 depth/1305031540.003691.png +1305031540.043468 rgb/1305031540.043468.png 1305031540.035614 depth/1305031540.035614.png +1305031540.075632 rgb/1305031540.075632.png 1305031540.067782 depth/1305031540.067782.png +1305031540.107421 rgb/1305031540.107421.png 1305031540.103651 depth/1305031540.103651.png +1305031540.143443 rgb/1305031540.143443.png 1305031540.135787 depth/1305031540.135787.png +1305031540.175595 rgb/1305031540.175595.png 1305031540.167625 depth/1305031540.167625.png +1305031540.207411 rgb/1305031540.207411.png 1305031540.204012 depth/1305031540.204012.png +1305031540.243496 rgb/1305031540.243496.png 1305031540.235943 depth/1305031540.235943.png +1305031540.275604 rgb/1305031540.275604.png 1305031540.267794 depth/1305031540.267794.png +1305031540.307411 rgb/1305031540.307411.png 1305031540.303627 depth/1305031540.303627.png +1305031540.343456 rgb/1305031540.343456.png 1305031540.335660 depth/1305031540.335660.png +1305031540.375438 rgb/1305031540.375438.png 1305031540.367613 depth/1305031540.367613.png +1305031540.407504 rgb/1305031540.407504.png 1305031540.403545 depth/1305031540.403545.png +1305031540.443453 rgb/1305031540.443453.png 1305031540.435756 depth/1305031540.435756.png +1305031540.475476 rgb/1305031540.475476.png 1305031540.467365 depth/1305031540.467365.png +1305031540.507525 rgb/1305031540.507525.png 1305031540.502953 depth/1305031540.502953.png +1305031540.543427 rgb/1305031540.543427.png 1305031540.535194 depth/1305031540.535194.png +1305031540.575635 rgb/1305031540.575635.png 1305031540.563522 depth/1305031540.563522.png +1305031540.607508 rgb/1305031540.607508.png 1305031540.603376 depth/1305031540.603376.png +1305031540.643443 rgb/1305031540.643443.png 1305031540.635224 depth/1305031540.635224.png +1305031540.675895 rgb/1305031540.675895.png 1305031540.667294 depth/1305031540.667294.png +1305031540.707442 rgb/1305031540.707442.png 1305031540.703386 depth/1305031540.703386.png +1305031540.743545 rgb/1305031540.743545.png 1305031540.735694 depth/1305031540.735694.png +1305031540.775513 rgb/1305031540.775513.png 1305031540.767548 depth/1305031540.767548.png +1305031540.807495 rgb/1305031540.807495.png 1305031540.803232 depth/1305031540.803232.png +1305031540.843557 rgb/1305031540.843557.png 1305031540.835181 depth/1305031540.835181.png +1305031540.875472 rgb/1305031540.875472.png 1305031540.871023 depth/1305031540.871023.png +1305031540.907447 rgb/1305031540.907447.png 1305031540.903222 depth/1305031540.903222.png +1305031540.943442 rgb/1305031540.943442.png 1305031540.935050 depth/1305031540.935050.png +1305031540.975401 rgb/1305031540.975401.png 1305031540.971078 depth/1305031540.971078.png +1305031541.007473 rgb/1305031541.007473.png 1305031541.003228 depth/1305031541.003228.png +1305031541.043464 rgb/1305031541.043464.png 1305031541.034514 depth/1305031541.034514.png +1305031541.075485 rgb/1305031541.075485.png 1305031541.070217 depth/1305031541.070217.png +1305031541.107513 rgb/1305031541.107513.png 1305031541.099997 depth/1305031541.099997.png +1305031541.143507 rgb/1305031541.143507.png 1305031541.135330 depth/1305031541.135330.png +1305031541.175472 rgb/1305031541.175472.png 1305031541.171574 depth/1305031541.171574.png +1305031541.207454 rgb/1305031541.207454.png 1305031541.202996 depth/1305031541.202996.png +1305031541.243593 rgb/1305031541.243593.png 1305031541.235198 depth/1305031541.235198.png +1305031541.275691 rgb/1305031541.275691.png 1305031541.267954 depth/1305031541.267954.png +1305031541.307436 rgb/1305031541.307436.png 1305031541.301672 depth/1305031541.301672.png +1305031541.343493 rgb/1305031541.343493.png 1305031541.331852 depth/1305031541.331852.png +1305031541.375507 rgb/1305031541.375507.png 1305031541.371250 depth/1305031541.371250.png +1305031541.407707 rgb/1305031541.407707.png 1305031541.402022 depth/1305031541.402022.png +1305031541.443699 rgb/1305031541.443699.png 1305031541.431932 depth/1305031541.431932.png +1305031541.475389 rgb/1305031541.475389.png 1305031541.471366 depth/1305031541.471366.png +1305031541.507656 rgb/1305031541.507656.png 1305031541.501569 depth/1305031541.501569.png +1305031541.543489 rgb/1305031541.543489.png 1305031541.535345 depth/1305031541.535345.png +1305031541.575608 rgb/1305031541.575608.png 1305031541.569819 depth/1305031541.569819.png +1305031541.607431 rgb/1305031541.607431.png 1305031541.603472 depth/1305031541.603472.png +1305031541.643543 rgb/1305031541.643543.png 1305031541.635279 depth/1305031541.635279.png +1305031541.675424 rgb/1305031541.675424.png 1305031541.671483 depth/1305031541.671483.png +1305031541.707418 rgb/1305031541.707418.png 1305031541.703527 depth/1305031541.703527.png +1305031541.743439 rgb/1305031541.743439.png 1305031541.734963 depth/1305031541.734963.png +1305031541.775415 rgb/1305031541.775415.png 1305031541.771656 depth/1305031541.771656.png +1305031541.807470 rgb/1305031541.807470.png 1305031541.803338 depth/1305031541.803338.png +1305031541.843441 rgb/1305031541.843441.png 1305031541.835259 depth/1305031541.835259.png +1305031541.875438 rgb/1305031541.875438.png 1305031541.871359 depth/1305031541.871359.png +1305031541.907570 rgb/1305031541.907570.png 1305031541.903131 depth/1305031541.903131.png +1305031541.943524 rgb/1305031541.943524.png 1305031541.932460 depth/1305031541.932460.png +1305031541.975524 rgb/1305031541.975524.png 1305031541.969202 depth/1305031541.969202.png +1305031542.007694 rgb/1305031542.007694.png 1305031542.000034 depth/1305031542.000034.png +1305031542.043489 rgb/1305031542.043489.png 1305031542.032795 depth/1305031542.032795.png +1305031542.075555 rgb/1305031542.075555.png 1305031542.069819 depth/1305031542.069819.png +1305031542.107416 rgb/1305031542.107416.png 1305031542.102573 depth/1305031542.102573.png +1305031542.143525 rgb/1305031542.143525.png 1305031542.139294 depth/1305031542.139294.png +1305031542.175524 rgb/1305031542.175524.png 1305031542.170485 depth/1305031542.170485.png +1305031542.207368 rgb/1305031542.207368.png 1305031542.202214 depth/1305031542.202214.png +1305031542.244091 rgb/1305031542.244091.png 1305031542.237243 depth/1305031542.237243.png +1305031542.275425 rgb/1305031542.275425.png 1305031542.269752 depth/1305031542.269752.png +1305031542.307528 rgb/1305031542.307528.png 1305031542.301218 depth/1305031542.301218.png +1305031542.343479 rgb/1305031542.343479.png 1305031542.338812 depth/1305031542.338812.png +1305031542.375553 rgb/1305031542.375553.png 1305031542.371582 depth/1305031542.371582.png +1305031542.407482 rgb/1305031542.407482.png 1305031542.403140 depth/1305031542.403140.png +1305031542.443447 rgb/1305031542.443447.png 1305031542.439210 depth/1305031542.439210.png +1305031542.475446 rgb/1305031542.475446.png 1305031542.471527 depth/1305031542.471527.png +1305031542.507447 rgb/1305031542.507447.png 1305031542.503717 depth/1305031542.503717.png +1305031542.543425 rgb/1305031542.543425.png 1305031542.539439 depth/1305031542.539439.png +1305031542.575428 rgb/1305031542.575428.png 1305031542.571672 depth/1305031542.571672.png +1305031542.607410 rgb/1305031542.607410.png 1305031542.603499 depth/1305031542.603499.png +1305031542.643424 rgb/1305031542.643424.png 1305031542.639171 depth/1305031542.639171.png +1305031542.675341 rgb/1305031542.675341.png 1305031542.668866 depth/1305031542.668866.png +1305031542.707362 rgb/1305031542.707362.png 1305031542.702239 depth/1305031542.702239.png +1305031542.743855 rgb/1305031542.743855.png 1305031542.737961 depth/1305031542.737961.png +1305031542.775624 rgb/1305031542.775624.png 1305031542.771170 depth/1305031542.771170.png +1305031542.807676 rgb/1305031542.807676.png 1305031542.803270 depth/1305031542.803270.png +1305031542.843453 rgb/1305031542.843453.png 1305031542.839568 depth/1305031542.839568.png +1305031542.875473 rgb/1305031542.875473.png 1305031542.871198 depth/1305031542.871198.png +1305031542.907374 rgb/1305031542.907374.png 1305031542.903732 depth/1305031542.903732.png +1305031542.943449 rgb/1305031542.943449.png 1305031542.939215 depth/1305031542.939215.png +1305031542.975416 rgb/1305031542.975416.png 1305031542.970866 depth/1305031542.970866.png +1305031543.007462 rgb/1305031543.007462.png 1305031543.002677 depth/1305031543.002677.png +1305031543.043546 rgb/1305031543.043546.png 1305031543.039126 depth/1305031543.039126.png +1305031543.075465 rgb/1305031543.075465.png 1305031543.070710 depth/1305031543.070710.png +1305031543.107471 rgb/1305031543.107471.png 1305031543.102755 depth/1305031543.102755.png +1305031543.143424 rgb/1305031543.143424.png 1305031543.139358 depth/1305031543.139358.png +1305031543.175587 rgb/1305031543.175587.png 1305031543.170265 depth/1305031543.170265.png +1305031543.207464 rgb/1305031543.207464.png 1305031543.200190 depth/1305031543.200190.png +1305031543.243490 rgb/1305031543.243490.png 1305031543.238701 depth/1305031543.238701.png +1305031543.275504 rgb/1305031543.275504.png 1305031543.270923 depth/1305031543.270923.png +1305031543.307391 rgb/1305031543.307391.png 1305031543.302962 depth/1305031543.302962.png +1305031543.343502 rgb/1305031543.343502.png 1305031543.338824 depth/1305031543.338824.png +1305031543.375520 rgb/1305031543.375520.png 1305031543.370800 depth/1305031543.370800.png +1305031543.407575 rgb/1305031543.407575.png 1305031543.407586 depth/1305031543.407586.png +1305031543.443593 rgb/1305031543.443593.png 1305031543.436408 depth/1305031543.436408.png +1305031543.475420 rgb/1305031543.475420.png 1305031543.472193 depth/1305031543.472193.png +1305031543.507652 rgb/1305031543.507652.png 1305031543.507662 depth/1305031543.507662.png +1305031543.543433 rgb/1305031543.543433.png 1305031543.539811 depth/1305031543.539811.png +1305031543.575393 rgb/1305031543.575393.png 1305031543.572301 depth/1305031543.572301.png +1305031543.607524 rgb/1305031543.607524.png 1305031543.607686 depth/1305031543.607686.png +1305031543.643400 rgb/1305031543.643400.png 1305031543.639875 depth/1305031543.639875.png +1305031543.675460 rgb/1305031543.675460.png 1305031543.671696 depth/1305031543.671696.png +1305031543.707478 rgb/1305031543.707478.png 1305031543.707488 depth/1305031543.707488.png +1305031543.743399 rgb/1305031543.743399.png 1305031543.739759 depth/1305031543.739759.png +1305031543.775642 rgb/1305031543.775642.png 1305031543.771875 depth/1305031543.771875.png +1305031543.807514 rgb/1305031543.807514.png 1305031543.807535 depth/1305031543.807535.png +1305031543.843406 rgb/1305031543.843406.png 1305031543.839894 depth/1305031543.839894.png +1305031543.875410 rgb/1305031543.875410.png 1305031543.871869 depth/1305031543.871869.png +1305031543.907459 rgb/1305031543.907459.png 1305031543.907474 depth/1305031543.907474.png +1305031543.943413 rgb/1305031543.943413.png 1305031543.939753 depth/1305031543.939753.png +1305031543.975473 rgb/1305031543.975473.png 1305031543.970786 depth/1305031543.970786.png +1305031544.007491 rgb/1305031544.007491.png 1305031544.007529 depth/1305031544.007529.png +1305031544.043491 rgb/1305031544.043491.png 1305031544.038948 depth/1305031544.038948.png +1305031544.075509 rgb/1305031544.075509.png 1305031544.070711 depth/1305031544.070711.png +1305031544.107376 rgb/1305031544.107376.png 1305031544.106609 depth/1305031544.106609.png +1305031544.143795 rgb/1305031544.143795.png 1305031544.137311 depth/1305031544.137311.png +1305031544.175829 rgb/1305031544.175829.png 1305031544.171722 depth/1305031544.171722.png +1305031544.207354 rgb/1305031544.207354.png 1305031544.206571 depth/1305031544.206571.png +1305031544.243427 rgb/1305031544.243427.png 1305031544.238072 depth/1305031544.238072.png +1305031544.275540 rgb/1305031544.275540.png 1305031544.267766 depth/1305031544.267766.png +1305031544.307370 rgb/1305031544.307370.png 1305031544.303584 depth/1305031544.303584.png +1305031544.343409 rgb/1305031544.343409.png 1305031544.338210 depth/1305031544.338210.png +1305031544.375459 rgb/1305031544.375459.png 1305031544.367911 depth/1305031544.367911.png +1305031544.407333 rgb/1305031544.407333.png 1305031544.405875 depth/1305031544.405875.png +1305031544.443375 rgb/1305031544.443375.png 1305031544.437826 depth/1305031544.437826.png +1305031544.475427 rgb/1305031544.475427.png 1305031544.469937 depth/1305031544.469937.png +1305031544.507367 rgb/1305031544.507367.png 1305031544.505986 depth/1305031544.505986.png +1305031544.543416 rgb/1305031544.543416.png 1305031544.539003 depth/1305031544.539003.png +1305031544.575497 rgb/1305031544.575497.png 1305031544.574785 depth/1305031544.574785.png +1305031544.607409 rgb/1305031544.607409.png 1305031544.607438 depth/1305031544.607438.png +1305031544.643444 rgb/1305031544.643444.png 1305031544.638925 depth/1305031544.638925.png +1305031544.675586 rgb/1305031544.675586.png 1305031544.675602 depth/1305031544.675602.png +1305031544.707411 rgb/1305031544.707411.png 1305031544.703615 depth/1305031544.703615.png +1305031544.743438 rgb/1305031544.743438.png 1305031544.738977 depth/1305031544.738977.png +1305031544.775418 rgb/1305031544.775418.png 1305031544.775192 depth/1305031544.775192.png +1305031544.807397 rgb/1305031544.807397.png 1305031544.807101 depth/1305031544.807101.png +1305031544.843491 rgb/1305031544.843491.png 1305031544.839027 depth/1305031544.839027.png +1305031544.875360 rgb/1305031544.875360.png 1305031544.875379 depth/1305031544.875379.png +1305031544.907423 rgb/1305031544.907423.png 1305031544.907436 depth/1305031544.907436.png +1305031544.943434 rgb/1305031544.943434.png 1305031544.939009 depth/1305031544.939009.png +1305031544.975537 rgb/1305031544.975537.png 1305031544.975561 depth/1305031544.975561.png +1305031545.007393 rgb/1305031545.007393.png 1305031545.007409 depth/1305031545.007409.png +1305031545.043477 rgb/1305031545.043477.png 1305031545.039484 depth/1305031545.039484.png +1305031545.075369 rgb/1305031545.075369.png 1305031545.075213 depth/1305031545.075213.png +1305031545.107399 rgb/1305031545.107399.png 1305031545.107171 depth/1305031545.107171.png +1305031545.144171 rgb/1305031545.144171.png 1305031545.139414 depth/1305031545.139414.png +1305031545.175406 rgb/1305031545.175406.png 1305031545.174984 depth/1305031545.174984.png +1305031545.207577 rgb/1305031545.207577.png 1305031545.207672 depth/1305031545.207672.png +1305031545.243483 rgb/1305031545.243483.png 1305031545.239686 depth/1305031545.239686.png +1305031545.275369 rgb/1305031545.275369.png 1305031545.275412 depth/1305031545.275412.png +1305031545.307451 rgb/1305031545.307451.png 1305031545.306213 depth/1305031545.306213.png +1305031545.343494 rgb/1305031545.343494.png 1305031545.339544 depth/1305031545.339544.png +1305031545.375545 rgb/1305031545.375545.png 1305031545.375555 depth/1305031545.375555.png +1305031545.407452 rgb/1305031545.407452.png 1305031545.407463 depth/1305031545.407463.png +1305031545.444180 rgb/1305031545.444180.png 1305031545.439168 depth/1305031545.439168.png +1305031545.475423 rgb/1305031545.475423.png 1305031545.475453 depth/1305031545.475453.png +1305031545.507394 rgb/1305031545.507394.png 1305031545.507417 depth/1305031545.507417.png +1305031545.543418 rgb/1305031545.543418.png 1305031545.539498 depth/1305031545.539498.png +1305031545.578078 rgb/1305031545.578078.png 1305031545.578088 depth/1305031545.578088.png +1305031545.607417 rgb/1305031545.607417.png 1305031545.603778 depth/1305031545.603778.png +1305031545.643463 rgb/1305031545.643463.png 1305031545.635945 depth/1305031545.635945.png +1305031545.675289 rgb/1305031545.675289.png 1305031545.673535 depth/1305031545.673535.png +1305031545.707398 rgb/1305031545.707398.png 1305031545.706561 depth/1305031545.706561.png +1305031545.743570 rgb/1305031545.743570.png 1305031545.739007 depth/1305031545.739007.png +1305031545.775452 rgb/1305031545.775452.png 1305031545.775565 depth/1305031545.775565.png +1305031545.807404 rgb/1305031545.807404.png 1305031545.807492 depth/1305031545.807492.png +1305031545.843376 rgb/1305031545.843376.png 1305031545.843386 depth/1305031545.843386.png +1305031545.875537 rgb/1305031545.875537.png 1305031545.875515 depth/1305031545.875515.png +1305031545.907389 rgb/1305031545.907389.png 1305031545.907616 depth/1305031545.907616.png +1305031545.943457 rgb/1305031545.943457.png 1305031545.943703 depth/1305031545.943703.png +1305031545.975621 rgb/1305031545.975621.png 1305031545.975685 depth/1305031545.975685.png +1305031546.007516 rgb/1305031546.007516.png 1305031546.007570 depth/1305031546.007570.png +1305031546.043769 rgb/1305031546.043769.png 1305031546.043793 depth/1305031546.043793.png +1305031546.075414 rgb/1305031546.075414.png 1305031546.075425 depth/1305031546.075425.png +1305031546.107395 rgb/1305031546.107395.png 1305031546.104074 depth/1305031546.104074.png +1305031546.143502 rgb/1305031546.143502.png 1305031546.143517 depth/1305031546.143517.png +1305031546.175952 rgb/1305031546.175952.png 1305031546.175972 depth/1305031546.175972.png +1305031546.207500 rgb/1305031546.207500.png 1305031546.207525 depth/1305031546.207525.png +1305031546.243551 rgb/1305031546.243551.png 1305031546.243573 depth/1305031546.243573.png +1305031546.276098 rgb/1305031546.276098.png 1305031546.276113 depth/1305031546.276113.png +1305031546.308110 rgb/1305031546.308110.png 1305031546.308117 depth/1305031546.308117.png +1305031546.343919 rgb/1305031546.343919.png 1305031546.343932 depth/1305031546.343932.png +1305031546.376056 rgb/1305031546.376056.png 1305031546.376105 depth/1305031546.376105.png +1305031546.407659 rgb/1305031546.407659.png 1305031546.407683 depth/1305031546.407683.png +1305031546.443968 rgb/1305031546.443968.png 1305031546.443985 depth/1305031546.443985.png +1305031546.475996 rgb/1305031546.475996.png 1305031546.476002 depth/1305031546.476002.png +1305031546.507967 rgb/1305031546.507967.png 1305031546.507978 depth/1305031546.507978.png +1305031546.544068 rgb/1305031546.544068.png 1305031546.544091 depth/1305031546.544091.png +1305031546.576412 rgb/1305031546.576412.png 1305031546.576436 depth/1305031546.576436.png +1305031546.607717 rgb/1305031546.607717.png 1305031546.604477 depth/1305031546.604477.png +1305031546.644200 rgb/1305031546.644200.png 1305031546.644231 depth/1305031546.644231.png +1305031546.676003 rgb/1305031546.676003.png 1305031546.676019 depth/1305031546.676019.png +1305031546.707934 rgb/1305031546.707934.png 1305031546.707952 depth/1305031546.707952.png +1305031546.743887 rgb/1305031546.743887.png 1305031546.743907 depth/1305031546.743907.png +1305031546.775864 rgb/1305031546.775864.png 1305031546.775885 depth/1305031546.775885.png +1305031546.807996 rgb/1305031546.807996.png 1305031546.808019 depth/1305031546.808019.png +1305031546.844079 rgb/1305031546.844079.png 1305031546.844098 depth/1305031546.844098.png +1305031546.876064 rgb/1305031546.876064.png 1305031546.876150 depth/1305031546.876150.png +1305031546.907783 rgb/1305031546.907783.png 1305031546.904254 depth/1305031546.904254.png +1305031546.943858 rgb/1305031546.943858.png 1305031546.943871 depth/1305031546.943871.png +1305031546.975884 rgb/1305031546.975884.png 1305031546.975693 depth/1305031546.975693.png +1305031547.011984 rgb/1305031547.011984.png 1305031547.008548 depth/1305031547.008548.png +1305031547.044214 rgb/1305031547.044214.png 1305031547.044236 depth/1305031547.044236.png +1305031547.076346 rgb/1305031547.076346.png 1305031547.074033 depth/1305031547.074033.png +1305031547.111991 rgb/1305031547.111991.png 1305031547.109368 depth/1305031547.109368.png +1305031547.144071 rgb/1305031547.144071.png 1305031547.143020 depth/1305031547.143020.png +1305031547.175909 rgb/1305031547.175909.png 1305031547.172567 depth/1305031547.172567.png +1305031547.211964 rgb/1305031547.211964.png 1305031547.211605 depth/1305031547.211605.png +1305031547.244113 rgb/1305031547.244113.png 1305031547.244133 depth/1305031547.244133.png +1305031547.276546 rgb/1305031547.276546.png 1305031547.276566 depth/1305031547.276566.png +1305031547.312261 rgb/1305031547.312261.png 1305031547.312300 depth/1305031547.312300.png +1305031547.344192 rgb/1305031547.344192.png 1305031547.344201 depth/1305031547.344201.png +1305031547.376753 rgb/1305031547.376753.png 1305031547.376783 depth/1305031547.376783.png +1305031547.412260 rgb/1305031547.412260.png 1305031547.412309 depth/1305031547.412309.png +1305031547.444472 rgb/1305031547.444472.png 1305031547.444479 depth/1305031547.444479.png +1305031547.476347 rgb/1305031547.476347.png 1305031547.475653 depth/1305031547.475653.png +1305031547.512114 rgb/1305031547.512114.png 1305031547.512129 depth/1305031547.512129.png +1305031547.544015 rgb/1305031547.544015.png 1305031547.543063 depth/1305031547.543063.png +1305031547.576437 rgb/1305031547.576437.png 1305031547.572452 depth/1305031547.572452.png +1305031547.612296 rgb/1305031547.612296.png 1305031547.610069 depth/1305031547.610069.png +1305031547.644160 rgb/1305031547.644160.png 1305031547.643685 depth/1305031547.643685.png +1305031547.677287 rgb/1305031547.677287.png 1305031547.675727 depth/1305031547.675727.png +1305031547.712338 rgb/1305031547.712338.png 1305031547.712359 depth/1305031547.712359.png +1305031547.744332 rgb/1305031547.744332.png 1305031547.741819 depth/1305031547.741819.png +1305031547.776390 rgb/1305031547.776390.png 1305031547.773659 depth/1305031547.773659.png +1305031547.812317 rgb/1305031547.812317.png 1305031547.812136 depth/1305031547.812136.png +1305031547.844564 rgb/1305031547.844564.png 1305031547.844573 depth/1305031547.844573.png +1305031547.876362 rgb/1305031547.876362.png 1305031547.875313 depth/1305031547.875313.png +1305031547.912744 rgb/1305031547.912744.png 1305031547.912229 depth/1305031547.912229.png +1305031547.944304 rgb/1305031547.944304.png 1305031547.942674 depth/1305031547.942674.png +1305031547.976482 rgb/1305031547.976482.png 1305031547.976525 depth/1305031547.976525.png diff --git a/Examples/RGB-D/associations/fr1_room.txt b/Examples/RGB-D/associations/fr1_room.txt new file mode 100644 index 0000000000..beed6d1537 --- /dev/null +++ b/Examples/RGB-D/associations/fr1_room.txt @@ -0,0 +1,1352 @@ +1305031910.765238 rgb/1305031910.765238.png 1305031910.771502 depth/1305031910.771502.png +1305031910.797230 rgb/1305031910.797230.png 1305031910.803249 depth/1305031910.803249.png +1305031910.835208 rgb/1305031910.835208.png 1305031910.835215 depth/1305031910.835215.png +1305031910.865025 rgb/1305031910.865025.png 1305031910.871167 depth/1305031910.871167.png +1305031910.897222 rgb/1305031910.897222.png 1305031910.903682 depth/1305031910.903682.png +1305031910.935211 rgb/1305031910.935211.png 1305031910.935221 depth/1305031910.935221.png +1305031910.965249 rgb/1305031910.965249.png 1305031910.971338 depth/1305031910.971338.png +1305031910.997325 rgb/1305031910.997325.png 1305031911.003202 depth/1305031911.003202.png +1305031911.035050 rgb/1305031911.035050.png 1305031911.035056 depth/1305031911.035056.png +1305031911.065269 rgb/1305031911.065269.png 1305031911.074509 depth/1305031911.074509.png +1305031911.097196 rgb/1305031911.097196.png 1305031911.103332 depth/1305031911.103332.png +1305031911.135664 rgb/1305031911.135664.png 1305031911.135683 depth/1305031911.135683.png +1305031911.165177 rgb/1305031911.165177.png 1305031911.171831 depth/1305031911.171831.png +1305031911.197213 rgb/1305031911.197213.png 1305031911.207568 depth/1305031911.207568.png +1305031911.235651 rgb/1305031911.235651.png 1305031911.235660 depth/1305031911.235660.png +1305031911.265104 rgb/1305031911.265104.png 1305031911.268497 depth/1305031911.268497.png +1305031911.297334 rgb/1305031911.297334.png 1305031911.303504 depth/1305031911.303504.png +1305031911.333191 rgb/1305031911.333191.png 1305031911.339412 depth/1305031911.339412.png +1305031911.365235 rgb/1305031911.365235.png 1305031911.371631 depth/1305031911.371631.png +1305031911.397333 rgb/1305031911.397333.png 1305031911.403484 depth/1305031911.403484.png +1305031911.433256 rgb/1305031911.433256.png 1305031911.439656 depth/1305031911.439656.png +1305031911.465250 rgb/1305031911.465250.png 1305031911.471398 depth/1305031911.471398.png +1305031911.497291 rgb/1305031911.497291.png 1305031911.503476 depth/1305031911.503476.png +1305031911.533251 rgb/1305031911.533251.png 1305031911.539636 depth/1305031911.539636.png +1305031911.565335 rgb/1305031911.565335.png 1305031911.571543 depth/1305031911.571543.png +1305031911.597302 rgb/1305031911.597302.png 1305031911.603617 depth/1305031911.603617.png +1305031911.633337 rgb/1305031911.633337.png 1305031911.639562 depth/1305031911.639562.png +1305031911.665124 rgb/1305031911.665124.png 1305031911.671469 depth/1305031911.671469.png +1305031911.697167 rgb/1305031911.697167.png 1305031911.705153 depth/1305031911.705153.png +1305031911.733203 rgb/1305031911.733203.png 1305031911.739460 depth/1305031911.739460.png +1305031911.765284 rgb/1305031911.765284.png 1305031911.771372 depth/1305031911.771372.png +1305031911.797297 rgb/1305031911.797297.png 1305031911.803540 depth/1305031911.803540.png +1305031911.833338 rgb/1305031911.833338.png 1305031911.839611 depth/1305031911.839611.png +1305031911.865269 rgb/1305031911.865269.png 1305031911.871650 depth/1305031911.871650.png +1305031911.897159 rgb/1305031911.897159.png 1305031911.904281 depth/1305031911.904281.png +1305031911.933063 rgb/1305031911.933063.png 1305031911.940338 depth/1305031911.940338.png +1305031911.965140 rgb/1305031911.965140.png 1305031911.972044 depth/1305031911.972044.png +1305031911.997252 rgb/1305031911.997252.png 1305031912.004430 depth/1305031912.004430.png +1305031912.033135 rgb/1305031912.033135.png 1305031912.040573 depth/1305031912.040573.png +1305031912.065365 rgb/1305031912.065365.png 1305031912.069771 depth/1305031912.069771.png +1305031912.096953 rgb/1305031912.096953.png 1305031912.104327 depth/1305031912.104327.png +1305031912.133282 rgb/1305031912.133282.png 1305031912.139831 depth/1305031912.139831.png +1305031912.165138 rgb/1305031912.165138.png 1305031912.171439 depth/1305031912.171439.png +1305031912.197357 rgb/1305031912.197357.png 1305031912.204109 depth/1305031912.204109.png +1305031912.233265 rgb/1305031912.233265.png 1305031912.239820 depth/1305031912.239820.png +1305031912.265090 rgb/1305031912.265090.png 1305031912.272101 depth/1305031912.272101.png +1305031912.297250 rgb/1305031912.297250.png 1305031912.303877 depth/1305031912.303877.png +1305031912.333274 rgb/1305031912.333274.png 1305031912.340453 depth/1305031912.340453.png +1305031912.365250 rgb/1305031912.365250.png 1305031912.371540 depth/1305031912.371540.png +1305031912.397198 rgb/1305031912.397198.png 1305031912.403793 depth/1305031912.403793.png +1305031912.433290 rgb/1305031912.433290.png 1305031912.438048 depth/1305031912.438048.png +1305031912.465142 rgb/1305031912.465142.png 1305031912.472320 depth/1305031912.472320.png +1305031912.497123 rgb/1305031912.497123.png 1305031912.508934 depth/1305031912.508934.png +1305031912.533113 rgb/1305031912.533113.png 1305031912.540326 depth/1305031912.540326.png +1305031912.565146 rgb/1305031912.565146.png 1305031912.572025 depth/1305031912.572025.png +1305031912.597090 rgb/1305031912.597090.png 1305031912.607722 depth/1305031912.607722.png +1305031912.633132 rgb/1305031912.633132.png 1305031912.637657 depth/1305031912.637657.png +1305031912.665220 rgb/1305031912.665220.png 1305031912.672091 depth/1305031912.672091.png +1305031912.697182 rgb/1305031912.697182.png 1305031912.708413 depth/1305031912.708413.png +1305031912.733125 rgb/1305031912.733125.png 1305031912.740310 depth/1305031912.740310.png +1305031912.765193 rgb/1305031912.765193.png 1305031912.772223 depth/1305031912.772223.png +1305031912.797155 rgb/1305031912.797155.png 1305031912.809603 depth/1305031912.809603.png +1305031912.833077 rgb/1305031912.833077.png 1305031912.840573 depth/1305031912.840573.png +1305031912.865153 rgb/1305031912.865153.png 1305031912.872087 depth/1305031912.872087.png +1305031912.897198 rgb/1305031912.897198.png 1305031912.908080 depth/1305031912.908080.png +1305031912.933115 rgb/1305031912.933115.png 1305031912.940609 depth/1305031912.940609.png +1305031912.965034 rgb/1305031912.965034.png 1305031912.972119 depth/1305031912.972119.png +1305031912.997049 rgb/1305031912.997049.png 1305031913.008923 depth/1305031913.008923.png +1305031913.033133 rgb/1305031913.033133.png 1305031913.040171 depth/1305031913.040171.png +1305031913.065209 rgb/1305031913.065209.png 1305031913.072194 depth/1305031913.072194.png +1305031913.097038 rgb/1305031913.097038.png 1305031913.108367 depth/1305031913.108367.png +1305031913.133146 rgb/1305031913.133146.png 1305031913.137597 depth/1305031913.137597.png +1305031913.165211 rgb/1305031913.165211.png 1305031913.172328 depth/1305031913.172328.png +1305031913.197113 rgb/1305031913.197113.png 1305031913.208546 depth/1305031913.208546.png +1305031913.233126 rgb/1305031913.233126.png 1305031913.240453 depth/1305031913.240453.png +1305031913.265022 rgb/1305031913.265022.png 1305031913.272069 depth/1305031913.272069.png +1305031913.297160 rgb/1305031913.297160.png 1305031913.308747 depth/1305031913.308747.png +1305031913.333122 rgb/1305031913.333122.png 1305031913.340047 depth/1305031913.340047.png +1305031913.365070 rgb/1305031913.365070.png 1305031913.372117 depth/1305031913.372117.png +1305031913.397099 rgb/1305031913.397099.png 1305031913.408181 depth/1305031913.408181.png +1305031913.433081 rgb/1305031913.433081.png 1305031913.440305 depth/1305031913.440305.png +1305031913.465231 rgb/1305031913.465231.png 1305031913.472064 depth/1305031913.472064.png +1305031913.497227 rgb/1305031913.497227.png 1305031913.508406 depth/1305031913.508406.png +1305031913.533297 rgb/1305031913.533297.png 1305031913.538696 depth/1305031913.538696.png +1305031913.565261 rgb/1305031913.565261.png 1305031913.568481 depth/1305031913.568481.png +1305031913.597139 rgb/1305031913.597139.png 1305031913.607051 depth/1305031913.607051.png +1305031913.633293 rgb/1305031913.633293.png 1305031913.637112 depth/1305031913.637112.png +1305031913.665421 rgb/1305031913.665421.png 1305031913.671418 depth/1305031913.671418.png +1305031913.697243 rgb/1305031913.697243.png 1305031913.709971 depth/1305031913.709971.png +1305031913.733097 rgb/1305031913.733097.png 1305031913.743396 depth/1305031913.743396.png +1305031913.765028 rgb/1305031913.765028.png 1305031913.778085 depth/1305031913.778085.png +1305031913.797106 rgb/1305031913.797106.png 1305031913.809508 depth/1305031913.809508.png +1305031913.833143 rgb/1305031913.833143.png 1305031913.840405 depth/1305031913.840405.png +1305031913.865063 rgb/1305031913.865063.png 1305031913.876025 depth/1305031913.876025.png +1305031913.897116 rgb/1305031913.897116.png 1305031913.908138 depth/1305031913.908138.png +1305031913.933123 rgb/1305031913.933123.png 1305031913.939898 depth/1305031913.939898.png +1305031913.965134 rgb/1305031913.965134.png 1305031913.977474 depth/1305031913.977474.png +1305031913.997116 rgb/1305031913.997116.png 1305031914.008756 depth/1305031914.008756.png +1305031914.033441 rgb/1305031914.033441.png 1305031914.042148 depth/1305031914.042148.png +1305031914.065072 rgb/1305031914.065072.png 1305031914.075482 depth/1305031914.075482.png +1305031914.097126 rgb/1305031914.097126.png 1305031914.108031 depth/1305031914.108031.png +1305031914.133245 rgb/1305031914.133245.png 1305031914.142725 depth/1305031914.142725.png +1305031914.165013 rgb/1305031914.165013.png 1305031914.177921 depth/1305031914.177921.png +1305031914.197110 rgb/1305031914.197110.png 1305031914.207783 depth/1305031914.207783.png +1305031914.233108 rgb/1305031914.233108.png 1305031914.239738 depth/1305031914.239738.png +1305031914.265074 rgb/1305031914.265074.png 1305031914.275498 depth/1305031914.275498.png +1305031914.297165 rgb/1305031914.297165.png 1305031914.307439 depth/1305031914.307439.png +1305031914.333148 rgb/1305031914.333148.png 1305031914.339813 depth/1305031914.339813.png +1305031914.365058 rgb/1305031914.365058.png 1305031914.376077 depth/1305031914.376077.png +1305031914.397215 rgb/1305031914.397215.png 1305031914.407339 depth/1305031914.407339.png +1305031914.433060 rgb/1305031914.433060.png 1305031914.439366 depth/1305031914.439366.png +1305031914.465054 rgb/1305031914.465054.png 1305031914.475929 depth/1305031914.475929.png +1305031914.497127 rgb/1305031914.497127.png 1305031914.508084 depth/1305031914.508084.png +1305031914.533107 rgb/1305031914.533107.png 1305031914.539445 depth/1305031914.539445.png +1305031914.565001 rgb/1305031914.565001.png 1305031914.575638 depth/1305031914.575638.png +1305031914.597122 rgb/1305031914.597122.png 1305031914.607525 depth/1305031914.607525.png +1305031914.633055 rgb/1305031914.633055.png 1305031914.639613 depth/1305031914.639613.png +1305031914.665019 rgb/1305031914.665019.png 1305031914.675447 depth/1305031914.675447.png +1305031914.697129 rgb/1305031914.697129.png 1305031914.707659 depth/1305031914.707659.png +1305031914.733078 rgb/1305031914.733078.png 1305031914.742851 depth/1305031914.742851.png +1305031914.764901 rgb/1305031914.764901.png 1305031914.776080 depth/1305031914.776080.png +1305031914.797119 rgb/1305031914.797119.png 1305031914.810077 depth/1305031914.810077.png +1305031914.833133 rgb/1305031914.833133.png 1305031914.839826 depth/1305031914.839826.png +1305031914.865128 rgb/1305031914.865128.png 1305031914.876190 depth/1305031914.876190.png +1305031914.897188 rgb/1305031914.897188.png 1305031914.908910 depth/1305031914.908910.png +1305031914.933099 rgb/1305031914.933099.png 1305031914.938404 depth/1305031914.938404.png +1305031914.964978 rgb/1305031914.964978.png 1305031914.975628 depth/1305031914.975628.png +1305031914.997078 rgb/1305031914.997078.png 1305031915.007678 depth/1305031915.007678.png +1305031915.033152 rgb/1305031915.033152.png 1305031915.044015 depth/1305031915.044015.png +1305031915.065009 rgb/1305031915.065009.png 1305031915.073665 depth/1305031915.073665.png +1305031915.097024 rgb/1305031915.097024.png 1305031915.105907 depth/1305031915.105907.png +1305031915.133208 rgb/1305031915.133208.png 1305031915.142313 depth/1305031915.142313.png +1305031915.165021 rgb/1305031915.165021.png 1305031915.173454 depth/1305031915.173454.png +1305031915.197108 rgb/1305031915.197108.png 1305031915.209278 depth/1305031915.209278.png +1305031915.233111 rgb/1305031915.233111.png 1305031915.244223 depth/1305031915.244223.png +1305031915.264979 rgb/1305031915.264979.png 1305031915.276431 depth/1305031915.276431.png +1305031915.297152 rgb/1305031915.297152.png 1305031915.306226 depth/1305031915.306226.png +1305031915.333207 rgb/1305031915.333207.png 1305031915.341488 depth/1305031915.341488.png +1305031915.365050 rgb/1305031915.365050.png 1305031915.373270 depth/1305031915.373270.png +1305031915.397167 rgb/1305031915.397167.png 1305031915.406736 depth/1305031915.406736.png +1305031915.432960 rgb/1305031915.432960.png 1305031915.442726 depth/1305031915.442726.png +1305031915.464920 rgb/1305031915.464920.png 1305031915.474257 depth/1305031915.474257.png +1305031915.497121 rgb/1305031915.497121.png 1305031915.506429 depth/1305031915.506429.png +1305031915.533058 rgb/1305031915.533058.png 1305031915.542700 depth/1305031915.542700.png +1305031915.564985 rgb/1305031915.564985.png 1305031915.575890 depth/1305031915.575890.png +1305031915.601161 rgb/1305031915.601161.png 1305031915.607095 depth/1305031915.607095.png +1305031915.633062 rgb/1305031915.633062.png 1305031915.644456 depth/1305031915.644456.png +1305031915.665003 rgb/1305031915.665003.png 1305031915.676911 depth/1305031915.676911.png +1305031915.701106 rgb/1305031915.701106.png 1305031915.710920 depth/1305031915.710920.png +1305031915.733046 rgb/1305031915.733046.png 1305031915.744275 depth/1305031915.744275.png +1305031915.765010 rgb/1305031915.765010.png 1305031915.776046 depth/1305031915.776046.png +1305031915.801243 rgb/1305031915.801243.png 1305031915.807068 depth/1305031915.807068.png +1305031915.833049 rgb/1305031915.833049.png 1305031915.844882 depth/1305031915.844882.png +1305031915.865069 rgb/1305031915.865069.png 1305031915.877002 depth/1305031915.877002.png +1305031915.901234 rgb/1305031915.901234.png 1305031915.907069 depth/1305031915.907069.png +1305031915.933056 rgb/1305031915.933056.png 1305031915.944991 depth/1305031915.944991.png +1305031915.965061 rgb/1305031915.965061.png 1305031915.976975 depth/1305031915.976975.png +1305031916.001234 rgb/1305031916.001234.png 1305031916.007650 depth/1305031916.007650.png +1305031916.033043 rgb/1305031916.033043.png 1305031916.044257 depth/1305031916.044257.png +1305031916.065060 rgb/1305031916.065060.png 1305031916.075852 depth/1305031916.075852.png +1305031916.101115 rgb/1305031916.101115.png 1305031916.107904 depth/1305031916.107904.png +1305031916.133093 rgb/1305031916.133093.png 1305031916.143770 depth/1305031916.143770.png +1305031916.165155 rgb/1305031916.165155.png 1305031916.175966 depth/1305031916.175966.png +1305031916.201031 rgb/1305031916.201031.png 1305031916.213438 depth/1305031916.213438.png +1305031916.233050 rgb/1305031916.233050.png 1305031916.244817 depth/1305031916.244817.png +1305031916.265060 rgb/1305031916.265060.png 1305031916.276150 depth/1305031916.276150.png +1305031916.301076 rgb/1305031916.301076.png 1305031916.312024 depth/1305031916.312024.png +1305031916.333426 rgb/1305031916.333426.png 1305031916.344853 depth/1305031916.344853.png +1305031916.365121 rgb/1305031916.365121.png 1305031916.375943 depth/1305031916.375943.png +1305031916.401006 rgb/1305031916.401006.png 1305031916.412634 depth/1305031916.412634.png +1305031916.433168 rgb/1305031916.433168.png 1305031916.445160 depth/1305031916.445160.png +1305031916.465124 rgb/1305031916.465124.png 1305031916.475799 depth/1305031916.475799.png +1305031916.501025 rgb/1305031916.501025.png 1305031916.511070 depth/1305031916.511070.png +1305031916.533266 rgb/1305031916.533266.png 1305031916.542416 depth/1305031916.542416.png +1305031916.565142 rgb/1305031916.565142.png 1305031916.574661 depth/1305031916.574661.png +1305031916.601238 rgb/1305031916.601238.png 1305031916.610788 depth/1305031916.610788.png +1305031916.633156 rgb/1305031916.633156.png 1305031916.643191 depth/1305031916.643191.png +1305031916.665139 rgb/1305031916.665139.png 1305031916.674514 depth/1305031916.674514.png +1305031916.701048 rgb/1305031916.701048.png 1305031916.711186 depth/1305031916.711186.png +1305031916.733056 rgb/1305031916.733056.png 1305031916.742388 depth/1305031916.742388.png +1305031916.765076 rgb/1305031916.765076.png 1305031916.774484 depth/1305031916.774484.png +1305031916.801088 rgb/1305031916.801088.png 1305031916.810984 depth/1305031916.810984.png +1305031916.833266 rgb/1305031916.833266.png 1305031916.842413 depth/1305031916.842413.png +1305031916.865085 rgb/1305031916.865085.png 1305031916.874597 depth/1305031916.874597.png +1305031916.901017 rgb/1305031916.901017.png 1305031916.911349 depth/1305031916.911349.png +1305031916.933088 rgb/1305031916.933088.png 1305031916.942991 depth/1305031916.942991.png +1305031916.965054 rgb/1305031916.965054.png 1305031916.975281 depth/1305031916.975281.png +1305031917.001132 rgb/1305031917.001132.png 1305031917.013257 depth/1305031917.013257.png +1305031917.033155 rgb/1305031917.033155.png 1305031917.045346 depth/1305031917.045346.png +1305031917.065136 rgb/1305031917.065136.png 1305031917.078672 depth/1305031917.078672.png +1305031917.101130 rgb/1305031917.101130.png 1305031917.112392 depth/1305031917.112392.png +1305031917.133106 rgb/1305031917.133106.png 1305031917.144721 depth/1305031917.144721.png +1305031917.165045 rgb/1305031917.165045.png 1305031917.175617 depth/1305031917.175617.png +1305031917.201175 rgb/1305031917.201175.png 1305031917.211105 depth/1305031917.211105.png +1305031917.233102 rgb/1305031917.233102.png 1305031917.242019 depth/1305031917.242019.png +1305031917.265163 rgb/1305031917.265163.png 1305031917.275690 depth/1305031917.275690.png +1305031917.301107 rgb/1305031917.301107.png 1305031917.311009 depth/1305031917.311009.png +1305031917.333229 rgb/1305031917.333229.png 1305031917.342994 depth/1305031917.342994.png +1305031917.365138 rgb/1305031917.365138.png 1305031917.375028 depth/1305031917.375028.png +1305031917.401065 rgb/1305031917.401065.png 1305031917.412516 depth/1305031917.412516.png +1305031917.433141 rgb/1305031917.433141.png 1305031917.442191 depth/1305031917.442191.png +1305031917.465076 rgb/1305031917.465076.png 1305031917.480876 depth/1305031917.480876.png +1305031917.501158 rgb/1305031917.501158.png 1305031917.512902 depth/1305031917.512902.png +1305031917.533057 rgb/1305031917.533057.png 1305031917.544881 depth/1305031917.544881.png +1305031917.565195 rgb/1305031917.565195.png 1305031917.581189 depth/1305031917.581189.png +1305031917.601069 rgb/1305031917.601069.png 1305031917.611278 depth/1305031917.611278.png +1305031917.633090 rgb/1305031917.633090.png 1305031917.644587 depth/1305031917.644587.png +1305031917.665060 rgb/1305031917.665060.png 1305031917.680182 depth/1305031917.680182.png +1305031917.701096 rgb/1305031917.701096.png 1305031917.712747 depth/1305031917.712747.png +1305031917.733003 rgb/1305031917.733003.png 1305031917.743645 depth/1305031917.743645.png +1305031917.765114 rgb/1305031917.765114.png 1305031917.776958 depth/1305031917.776958.png +1305031917.801048 rgb/1305031917.801048.png 1305031917.812348 depth/1305031917.812348.png +1305031917.833090 rgb/1305031917.833090.png 1305031917.844755 depth/1305031917.844755.png +1305031917.865107 rgb/1305031917.865107.png 1305031917.879431 depth/1305031917.879431.png +1305031917.901060 rgb/1305031917.901060.png 1305031917.907881 depth/1305031917.907881.png +1305031917.932948 rgb/1305031917.932948.png 1305031917.941261 depth/1305031917.941261.png +1305031917.965346 rgb/1305031917.965346.png 1305031917.978906 depth/1305031917.978906.png +1305031918.001098 rgb/1305031918.001098.png 1305031918.011404 depth/1305031918.011404.png +1305031918.033144 rgb/1305031918.033144.png 1305031918.044049 depth/1305031918.044049.png +1305031918.065137 rgb/1305031918.065137.png 1305031918.081372 depth/1305031918.081372.png +1305031918.101060 rgb/1305031918.101060.png 1305031918.113495 depth/1305031918.113495.png +1305031918.133054 rgb/1305031918.133054.png 1305031918.145896 depth/1305031918.145896.png +1305031918.165017 rgb/1305031918.165017.png 1305031918.179489 depth/1305031918.179489.png +1305031918.201086 rgb/1305031918.201086.png 1305031918.214208 depth/1305031918.214208.png +1305031918.233042 rgb/1305031918.233042.png 1305031918.244974 depth/1305031918.244974.png +1305031918.265256 rgb/1305031918.265256.png 1305031918.280832 depth/1305031918.280832.png +1305031918.301124 rgb/1305031918.301124.png 1305031918.312487 depth/1305031918.312487.png +1305031918.333165 rgb/1305031918.333165.png 1305031918.344896 depth/1305031918.344896.png +1305031918.365072 rgb/1305031918.365072.png 1305031918.379884 depth/1305031918.379884.png +1305031918.401030 rgb/1305031918.401030.png 1305031918.413065 depth/1305031918.413065.png +1305031918.433043 rgb/1305031918.433043.png 1305031918.445292 depth/1305031918.445292.png +1305031918.465089 rgb/1305031918.465089.png 1305031918.481811 depth/1305031918.481811.png +1305031918.501125 rgb/1305031918.501125.png 1305031918.513488 depth/1305031918.513488.png +1305031918.533134 rgb/1305031918.533134.png 1305031918.545221 depth/1305031918.545221.png +1305031918.565018 rgb/1305031918.565018.png 1305031918.582328 depth/1305031918.582328.png +1305031918.601029 rgb/1305031918.601029.png 1305031918.613230 depth/1305031918.613230.png +1305031918.633027 rgb/1305031918.633027.png 1305031918.645169 depth/1305031918.645169.png +1305031918.665112 rgb/1305031918.665112.png 1305031918.681778 depth/1305031918.681778.png +1305031918.701017 rgb/1305031918.701017.png 1305031918.713496 depth/1305031918.713496.png +1305031918.765151 rgb/1305031918.765151.png 1305031918.749734 depth/1305031918.749734.png +1305031918.801097 rgb/1305031918.801097.png 1305031918.814538 depth/1305031918.814538.png +1305031918.833123 rgb/1305031918.833123.png 1305031918.850071 depth/1305031918.850071.png +1305031918.865115 rgb/1305031918.865115.png 1305031918.880096 depth/1305031918.880096.png +1305031918.901084 rgb/1305031918.901084.png 1305031918.912498 depth/1305031918.912498.png +1305031918.933071 rgb/1305031918.933071.png 1305031918.948107 depth/1305031918.948107.png +1305031918.965058 rgb/1305031918.965058.png 1305031918.980882 depth/1305031918.980882.png +1305031919.001053 rgb/1305031919.001053.png 1305031919.013079 depth/1305031919.013079.png +1305031919.033082 rgb/1305031919.033082.png 1305031919.047888 depth/1305031919.047888.png +1305031919.065147 rgb/1305031919.065147.png 1305031919.081202 depth/1305031919.081202.png +1305031919.101028 rgb/1305031919.101028.png 1305031919.113268 depth/1305031919.113268.png +1305031919.133133 rgb/1305031919.133133.png 1305031919.149786 depth/1305031919.149786.png +1305031919.165110 rgb/1305031919.165110.png 1305031919.180150 depth/1305031919.180150.png +1305031919.201124 rgb/1305031919.201124.png 1305031919.212613 depth/1305031919.212613.png +1305031919.233093 rgb/1305031919.233093.png 1305031919.248053 depth/1305031919.248053.png +1305031919.265125 rgb/1305031919.265125.png 1305031919.282212 depth/1305031919.282212.png +1305031919.301119 rgb/1305031919.301119.png 1305031919.313576 depth/1305031919.313576.png +1305031919.333120 rgb/1305031919.333120.png 1305031919.348352 depth/1305031919.348352.png +1305031919.364948 rgb/1305031919.364948.png 1305031919.376791 depth/1305031919.376791.png +1305031919.401124 rgb/1305031919.401124.png 1305031919.413966 depth/1305031919.413966.png +1305031919.433256 rgb/1305031919.433256.png 1305031919.446851 depth/1305031919.446851.png +1305031919.465070 rgb/1305031919.465070.png 1305031919.480223 depth/1305031919.480223.png +1305031919.501049 rgb/1305031919.501049.png 1305031919.512137 depth/1305031919.512137.png +1305031919.533110 rgb/1305031919.533110.png 1305031919.548061 depth/1305031919.548061.png +1305031919.565165 rgb/1305031919.565165.png 1305031919.580925 depth/1305031919.580925.png +1305031919.601094 rgb/1305031919.601094.png 1305031919.611928 depth/1305031919.611928.png +1305031919.633127 rgb/1305031919.633127.png 1305031919.649872 depth/1305031919.649872.png +1305031919.665042 rgb/1305031919.665042.png 1305031919.680144 depth/1305031919.680144.png +1305031919.701092 rgb/1305031919.701092.png 1305031919.711961 depth/1305031919.711961.png +1305031919.733117 rgb/1305031919.733117.png 1305031919.747809 depth/1305031919.747809.png +1305031919.765060 rgb/1305031919.765060.png 1305031919.779527 depth/1305031919.779527.png +1305031919.801129 rgb/1305031919.801129.png 1305031919.815366 depth/1305031919.815366.png +1305031919.833072 rgb/1305031919.833072.png 1305031919.849456 depth/1305031919.849456.png +1305031919.865180 rgb/1305031919.865180.png 1305031919.880464 depth/1305031919.880464.png +1305031919.901067 rgb/1305031919.901067.png 1305031919.917226 depth/1305031919.917226.png +1305031919.933102 rgb/1305031919.933102.png 1305031919.948072 depth/1305031919.948072.png +1305031919.965129 rgb/1305031919.965129.png 1305031919.981539 depth/1305031919.981539.png +1305031920.001054 rgb/1305031920.001054.png 1305031920.017137 depth/1305031920.017137.png +1305031920.033118 rgb/1305031920.033118.png 1305031920.048127 depth/1305031920.048127.png +1305031920.065136 rgb/1305031920.065136.png 1305031920.081263 depth/1305031920.081263.png +1305031920.101055 rgb/1305031920.101055.png 1305031920.116134 depth/1305031920.116134.png +1305031920.132987 rgb/1305031920.132987.png 1305031920.148679 depth/1305031920.148679.png +1305031920.165140 rgb/1305031920.165140.png 1305031920.180544 depth/1305031920.180544.png +1305031920.201166 rgb/1305031920.201166.png 1305031920.217426 depth/1305031920.217426.png +1305031920.233083 rgb/1305031920.233083.png 1305031920.248168 depth/1305031920.248168.png +1305031920.265120 rgb/1305031920.265120.png 1305031920.280534 depth/1305031920.280534.png +1305031920.301096 rgb/1305031920.301096.png 1305031920.316524 depth/1305031920.316524.png +1305031920.333124 rgb/1305031920.333124.png 1305031920.349842 depth/1305031920.349842.png +1305031920.365130 rgb/1305031920.365130.png 1305031920.380357 depth/1305031920.380357.png +1305031920.401115 rgb/1305031920.401115.png 1305031920.417274 depth/1305031920.417274.png +1305031920.433123 rgb/1305031920.433123.png 1305031920.448025 depth/1305031920.448025.png +1305031920.465148 rgb/1305031920.465148.png 1305031920.481785 depth/1305031920.481785.png +1305031920.501107 rgb/1305031920.501107.png 1305031920.517298 depth/1305031920.517298.png +1305031920.533105 rgb/1305031920.533105.png 1305031920.547964 depth/1305031920.547964.png +1305031920.565153 rgb/1305031920.565153.png 1305031920.581456 depth/1305031920.581456.png +1305031920.633105 rgb/1305031920.633105.png 1305031920.617995 depth/1305031920.617995.png +1305031920.665129 rgb/1305031920.665129.png 1305031920.680130 depth/1305031920.680130.png +1305031920.701147 rgb/1305031920.701147.png 1305031920.717318 depth/1305031920.717318.png +1305031920.733091 rgb/1305031920.733091.png 1305031920.747997 depth/1305031920.747997.png +1305031920.765152 rgb/1305031920.765152.png 1305031920.780346 depth/1305031920.780346.png +1305031920.801031 rgb/1305031920.801031.png 1305031920.813643 depth/1305031920.813643.png +1305031920.833132 rgb/1305031920.833132.png 1305031920.848339 depth/1305031920.848339.png +1305031920.865163 rgb/1305031920.865163.png 1305031920.879246 depth/1305031920.879246.png +1305031920.901037 rgb/1305031920.901037.png 1305031920.915238 depth/1305031920.915238.png +1305031920.933077 rgb/1305031920.933077.png 1305031920.947777 depth/1305031920.947777.png +1305031920.965217 rgb/1305031920.965217.png 1305031920.981269 depth/1305031920.981269.png +1305031921.001108 rgb/1305031921.001108.png 1305031921.015897 depth/1305031921.015897.png +1305031921.033111 rgb/1305031921.033111.png 1305031921.046752 depth/1305031921.046752.png +1305031921.065147 rgb/1305031921.065147.png 1305031921.081623 depth/1305031921.081623.png +1305031921.101105 rgb/1305031921.101105.png 1305031921.116426 depth/1305031921.116426.png +1305031921.133159 rgb/1305031921.133159.png 1305031921.147542 depth/1305031921.147542.png +1305031921.165116 rgb/1305031921.165116.png 1305031921.183591 depth/1305031921.183591.png +1305031921.201159 rgb/1305031921.201159.png 1305031921.216248 depth/1305031921.216248.png +1305031921.233189 rgb/1305031921.233189.png 1305031921.247511 depth/1305031921.247511.png +1305031921.265164 rgb/1305031921.265164.png 1305031921.283682 depth/1305031921.283682.png +1305031921.301188 rgb/1305031921.301188.png 1305031921.316687 depth/1305031921.316687.png +1305031921.333158 rgb/1305031921.333158.png 1305031921.348715 depth/1305031921.348715.png +1305031921.365112 rgb/1305031921.365112.png 1305031921.383334 depth/1305031921.383334.png +1305031921.401108 rgb/1305031921.401108.png 1305031921.417533 depth/1305031921.417533.png +1305031921.433143 rgb/1305031921.433143.png 1305031921.447829 depth/1305031921.447829.png +1305031921.465014 rgb/1305031921.465014.png 1305031921.483449 depth/1305031921.483449.png +1305031921.501096 rgb/1305031921.501096.png 1305031921.516337 depth/1305031921.516337.png +1305031921.533099 rgb/1305031921.533099.png 1305031921.547693 depth/1305031921.547693.png +1305031921.565119 rgb/1305031921.565119.png 1305031921.584755 depth/1305031921.584755.png +1305031921.601114 rgb/1305031921.601114.png 1305031921.616860 depth/1305031921.616860.png +1305031921.633107 rgb/1305031921.633107.png 1305031921.648077 depth/1305031921.648077.png +1305031921.701068 rgb/1305031921.701068.png 1305031921.684108 depth/1305031921.684108.png +1305031921.733068 rgb/1305031921.733068.png 1305031921.717161 depth/1305031921.717161.png +1305031921.765060 rgb/1305031921.765060.png 1305031921.749472 depth/1305031921.749472.png +1305031921.801034 rgb/1305031921.801034.png 1305031921.815490 depth/1305031921.815490.png +1305031921.833122 rgb/1305031921.833122.png 1305031921.847815 depth/1305031921.847815.png +1305031921.865148 rgb/1305031921.865148.png 1305031921.883647 depth/1305031921.883647.png +1305031921.901117 rgb/1305031921.901117.png 1305031921.915912 depth/1305031921.915912.png +1305031921.933132 rgb/1305031921.933132.png 1305031921.947748 depth/1305031921.947748.png +1305031921.965107 rgb/1305031921.965107.png 1305031921.983963 depth/1305031921.983963.png +1305031922.001101 rgb/1305031922.001101.png 1305031922.017509 depth/1305031922.017509.png +1305031922.033170 rgb/1305031922.033170.png 1305031922.048087 depth/1305031922.048087.png +1305031922.101032 rgb/1305031922.101032.png 1305031922.084015 depth/1305031922.084015.png +1305031922.133245 rgb/1305031922.133245.png 1305031922.117449 depth/1305031922.117449.png +1305031922.165062 rgb/1305031922.165062.png 1305031922.150410 depth/1305031922.150410.png +1305031922.201057 rgb/1305031922.201057.png 1305031922.217879 depth/1305031922.217879.png +1305031922.233248 rgb/1305031922.233248.png 1305031922.248353 depth/1305031922.248353.png +1305031922.265183 rgb/1305031922.265183.png 1305031922.284278 depth/1305031922.284278.png +1305031922.301137 rgb/1305031922.301137.png 1305031922.315988 depth/1305031922.315988.png +1305031922.333215 rgb/1305031922.333215.png 1305031922.348617 depth/1305031922.348617.png +1305031922.365143 rgb/1305031922.365143.png 1305031922.384534 depth/1305031922.384534.png +1305031922.401139 rgb/1305031922.401139.png 1305031922.414362 depth/1305031922.414362.png +1305031922.465219 rgb/1305031922.465219.png 1305031922.449565 depth/1305031922.449565.png +1305031922.501312 rgb/1305031922.501312.png 1305031922.483598 depth/1305031922.483598.png +1305031922.533139 rgb/1305031922.533139.png 1305031922.517313 depth/1305031922.517313.png +1305031922.565031 rgb/1305031922.565031.png 1305031922.551135 depth/1305031922.551135.png +1305031922.601111 rgb/1305031922.601111.png 1305031922.616826 depth/1305031922.616826.png +1305031922.665318 rgb/1305031922.665318.png 1305031922.651650 depth/1305031922.651650.png +1305031922.701355 rgb/1305031922.701355.png 1305031922.684543 depth/1305031922.684543.png +1305031922.733235 rgb/1305031922.733235.png 1305031922.718051 depth/1305031922.718051.png +1305031922.765373 rgb/1305031922.765373.png 1305031922.752032 depth/1305031922.752032.png +1305031922.801220 rgb/1305031922.801220.png 1305031922.784245 depth/1305031922.784245.png +1305031922.833262 rgb/1305031922.833262.png 1305031922.818079 depth/1305031922.818079.png +1305031922.865045 rgb/1305031922.865045.png 1305031922.851561 depth/1305031922.851561.png +1305031922.901109 rgb/1305031922.901109.png 1305031922.916045 depth/1305031922.916045.png +1305031922.965220 rgb/1305031922.965220.png 1305031922.951632 depth/1305031922.951632.png +1305031923.001054 rgb/1305031923.001054.png 1305031923.016127 depth/1305031923.016127.png +1305031923.065085 rgb/1305031923.065085.png 1305031923.051643 depth/1305031923.051643.png +1305031923.101056 rgb/1305031923.101056.png 1305031923.083189 depth/1305031923.083189.png +1305031923.133238 rgb/1305031923.133238.png 1305031923.117556 depth/1305031923.117556.png +1305031923.165168 rgb/1305031923.165168.png 1305031923.152033 depth/1305031923.152033.png +1305031923.201181 rgb/1305031923.201181.png 1305031923.215945 depth/1305031923.215945.png +1305031923.265159 rgb/1305031923.265159.png 1305031923.251678 depth/1305031923.251678.png +1305031923.301183 rgb/1305031923.301183.png 1305031923.283836 depth/1305031923.283836.png +1305031923.333169 rgb/1305031923.333169.png 1305031923.317750 depth/1305031923.317750.png +1305031923.365230 rgb/1305031923.365230.png 1305031923.351741 depth/1305031923.351741.png +1305031923.401139 rgb/1305031923.401139.png 1305031923.384405 depth/1305031923.384405.png +1305031923.433112 rgb/1305031923.433112.png 1305031923.417551 depth/1305031923.417551.png +1305031923.465290 rgb/1305031923.465290.png 1305031923.452014 depth/1305031923.452014.png +1305031923.501145 rgb/1305031923.501145.png 1305031923.483984 depth/1305031923.483984.png +1305031923.533199 rgb/1305031923.533199.png 1305031923.517826 depth/1305031923.517826.png +1305031923.565198 rgb/1305031923.565198.png 1305031923.551611 depth/1305031923.551611.png +1305031923.601069 rgb/1305031923.601069.png 1305031923.584004 depth/1305031923.584004.png +1305031923.633244 rgb/1305031923.633244.png 1305031923.617213 depth/1305031923.617213.png +1305031923.665141 rgb/1305031923.665141.png 1305031923.651604 depth/1305031923.651604.png +1305031923.701144 rgb/1305031923.701144.png 1305031923.683339 depth/1305031923.683339.png +1305031923.733145 rgb/1305031923.733145.png 1305031923.719218 depth/1305031923.719218.png +1305031923.765175 rgb/1305031923.765175.png 1305031923.751229 depth/1305031923.751229.png +1305031923.801150 rgb/1305031923.801150.png 1305031923.784138 depth/1305031923.784138.png +1305031923.833045 rgb/1305031923.833045.png 1305031923.819707 depth/1305031923.819707.png +1305031923.865161 rgb/1305031923.865161.png 1305031923.848797 depth/1305031923.848797.png +1305031923.901121 rgb/1305031923.901121.png 1305031923.883914 depth/1305031923.883914.png +1305031923.933140 rgb/1305031923.933140.png 1305031923.919849 depth/1305031923.919849.png +1305031923.965198 rgb/1305031923.965198.png 1305031923.952341 depth/1305031923.952341.png +1305031924.001096 rgb/1305031924.001096.png 1305031923.985402 depth/1305031923.985402.png +1305031924.033250 rgb/1305031924.033250.png 1305031924.020347 depth/1305031924.020347.png +1305031924.065224 rgb/1305031924.065224.png 1305031924.052305 depth/1305031924.052305.png +1305031924.101175 rgb/1305031924.101175.png 1305031924.084935 depth/1305031924.084935.png +1305031924.133285 rgb/1305031924.133285.png 1305031924.120309 depth/1305031924.120309.png +1305031924.165591 rgb/1305031924.165591.png 1305031924.149942 depth/1305031924.149942.png +1305031924.201130 rgb/1305031924.201130.png 1305031924.183240 depth/1305031924.183240.png +1305031924.233238 rgb/1305031924.233238.png 1305031924.221139 depth/1305031924.221139.png +1305031924.265335 rgb/1305031924.265335.png 1305031924.251933 depth/1305031924.251933.png +1305031924.301099 rgb/1305031924.301099.png 1305031924.284047 depth/1305031924.284047.png +1305031924.333113 rgb/1305031924.333113.png 1305031924.319056 depth/1305031924.319056.png +1305031924.365169 rgb/1305031924.365169.png 1305031924.351287 depth/1305031924.351287.png +1305031924.401095 rgb/1305031924.401095.png 1305031924.383380 depth/1305031924.383380.png +1305031924.433069 rgb/1305031924.433069.png 1305031924.419225 depth/1305031924.419225.png +1305031924.465394 rgb/1305031924.465394.png 1305031924.452792 depth/1305031924.452792.png +1305031924.501116 rgb/1305031924.501116.png 1305031924.483315 depth/1305031924.483315.png +1305031924.533245 rgb/1305031924.533245.png 1305031924.519657 depth/1305031924.519657.png +1305031924.565264 rgb/1305031924.565264.png 1305031924.552273 depth/1305031924.552273.png +1305031924.601161 rgb/1305031924.601161.png 1305031924.584109 depth/1305031924.584109.png +1305031924.633221 rgb/1305031924.633221.png 1305031924.620515 depth/1305031924.620515.png +1305031924.665187 rgb/1305031924.665187.png 1305031924.652060 depth/1305031924.652060.png +1305031924.701168 rgb/1305031924.701168.png 1305031924.684319 depth/1305031924.684319.png +1305031924.733166 rgb/1305031924.733166.png 1305031924.719995 depth/1305031924.719995.png +1305031924.765170 rgb/1305031924.765170.png 1305031924.751699 depth/1305031924.751699.png +1305031924.801057 rgb/1305031924.801057.png 1305031924.783411 depth/1305031924.783411.png +1305031924.833187 rgb/1305031924.833187.png 1305031924.819277 depth/1305031924.819277.png +1305031924.865165 rgb/1305031924.865165.png 1305031924.851149 depth/1305031924.851149.png +1305031924.901110 rgb/1305031924.901110.png 1305031924.887231 depth/1305031924.887231.png +1305031924.933186 rgb/1305031924.933186.png 1305031924.919219 depth/1305031924.919219.png +1305031924.969060 rgb/1305031924.969060.png 1305031924.951326 depth/1305031924.951326.png +1305031925.001103 rgb/1305031925.001103.png 1305031924.987062 depth/1305031924.987062.png +1305031925.033148 rgb/1305031925.033148.png 1305031925.019418 depth/1305031925.019418.png +1305031925.069090 rgb/1305031925.069090.png 1305031925.051227 depth/1305031925.051227.png +1305031925.101107 rgb/1305031925.101107.png 1305031925.086881 depth/1305031925.086881.png +1305031925.133209 rgb/1305031925.133209.png 1305031925.119070 depth/1305031925.119070.png +1305031925.169080 rgb/1305031925.169080.png 1305031925.150861 depth/1305031925.150861.png +1305031925.201117 rgb/1305031925.201117.png 1305031925.186995 depth/1305031925.186995.png +1305031925.233193 rgb/1305031925.233193.png 1305031925.219143 depth/1305031925.219143.png +1305031925.269164 rgb/1305031925.269164.png 1305031925.250215 depth/1305031925.250215.png +1305031925.301283 rgb/1305031925.301283.png 1305031925.287610 depth/1305031925.287610.png +1305031925.333142 rgb/1305031925.333142.png 1305031925.318360 depth/1305031925.318360.png +1305031925.369107 rgb/1305031925.369107.png 1305031925.351623 depth/1305031925.351623.png +1305031925.401456 rgb/1305031925.401456.png 1305031925.386446 depth/1305031925.386446.png +1305031925.433406 rgb/1305031925.433406.png 1305031925.420497 depth/1305031925.420497.png +1305031925.469099 rgb/1305031925.469099.png 1305031925.451669 depth/1305031925.451669.png +1305031925.501267 rgb/1305031925.501267.png 1305031925.487976 depth/1305031925.487976.png +1305031925.533321 rgb/1305031925.533321.png 1305031925.520197 depth/1305031925.520197.png +1305031925.569132 rgb/1305031925.569132.png 1305031925.551723 depth/1305031925.551723.png +1305031925.601218 rgb/1305031925.601218.png 1305031925.587951 depth/1305031925.587951.png +1305031925.633430 rgb/1305031925.633430.png 1305031925.620389 depth/1305031925.620389.png +1305031925.669137 rgb/1305031925.669137.png 1305031925.652177 depth/1305031925.652177.png +1305031925.701322 rgb/1305031925.701322.png 1305031925.688138 depth/1305031925.688138.png +1305031925.733167 rgb/1305031925.733167.png 1305031925.719963 depth/1305031925.719963.png +1305031925.769246 rgb/1305031925.769246.png 1305031925.752010 depth/1305031925.752010.png +1305031925.801208 rgb/1305031925.801208.png 1305031925.788128 depth/1305031925.788128.png +1305031925.833148 rgb/1305031925.833148.png 1305031925.819737 depth/1305031925.819737.png +1305031925.869197 rgb/1305031925.869197.png 1305031925.852900 depth/1305031925.852900.png +1305031925.901176 rgb/1305031925.901176.png 1305031925.887783 depth/1305031925.887783.png +1305031925.933170 rgb/1305031925.933170.png 1305031925.917070 depth/1305031925.917070.png +1305031925.969198 rgb/1305031925.969198.png 1305031925.952071 depth/1305031925.952071.png +1305031926.001186 rgb/1305031926.001186.png 1305031925.987927 depth/1305031925.987927.png +1305031926.033156 rgb/1305031926.033156.png 1305031926.019599 depth/1305031926.019599.png +1305031926.069077 rgb/1305031926.069077.png 1305031926.051425 depth/1305031926.051425.png +1305031926.101106 rgb/1305031926.101106.png 1305031926.087671 depth/1305031926.087671.png +1305031926.133181 rgb/1305031926.133181.png 1305031926.119488 depth/1305031926.119488.png +1305031926.169101 rgb/1305031926.169101.png 1305031926.155476 depth/1305031926.155476.png +1305031926.201141 rgb/1305031926.201141.png 1305031926.187287 depth/1305031926.187287.png +1305031926.233134 rgb/1305031926.233134.png 1305031926.219471 depth/1305031926.219471.png +1305031926.269135 rgb/1305031926.269135.png 1305031926.255515 depth/1305031926.255515.png +1305031926.301054 rgb/1305031926.301054.png 1305031926.287524 depth/1305031926.287524.png +1305031926.333164 rgb/1305031926.333164.png 1305031926.319314 depth/1305031926.319314.png +1305031926.369064 rgb/1305031926.369064.png 1305031926.355226 depth/1305031926.355226.png +1305031926.401166 rgb/1305031926.401166.png 1305031926.387186 depth/1305031926.387186.png +1305031926.433155 rgb/1305031926.433155.png 1305031926.416195 depth/1305031926.416195.png +1305031926.469090 rgb/1305031926.469090.png 1305031926.456138 depth/1305031926.456138.png +1305031926.501075 rgb/1305031926.501075.png 1305031926.487337 depth/1305031926.487337.png +1305031926.533176 rgb/1305031926.533176.png 1305031926.519488 depth/1305031926.519488.png +1305031926.569122 rgb/1305031926.569122.png 1305031926.555508 depth/1305031926.555508.png +1305031926.601166 rgb/1305031926.601166.png 1305031926.587389 depth/1305031926.587389.png +1305031926.633127 rgb/1305031926.633127.png 1305031926.617031 depth/1305031926.617031.png +1305031926.669140 rgb/1305031926.669140.png 1305031926.655592 depth/1305031926.655592.png +1305031926.701042 rgb/1305031926.701042.png 1305031926.686940 depth/1305031926.686940.png +1305031926.733207 rgb/1305031926.733207.png 1305031926.716774 depth/1305031926.716774.png +1305031926.769141 rgb/1305031926.769141.png 1305031926.754636 depth/1305031926.754636.png +1305031926.801342 rgb/1305031926.801342.png 1305031926.787267 depth/1305031926.787267.png +1305031926.833209 rgb/1305031926.833209.png 1305031926.817567 depth/1305031926.817567.png +1305031926.869333 rgb/1305031926.869333.png 1305031926.856453 depth/1305031926.856453.png +1305031926.901097 rgb/1305031926.901097.png 1305031926.885854 depth/1305031926.885854.png +1305031926.933348 rgb/1305031926.933348.png 1305031926.920915 depth/1305031926.920915.png +1305031926.969122 rgb/1305031926.969122.png 1305031926.956342 depth/1305031926.956342.png +1305031927.001575 rgb/1305031927.001575.png 1305031926.988250 depth/1305031926.988250.png +1305031927.033929 rgb/1305031927.033929.png 1305031927.021193 depth/1305031927.021193.png +1305031927.070528 rgb/1305031927.070528.png 1305031927.056355 depth/1305031927.056355.png +1305031927.101272 rgb/1305031927.101272.png 1305031927.088782 depth/1305031927.088782.png +1305031927.133471 rgb/1305031927.133471.png 1305031927.120454 depth/1305031927.120454.png +1305031927.169161 rgb/1305031927.169161.png 1305031927.156388 depth/1305031927.156388.png +1305031927.201210 rgb/1305031927.201210.png 1305031927.188222 depth/1305031927.188222.png +1305031927.233491 rgb/1305031927.233491.png 1305031927.220398 depth/1305031927.220398.png +1305031927.269153 rgb/1305031927.269153.png 1305031927.255554 depth/1305031927.255554.png +1305031927.301135 rgb/1305031927.301135.png 1305031927.288179 depth/1305031927.288179.png +1305031927.333139 rgb/1305031927.333139.png 1305031927.319728 depth/1305031927.319728.png +1305031927.369147 rgb/1305031927.369147.png 1305031927.355704 depth/1305031927.355704.png +1305031927.401161 rgb/1305031927.401161.png 1305031927.387697 depth/1305031927.387697.png +1305031927.433274 rgb/1305031927.433274.png 1305031927.423646 depth/1305031927.423646.png +1305031927.469105 rgb/1305031927.469105.png 1305031927.455842 depth/1305031927.455842.png +1305031927.501136 rgb/1305031927.501136.png 1305031927.487526 depth/1305031927.487526.png +1305031927.533182 rgb/1305031927.533182.png 1305031927.523735 depth/1305031927.523735.png +1305031927.569225 rgb/1305031927.569225.png 1305031927.555610 depth/1305031927.555610.png +1305031927.601132 rgb/1305031927.601132.png 1305031927.587778 depth/1305031927.587778.png +1305031927.633201 rgb/1305031927.633201.png 1305031927.623566 depth/1305031927.623566.png +1305031927.669158 rgb/1305031927.669158.png 1305031927.655615 depth/1305031927.655615.png +1305031927.701131 rgb/1305031927.701131.png 1305031927.687849 depth/1305031927.687849.png +1305031927.733219 rgb/1305031927.733219.png 1305031927.720304 depth/1305031927.720304.png +1305031927.769158 rgb/1305031927.769158.png 1305031927.755615 depth/1305031927.755615.png +1305031927.801109 rgb/1305031927.801109.png 1305031927.784053 depth/1305031927.784053.png +1305031927.833282 rgb/1305031927.833282.png 1305031927.825135 depth/1305031927.825135.png +1305031927.869143 rgb/1305031927.869143.png 1305031927.855551 depth/1305031927.855551.png +1305031927.901130 rgb/1305031927.901130.png 1305031927.887591 depth/1305031927.887591.png +1305031927.933465 rgb/1305031927.933465.png 1305031927.923620 depth/1305031927.923620.png +1305031927.969176 rgb/1305031927.969176.png 1305031927.955459 depth/1305031927.955459.png +1305031928.001134 rgb/1305031928.001134.png 1305031927.987655 depth/1305031927.987655.png +1305031928.033186 rgb/1305031928.033186.png 1305031928.023669 depth/1305031928.023669.png +1305031928.069125 rgb/1305031928.069125.png 1305031928.055649 depth/1305031928.055649.png +1305031928.101114 rgb/1305031928.101114.png 1305031928.087657 depth/1305031928.087657.png +1305031928.133202 rgb/1305031928.133202.png 1305031928.123611 depth/1305031928.123611.png +1305031928.169018 rgb/1305031928.169018.png 1305031928.153645 depth/1305031928.153645.png +1305031928.201096 rgb/1305031928.201096.png 1305031928.185349 depth/1305031928.185349.png +1305031928.233133 rgb/1305031928.233133.png 1305031928.223567 depth/1305031928.223567.png +1305031928.269216 rgb/1305031928.269216.png 1305031928.256019 depth/1305031928.256019.png +1305031928.301255 rgb/1305031928.301255.png 1305031928.287847 depth/1305031928.287847.png +1305031928.333609 rgb/1305031928.333609.png 1305031928.324414 depth/1305031928.324414.png +1305031928.369520 rgb/1305031928.369520.png 1305031928.356445 depth/1305031928.356445.png +1305031928.401116 rgb/1305031928.401116.png 1305031928.388295 depth/1305031928.388295.png +1305031928.433543 rgb/1305031928.433543.png 1305031928.424766 depth/1305031928.424766.png +1305031928.469232 rgb/1305031928.469232.png 1305031928.456406 depth/1305031928.456406.png +1305031928.501428 rgb/1305031928.501428.png 1305031928.489516 depth/1305031928.489516.png +1305031928.533982 rgb/1305031928.533982.png 1305031928.524415 depth/1305031928.524415.png +1305031928.569299 rgb/1305031928.569299.png 1305031928.556287 depth/1305031928.556287.png +1305031928.601271 rgb/1305031928.601271.png 1305031928.588557 depth/1305031928.588557.png +1305031928.633595 rgb/1305031928.633595.png 1305031928.624251 depth/1305031928.624251.png +1305031928.669146 rgb/1305031928.669146.png 1305031928.656233 depth/1305031928.656233.png +1305031928.701110 rgb/1305031928.701110.png 1305031928.691555 depth/1305031928.691555.png +1305031928.733185 rgb/1305031928.733185.png 1305031928.723927 depth/1305031928.723927.png +1305031928.769202 rgb/1305031928.769202.png 1305031928.755499 depth/1305031928.755499.png +1305031928.801117 rgb/1305031928.801117.png 1305031928.791463 depth/1305031928.791463.png +1305031928.833193 rgb/1305031928.833193.png 1305031928.823577 depth/1305031928.823577.png +1305031928.869148 rgb/1305031928.869148.png 1305031928.855468 depth/1305031928.855468.png +1305031928.901197 rgb/1305031928.901197.png 1305031928.891499 depth/1305031928.891499.png +1305031928.933215 rgb/1305031928.933215.png 1305031928.923473 depth/1305031928.923473.png +1305031928.969097 rgb/1305031928.969097.png 1305031928.955544 depth/1305031928.955544.png +1305031929.001155 rgb/1305031929.001155.png 1305031928.991477 depth/1305031928.991477.png +1305031929.033640 rgb/1305031929.033640.png 1305031929.023472 depth/1305031929.023472.png +1305031929.069089 rgb/1305031929.069089.png 1305031929.052047 depth/1305031929.052047.png +1305031929.101213 rgb/1305031929.101213.png 1305031929.091469 depth/1305031929.091469.png +1305031929.133202 rgb/1305031929.133202.png 1305031929.123397 depth/1305031929.123397.png +1305031929.169204 rgb/1305031929.169204.png 1305031929.155442 depth/1305031929.155442.png +1305031929.201163 rgb/1305031929.201163.png 1305031929.191433 depth/1305031929.191433.png +1305031929.233293 rgb/1305031929.233293.png 1305031929.224389 depth/1305031929.224389.png +1305031929.269214 rgb/1305031929.269214.png 1305031929.256040 depth/1305031929.256040.png +1305031929.301292 rgb/1305031929.301292.png 1305031929.292331 depth/1305031929.292331.png +1305031929.333529 rgb/1305031929.333529.png 1305031929.324071 depth/1305031929.324071.png +1305031929.369189 rgb/1305031929.369189.png 1305031929.356012 depth/1305031929.356012.png +1305031929.401369 rgb/1305031929.401369.png 1305031929.391503 depth/1305031929.391503.png +1305031929.433239 rgb/1305031929.433239.png 1305031929.423543 depth/1305031929.423543.png +1305031929.469219 rgb/1305031929.469219.png 1305031929.455568 depth/1305031929.455568.png +1305031929.501198 rgb/1305031929.501198.png 1305031929.491502 depth/1305031929.491502.png +1305031929.533262 rgb/1305031929.533262.png 1305031929.523520 depth/1305031929.523520.png +1305031929.569172 rgb/1305031929.569172.png 1305031929.555525 depth/1305031929.555525.png +1305031929.601101 rgb/1305031929.601101.png 1305031929.591341 depth/1305031929.591341.png +1305031929.634447 rgb/1305031929.634447.png 1305031929.627102 depth/1305031929.627102.png +1305031929.669287 rgb/1305031929.669287.png 1305031929.652934 depth/1305031929.652934.png +1305031929.701269 rgb/1305031929.701269.png 1305031929.688977 depth/1305031929.688977.png +1305031929.733617 rgb/1305031929.733617.png 1305031929.722904 depth/1305031929.722904.png +1305031929.769190 rgb/1305031929.769190.png 1305031929.755544 depth/1305031929.755544.png +1305031929.801229 rgb/1305031929.801229.png 1305031929.791661 depth/1305031929.791661.png +1305031929.833358 rgb/1305031929.833358.png 1305031929.824100 depth/1305031929.824100.png +1305031929.869242 rgb/1305031929.869242.png 1305031929.859997 depth/1305031929.859997.png +1305031929.901292 rgb/1305031929.901292.png 1305031929.892100 depth/1305031929.892100.png +1305031929.933176 rgb/1305031929.933176.png 1305031929.920589 depth/1305031929.920589.png +1305031929.969176 rgb/1305031929.969176.png 1305031929.960336 depth/1305031929.960336.png +1305031930.001350 rgb/1305031930.001350.png 1305031929.992281 depth/1305031929.992281.png +1305031930.033650 rgb/1305031930.033650.png 1305031930.024129 depth/1305031930.024129.png +1305031930.069293 rgb/1305031930.069293.png 1305031930.059766 depth/1305031930.059766.png +1305031930.101133 rgb/1305031930.101133.png 1305031930.088504 depth/1305031930.088504.png +1305031930.134163 rgb/1305031930.134163.png 1305031930.122266 depth/1305031930.122266.png +1305031930.169117 rgb/1305031930.169117.png 1305031930.159452 depth/1305031930.159452.png +1305031930.201148 rgb/1305031930.201148.png 1305031930.191333 depth/1305031930.191333.png +1305031930.233355 rgb/1305031930.233355.png 1305031930.223366 depth/1305031930.223366.png +1305031930.269064 rgb/1305031930.269064.png 1305031930.259685 depth/1305031930.259685.png +1305031930.301105 rgb/1305031930.301105.png 1305031930.291415 depth/1305031930.291415.png +1305031930.333138 rgb/1305031930.333138.png 1305031930.324425 depth/1305031930.324425.png +1305031930.369794 rgb/1305031930.369794.png 1305031930.360687 depth/1305031930.360687.png +1305031930.401077 rgb/1305031930.401077.png 1305031930.392204 depth/1305031930.392204.png +1305031930.433290 rgb/1305031930.433290.png 1305031930.424494 depth/1305031930.424494.png +1305031930.469130 rgb/1305031930.469130.png 1305031930.460645 depth/1305031930.460645.png +1305031930.501044 rgb/1305031930.501044.png 1305031930.491893 depth/1305031930.491893.png +1305031930.533067 rgb/1305031930.533067.png 1305031930.523304 depth/1305031930.523304.png +1305031930.569007 rgb/1305031930.569007.png 1305031930.559268 depth/1305031930.559268.png +1305031930.601041 rgb/1305031930.601041.png 1305031930.591038 depth/1305031930.591038.png +1305031930.633126 rgb/1305031930.633126.png 1305031930.620257 depth/1305031930.620257.png +1305031930.668925 rgb/1305031930.668925.png 1305031930.659428 depth/1305031930.659428.png +1305031930.701009 rgb/1305031930.701009.png 1305031930.691306 depth/1305031930.691306.png +1305031930.733195 rgb/1305031930.733195.png 1305031930.723254 depth/1305031930.723254.png +1305031930.769068 rgb/1305031930.769068.png 1305031930.759257 depth/1305031930.759257.png +1305031930.801055 rgb/1305031930.801055.png 1305031930.791524 depth/1305031930.791524.png +1305031930.833091 rgb/1305031930.833091.png 1305031930.823348 depth/1305031930.823348.png +1305031930.869070 rgb/1305031930.869070.png 1305031930.860005 depth/1305031930.860005.png +1305031930.900829 rgb/1305031930.900829.png 1305031930.887927 depth/1305031930.887927.png +1305031930.933330 rgb/1305031930.933330.png 1305031930.923290 depth/1305031930.923290.png +1305031930.969059 rgb/1305031930.969059.png 1305031930.959881 depth/1305031930.959881.png +1305031931.000795 rgb/1305031931.000795.png 1305031930.991760 depth/1305031930.991760.png +1305031931.033023 rgb/1305031931.033023.png 1305031931.023642 depth/1305031931.023642.png +1305031931.068905 rgb/1305031931.068905.png 1305031931.059938 depth/1305031931.059938.png +1305031931.100819 rgb/1305031931.100819.png 1305031931.091660 depth/1305031931.091660.png +1305031931.133042 rgb/1305031931.133042.png 1305031931.126327 depth/1305031931.126327.png +1305031931.168900 rgb/1305031931.168900.png 1305031931.156194 depth/1305031931.156194.png +1305031931.200696 rgb/1305031931.200696.png 1305031931.187879 depth/1305031931.187879.png +1305031931.233053 rgb/1305031931.233053.png 1305031931.226834 depth/1305031931.226834.png +1305031931.268951 rgb/1305031931.268951.png 1305031931.259538 depth/1305031931.259538.png +1305031931.300955 rgb/1305031931.300955.png 1305031931.291735 depth/1305031931.291735.png +1305031931.332991 rgb/1305031931.332991.png 1305031931.327534 depth/1305031931.327534.png +1305031931.369797 rgb/1305031931.369797.png 1305031931.359406 depth/1305031931.359406.png +1305031931.401337 rgb/1305031931.401337.png 1305031931.391729 depth/1305031931.391729.png +1305031931.432892 rgb/1305031931.432892.png 1305031931.427416 depth/1305031931.427416.png +1305031931.469079 rgb/1305031931.469079.png 1305031931.459719 depth/1305031931.459719.png +1305031931.500852 rgb/1305031931.500852.png 1305031931.491781 depth/1305031931.491781.png +1305031931.532871 rgb/1305031931.532871.png 1305031931.527311 depth/1305031931.527311.png +1305031931.569726 rgb/1305031931.569726.png 1305031931.559707 depth/1305031931.559707.png +1305031931.601199 rgb/1305031931.601199.png 1305031931.590720 depth/1305031931.590720.png +1305031931.633004 rgb/1305031931.633004.png 1305031931.627134 depth/1305031931.627134.png +1305031931.669064 rgb/1305031931.669064.png 1305031931.659798 depth/1305031931.659798.png +1305031931.701060 rgb/1305031931.701060.png 1305031931.691463 depth/1305031931.691463.png +1305031931.732985 rgb/1305031931.732985.png 1305031931.727210 depth/1305031931.727210.png +1305031931.768911 rgb/1305031931.768911.png 1305031931.759394 depth/1305031931.759394.png +1305031931.800959 rgb/1305031931.800959.png 1305031931.791463 depth/1305031931.791463.png +1305031931.832926 rgb/1305031931.832926.png 1305031931.827415 depth/1305031931.827415.png +1305031931.868988 rgb/1305031931.868988.png 1305031931.859949 depth/1305031931.859949.png +1305031931.900957 rgb/1305031931.900957.png 1305031931.891964 depth/1305031931.891964.png +1305031931.932907 rgb/1305031931.932907.png 1305031931.927455 depth/1305031931.927455.png +1305031931.968902 rgb/1305031931.968902.png 1305031931.959755 depth/1305031931.959755.png +1305031932.000829 rgb/1305031932.000829.png 1305031931.991729 depth/1305031931.991729.png +1305031932.032913 rgb/1305031932.032913.png 1305031932.026867 depth/1305031932.026867.png +1305031932.068920 rgb/1305031932.068920.png 1305031932.058924 depth/1305031932.058924.png +1305031932.101294 rgb/1305031932.101294.png 1305031932.092565 depth/1305031932.092565.png +1305031932.132895 rgb/1305031932.132895.png 1305031932.127607 depth/1305031932.127607.png +1305031932.169077 rgb/1305031932.169077.png 1305031932.159854 depth/1305031932.159854.png +1305031932.200948 rgb/1305031932.200948.png 1305031932.192165 depth/1305031932.192165.png +1305031932.232821 rgb/1305031932.232821.png 1305031932.227671 depth/1305031932.227671.png +1305031932.268818 rgb/1305031932.268818.png 1305031932.259182 depth/1305031932.259182.png +1305031932.300945 rgb/1305031932.300945.png 1305031932.291317 depth/1305031932.291317.png +1305031932.333175 rgb/1305031932.333175.png 1305031932.326984 depth/1305031932.326984.png +1305031932.368837 rgb/1305031932.368837.png 1305031932.359352 depth/1305031932.359352.png +1305031932.401680 rgb/1305031932.401680.png 1305031932.395192 depth/1305031932.395192.png +1305031932.432994 rgb/1305031932.432994.png 1305031932.427402 depth/1305031932.427402.png +1305031932.469022 rgb/1305031932.469022.png 1305031932.460162 depth/1305031932.460162.png +1305031932.500893 rgb/1305031932.500893.png 1305031932.495912 depth/1305031932.495912.png +1305031932.532959 rgb/1305031932.532959.png 1305031932.527699 depth/1305031932.527699.png +1305031932.568972 rgb/1305031932.568972.png 1305031932.556042 depth/1305031932.556042.png +1305031932.600957 rgb/1305031932.600957.png 1305031932.593841 depth/1305031932.593841.png +1305031932.632929 rgb/1305031932.632929.png 1305031932.627666 depth/1305031932.627666.png +1305031932.669236 rgb/1305031932.669236.png 1305031932.659769 depth/1305031932.659769.png +1305031932.700806 rgb/1305031932.700806.png 1305031932.695841 depth/1305031932.695841.png +1305031932.732848 rgb/1305031932.732848.png 1305031932.727524 depth/1305031932.727524.png +1305031932.768757 rgb/1305031932.768757.png 1305031932.759892 depth/1305031932.759892.png +1305031932.800821 rgb/1305031932.800821.png 1305031932.795486 depth/1305031932.795486.png +1305031932.832891 rgb/1305031932.832891.png 1305031932.827627 depth/1305031932.827627.png +1305031932.869016 rgb/1305031932.869016.png 1305031932.859777 depth/1305031932.859777.png +1305031932.901214 rgb/1305031932.901214.png 1305031932.896209 depth/1305031932.896209.png +1305031932.932932 rgb/1305031932.932932.png 1305031932.928147 depth/1305031932.928147.png +1305031932.968787 rgb/1305031932.968787.png 1305031932.959759 depth/1305031932.959759.png +1305031933.001958 rgb/1305031933.001958.png 1305031932.995065 depth/1305031932.995065.png +1305031933.033045 rgb/1305031933.033045.png 1305031933.026975 depth/1305031933.026975.png +1305031933.068879 rgb/1305031933.068879.png 1305031933.059632 depth/1305031933.059632.png +1305031933.100908 rgb/1305031933.100908.png 1305031933.095661 depth/1305031933.095661.png +1305031933.132911 rgb/1305031933.132911.png 1305031933.127608 depth/1305031933.127608.png +1305031933.169450 rgb/1305031933.169450.png 1305031933.159744 depth/1305031933.159744.png +1305031933.200949 rgb/1305031933.200949.png 1305031933.195887 depth/1305031933.195887.png +1305031933.233374 rgb/1305031933.233374.png 1305031933.227642 depth/1305031933.227642.png +1305031933.269079 rgb/1305031933.269079.png 1305031933.259844 depth/1305031933.259844.png +1305031933.300869 rgb/1305031933.300869.png 1305031933.296061 depth/1305031933.296061.png +1305031933.332881 rgb/1305031933.332881.png 1305031933.327953 depth/1305031933.327953.png +1305031933.368978 rgb/1305031933.368978.png 1305031933.359852 depth/1305031933.359852.png +1305031933.400926 rgb/1305031933.400926.png 1305031933.395603 depth/1305031933.395603.png +1305031933.432912 rgb/1305031933.432912.png 1305031933.427651 depth/1305031933.427651.png +1305031933.469486 rgb/1305031933.469486.png 1305031933.459920 depth/1305031933.459920.png +1305031933.500809 rgb/1305031933.500809.png 1305031933.495920 depth/1305031933.495920.png +1305031933.533065 rgb/1305031933.533065.png 1305031933.527835 depth/1305031933.527835.png +1305031933.568861 rgb/1305031933.568861.png 1305031933.564265 depth/1305031933.564265.png +1305031933.600899 rgb/1305031933.600899.png 1305031933.595687 depth/1305031933.595687.png +1305031933.632949 rgb/1305031933.632949.png 1305031933.626979 depth/1305031933.626979.png +1305031933.669114 rgb/1305031933.669114.png 1305031933.663105 depth/1305031933.663105.png +1305031933.700931 rgb/1305031933.700931.png 1305031933.695772 depth/1305031933.695772.png +1305031933.732901 rgb/1305031933.732901.png 1305031933.727622 depth/1305031933.727622.png +1305031933.768934 rgb/1305031933.768934.png 1305031933.763831 depth/1305031933.763831.png +1305031933.800879 rgb/1305031933.800879.png 1305031933.795823 depth/1305031933.795823.png +1305031933.833132 rgb/1305031933.833132.png 1305031933.827513 depth/1305031933.827513.png +1305031933.868855 rgb/1305031933.868855.png 1305031933.863871 depth/1305031933.863871.png +1305031933.900942 rgb/1305031933.900942.png 1305031933.895826 depth/1305031933.895826.png +1305031933.932925 rgb/1305031933.932925.png 1305031933.927864 depth/1305031933.927864.png +1305031933.968843 rgb/1305031933.968843.png 1305031933.964067 depth/1305031933.964067.png +1305031934.000841 rgb/1305031934.000841.png 1305031933.996159 depth/1305031933.996159.png +1305031934.033000 rgb/1305031934.033000.png 1305031934.025036 depth/1305031934.025036.png +1305031934.068946 rgb/1305031934.068946.png 1305031934.062070 depth/1305031934.062070.png +1305031934.100917 rgb/1305031934.100917.png 1305031934.095754 depth/1305031934.095754.png +1305031934.132845 rgb/1305031934.132845.png 1305031934.123903 depth/1305031934.123903.png +1305031934.169177 rgb/1305031934.169177.png 1305031934.163843 depth/1305031934.163843.png +1305031934.200808 rgb/1305031934.200808.png 1305031934.196078 depth/1305031934.196078.png +1305031934.232870 rgb/1305031934.232870.png 1305031934.226959 depth/1305031934.226959.png +1305031934.269296 rgb/1305031934.269296.png 1305031934.263347 depth/1305031934.263347.png +1305031934.300934 rgb/1305031934.300934.png 1305031934.295644 depth/1305031934.295644.png +1305031934.336871 rgb/1305031934.336871.png 1305031934.327544 depth/1305031934.327544.png +1305031934.368906 rgb/1305031934.368906.png 1305031934.363432 depth/1305031934.363432.png +1305031934.400928 rgb/1305031934.400928.png 1305031934.395278 depth/1305031934.395278.png +1305031934.436865 rgb/1305031934.436865.png 1305031934.427107 depth/1305031934.427107.png +1305031934.469287 rgb/1305031934.469287.png 1305031934.460046 depth/1305031934.460046.png +1305031934.501241 rgb/1305031934.501241.png 1305031934.495228 depth/1305031934.495228.png +1305031934.536876 rgb/1305031934.536876.png 1305031934.527409 depth/1305031934.527409.png +1305031934.569101 rgb/1305031934.569101.png 1305031934.563395 depth/1305031934.563395.png +1305031934.600850 rgb/1305031934.600850.png 1305031934.595082 depth/1305031934.595082.png +1305031934.637030 rgb/1305031934.637030.png 1305031934.627102 depth/1305031934.627102.png +1305031934.668984 rgb/1305031934.668984.png 1305031934.662910 depth/1305031934.662910.png +1305031934.700945 rgb/1305031934.700945.png 1305031934.694817 depth/1305031934.694817.png +1305031934.736903 rgb/1305031934.736903.png 1305031934.726749 depth/1305031934.726749.png +1305031934.769124 rgb/1305031934.769124.png 1305031934.762903 depth/1305031934.762903.png +1305031934.801627 rgb/1305031934.801627.png 1305031934.794831 depth/1305031934.794831.png +1305031934.836769 rgb/1305031934.836769.png 1305031934.830983 depth/1305031934.830983.png +1305031934.869115 rgb/1305031934.869115.png 1305031934.862668 depth/1305031934.862668.png +1305031934.901010 rgb/1305031934.901010.png 1305031934.894445 depth/1305031934.894445.png +1305031934.937234 rgb/1305031934.937234.png 1305031934.931747 depth/1305031934.931747.png +1305031934.969077 rgb/1305031934.969077.png 1305031934.963384 depth/1305031934.963384.png +1305031935.001270 rgb/1305031935.001270.png 1305031934.995132 depth/1305031934.995132.png +1305031935.036852 rgb/1305031935.036852.png 1305031935.033022 depth/1305031935.033022.png +1305031935.069722 rgb/1305031935.069722.png 1305031935.063116 depth/1305031935.063116.png +1305031935.100912 rgb/1305031935.100912.png 1305031935.095058 depth/1305031935.095058.png +1305031935.136853 rgb/1305031935.136853.png 1305031935.130727 depth/1305031935.130727.png +1305031935.169281 rgb/1305031935.169281.png 1305031935.162214 depth/1305031935.162214.png +1305031935.200951 rgb/1305031935.200951.png 1305031935.194899 depth/1305031935.194899.png +1305031935.237095 rgb/1305031935.237095.png 1305031935.231025 depth/1305031935.231025.png +1305031935.268965 rgb/1305031935.268965.png 1305031935.260736 depth/1305031935.260736.png +1305031935.300805 rgb/1305031935.300805.png 1305031935.295152 depth/1305031935.295152.png +1305031935.336810 rgb/1305031935.336810.png 1305031935.330960 depth/1305031935.330960.png +1305031935.368827 rgb/1305031935.368827.png 1305031935.363255 depth/1305031935.363255.png +1305031935.400848 rgb/1305031935.400848.png 1305031935.394932 depth/1305031935.394932.png +1305031935.436887 rgb/1305031935.436887.png 1305031935.430905 depth/1305031935.430905.png +1305031935.468890 rgb/1305031935.468890.png 1305031935.463017 depth/1305031935.463017.png +1305031935.500863 rgb/1305031935.500863.png 1305031935.493044 depth/1305031935.493044.png +1305031935.536900 rgb/1305031935.536900.png 1305031935.530045 depth/1305031935.530045.png +1305031935.568783 rgb/1305031935.568783.png 1305031935.562732 depth/1305031935.562732.png +1305031935.600963 rgb/1305031935.600963.png 1305031935.594819 depth/1305031935.594819.png +1305031935.636916 rgb/1305031935.636916.png 1305031935.631390 depth/1305031935.631390.png +1305031935.669100 rgb/1305031935.669100.png 1305031935.663543 depth/1305031935.663543.png +1305031935.700948 rgb/1305031935.700948.png 1305031935.695531 depth/1305031935.695531.png +1305031935.736900 rgb/1305031935.736900.png 1305031935.731180 depth/1305031935.731180.png +1305031935.768974 rgb/1305031935.768974.png 1305031935.763521 depth/1305031935.763521.png +1305031935.801178 rgb/1305031935.801178.png 1305031935.795359 depth/1305031935.795359.png +1305031935.836877 rgb/1305031935.836877.png 1305031935.831205 depth/1305031935.831205.png +1305031935.869025 rgb/1305031935.869025.png 1305031935.863651 depth/1305031935.863651.png +1305031935.901144 rgb/1305031935.901144.png 1305031935.895325 depth/1305031935.895325.png +1305031935.936825 rgb/1305031935.936825.png 1305031935.931428 depth/1305031935.931428.png +1305031935.969109 rgb/1305031935.969109.png 1305031935.963243 depth/1305031935.963243.png +1305031936.000820 rgb/1305031936.000820.png 1305031935.995756 depth/1305031935.995756.png +1305031936.036965 rgb/1305031936.036965.png 1305031936.031927 depth/1305031936.031927.png +1305031936.068809 rgb/1305031936.068809.png 1305031936.063602 depth/1305031936.063602.png +1305031936.100718 rgb/1305031936.100718.png 1305031936.099066 depth/1305031936.099066.png +1305031936.137490 rgb/1305031936.137490.png 1305031936.130808 depth/1305031936.130808.png +1305031936.168897 rgb/1305031936.168897.png 1305031936.163443 depth/1305031936.163443.png +1305031936.200867 rgb/1305031936.200867.png 1305031936.200045 depth/1305031936.200045.png +1305031936.237546 rgb/1305031936.237546.png 1305031936.231637 depth/1305031936.231637.png +1305031936.268981 rgb/1305031936.268981.png 1305031936.262854 depth/1305031936.262854.png +1305031936.300816 rgb/1305031936.300816.png 1305031936.299656 depth/1305031936.299656.png +1305031936.336863 rgb/1305031936.336863.png 1305031936.331649 depth/1305031936.331649.png +1305031936.368927 rgb/1305031936.368927.png 1305031936.363578 depth/1305031936.363578.png +1305031936.400840 rgb/1305031936.400840.png 1305031936.399525 depth/1305031936.399525.png +1305031936.436777 rgb/1305031936.436777.png 1305031936.431784 depth/1305031936.431784.png +1305031936.468789 rgb/1305031936.468789.png 1305031936.463134 depth/1305031936.463134.png +1305031936.500753 rgb/1305031936.500753.png 1305031936.499445 depth/1305031936.499445.png +1305031936.536847 rgb/1305031936.536847.png 1305031936.531202 depth/1305031936.531202.png +1305031936.569452 rgb/1305031936.569452.png 1305031936.563251 depth/1305031936.563251.png +1305031936.600821 rgb/1305031936.600821.png 1305031936.599685 depth/1305031936.599685.png +1305031936.636879 rgb/1305031936.636879.png 1305031936.631518 depth/1305031936.631518.png +1305031936.668885 rgb/1305031936.668885.png 1305031936.663832 depth/1305031936.663832.png +1305031936.700881 rgb/1305031936.700881.png 1305031936.699970 depth/1305031936.699970.png +1305031936.737504 rgb/1305031936.737504.png 1305031936.731597 depth/1305031936.731597.png +1305031936.768825 rgb/1305031936.768825.png 1305031936.763730 depth/1305031936.763730.png +1305031936.800856 rgb/1305031936.800856.png 1305031936.799809 depth/1305031936.799809.png +1305031936.836845 rgb/1305031936.836845.png 1305031936.831892 depth/1305031936.831892.png +1305031936.868891 rgb/1305031936.868891.png 1305031936.863697 depth/1305031936.863697.png +1305031936.900833 rgb/1305031936.900833.png 1305031936.900115 depth/1305031936.900115.png +1305031936.936914 rgb/1305031936.936914.png 1305031936.931480 depth/1305031936.931480.png +1305031936.968821 rgb/1305031936.968821.png 1305031936.963897 depth/1305031936.963897.png +1305031937.001118 rgb/1305031937.001118.png 1305031937.000148 depth/1305031937.000148.png +1305031937.036874 rgb/1305031937.036874.png 1305031937.032120 depth/1305031937.032120.png +1305031937.068765 rgb/1305031937.068765.png 1305031937.060179 depth/1305031937.060179.png +1305031937.100716 rgb/1305031937.100716.png 1305031937.097948 depth/1305031937.097948.png +1305031937.136838 rgb/1305031937.136838.png 1305031937.131381 depth/1305031937.131381.png +1305031937.168856 rgb/1305031937.168856.png 1305031937.162199 depth/1305031937.162199.png +1305031937.200813 rgb/1305031937.200813.png 1305031937.199678 depth/1305031937.199678.png +1305031937.236893 rgb/1305031937.236893.png 1305031937.231385 depth/1305031937.231385.png +1305031937.268821 rgb/1305031937.268821.png 1305031937.263361 depth/1305031937.263361.png +1305031937.300783 rgb/1305031937.300783.png 1305031937.299172 depth/1305031937.299172.png +1305031937.336862 rgb/1305031937.336862.png 1305031937.331472 depth/1305031937.331472.png +1305031937.368734 rgb/1305031937.368734.png 1305031937.367035 depth/1305031937.367035.png +1305031937.400796 rgb/1305031937.400796.png 1305031937.399644 depth/1305031937.399644.png +1305031937.438211 rgb/1305031937.438211.png 1305031937.431305 depth/1305031937.431305.png +1305031937.468824 rgb/1305031937.468824.png 1305031937.467256 depth/1305031937.467256.png +1305031937.500797 rgb/1305031937.500797.png 1305031937.499237 depth/1305031937.499237.png +1305031937.536931 rgb/1305031937.536931.png 1305031937.531606 depth/1305031937.531606.png +1305031937.568829 rgb/1305031937.568829.png 1305031937.566400 depth/1305031937.566400.png +1305031937.600746 rgb/1305031937.600746.png 1305031937.599586 depth/1305031937.599586.png +1305031937.636891 rgb/1305031937.636891.png 1305031937.627766 depth/1305031937.627766.png +1305031937.668803 rgb/1305031937.668803.png 1305031937.667658 depth/1305031937.667658.png +1305031937.700837 rgb/1305031937.700837.png 1305031937.699645 depth/1305031937.699645.png +1305031937.736899 rgb/1305031937.736899.png 1305031937.731732 depth/1305031937.731732.png +1305031937.768919 rgb/1305031937.768919.png 1305031937.767791 depth/1305031937.767791.png +1305031937.800834 rgb/1305031937.800834.png 1305031937.799732 depth/1305031937.799732.png +1305031937.836877 rgb/1305031937.836877.png 1305031937.831889 depth/1305031937.831889.png +1305031937.868807 rgb/1305031937.868807.png 1305031937.867758 depth/1305031937.867758.png +1305031937.900823 rgb/1305031937.900823.png 1305031937.899933 depth/1305031937.899933.png +1305031937.936960 rgb/1305031937.936960.png 1305031937.931831 depth/1305031937.931831.png +1305031937.968830 rgb/1305031937.968830.png 1305031937.968127 depth/1305031937.968127.png +1305031938.000822 rgb/1305031938.000822.png 1305031938.000042 depth/1305031938.000042.png +1305031938.036945 rgb/1305031938.036945.png 1305031938.031836 depth/1305031938.031836.png +1305031938.068761 rgb/1305031938.068761.png 1305031938.067761 depth/1305031938.067761.png +1305031938.100744 rgb/1305031938.100744.png 1305031938.100010 depth/1305031938.100010.png +1305031938.136885 rgb/1305031938.136885.png 1305031938.131856 depth/1305031938.131856.png +1305031938.168914 rgb/1305031938.168914.png 1305031938.168307 depth/1305031938.168307.png +1305031938.200883 rgb/1305031938.200883.png 1305031938.199974 depth/1305031938.199974.png +1305031938.236878 rgb/1305031938.236878.png 1305031938.231649 depth/1305031938.231649.png +1305031938.268809 rgb/1305031938.268809.png 1305031938.267768 depth/1305031938.267768.png +1305031938.300837 rgb/1305031938.300837.png 1305031938.300089 depth/1305031938.300089.png +1305031938.336900 rgb/1305031938.336900.png 1305031938.331736 depth/1305031938.331736.png +1305031938.368914 rgb/1305031938.368914.png 1305031938.367715 depth/1305031938.367715.png +1305031938.400842 rgb/1305031938.400842.png 1305031938.400257 depth/1305031938.400257.png +1305031938.436889 rgb/1305031938.436889.png 1305031938.431934 depth/1305031938.431934.png +1305031938.468781 rgb/1305031938.468781.png 1305031938.468046 depth/1305031938.468046.png +1305031938.501288 rgb/1305031938.501288.png 1305031938.496114 depth/1305031938.496114.png +1305031938.537028 rgb/1305031938.537028.png 1305031938.535972 depth/1305031938.535972.png +1305031938.568999 rgb/1305031938.568999.png 1305031938.563904 depth/1305031938.563904.png +1305031938.601007 rgb/1305031938.601007.png 1305031938.598200 depth/1305031938.598200.png +1305031938.637299 rgb/1305031938.637299.png 1305031938.637455 depth/1305031938.637455.png +1305031938.668747 rgb/1305031938.668747.png 1305031938.667115 depth/1305031938.667115.png +1305031938.700851 rgb/1305031938.700851.png 1305031938.699613 depth/1305031938.699613.png +1305031938.736859 rgb/1305031938.736859.png 1305031938.735353 depth/1305031938.735353.png +1305031938.769073 rgb/1305031938.769073.png 1305031938.767438 depth/1305031938.767438.png +1305031938.800781 rgb/1305031938.800781.png 1305031938.799553 depth/1305031938.799553.png +1305031938.836754 rgb/1305031938.836754.png 1305031938.835081 depth/1305031938.835081.png +1305031938.869057 rgb/1305031938.869057.png 1305031938.867115 depth/1305031938.867115.png +1305031938.900976 rgb/1305031938.900976.png 1305031938.899948 depth/1305031938.899948.png +1305031938.936828 rgb/1305031938.936828.png 1305031938.935595 depth/1305031938.935595.png +1305031938.969026 rgb/1305031938.969026.png 1305031938.967685 depth/1305031938.967685.png +1305031939.001030 rgb/1305031939.001030.png 1305031939.000242 depth/1305031939.000242.png +1305031939.037090 rgb/1305031939.037090.png 1305031939.035825 depth/1305031939.035825.png +1305031939.069377 rgb/1305031939.069377.png 1305031939.067934 depth/1305031939.067934.png +1305031939.101368 rgb/1305031939.101368.png 1305031939.099862 depth/1305031939.099862.png +1305031939.137143 rgb/1305031939.137143.png 1305031939.135566 depth/1305031939.135566.png +1305031939.168815 rgb/1305031939.168815.png 1305031939.167694 depth/1305031939.167694.png +1305031939.200865 rgb/1305031939.200865.png 1305031939.200214 depth/1305031939.200214.png +1305031939.237165 rgb/1305031939.237165.png 1305031939.235712 depth/1305031939.235712.png +1305031939.268824 rgb/1305031939.268824.png 1305031939.267640 depth/1305031939.267640.png +1305031939.300842 rgb/1305031939.300842.png 1305031939.300206 depth/1305031939.300206.png +1305031939.336729 rgb/1305031939.336729.png 1305031939.335053 depth/1305031939.335053.png +1305031939.368966 rgb/1305031939.368966.png 1305031939.367490 depth/1305031939.367490.png +1305031939.400848 rgb/1305031939.400848.png 1305031939.399885 depth/1305031939.399885.png +1305031939.436845 rgb/1305031939.436845.png 1305031939.435410 depth/1305031939.435410.png +1305031939.468851 rgb/1305031939.468851.png 1305031939.467647 depth/1305031939.467647.png +1305031939.500839 rgb/1305031939.500839.png 1305031939.499844 depth/1305031939.499844.png +1305031939.536755 rgb/1305031939.536755.png 1305031939.535364 depth/1305031939.535364.png +1305031939.568772 rgb/1305031939.568772.png 1305031939.567564 depth/1305031939.567564.png +1305031939.600838 rgb/1305031939.600838.png 1305031939.600160 depth/1305031939.600160.png +1305031939.636792 rgb/1305031939.636792.png 1305031939.635762 depth/1305031939.635762.png +1305031939.668867 rgb/1305031939.668867.png 1305031939.667415 depth/1305031939.667415.png +1305031939.700830 rgb/1305031939.700830.png 1305031939.700124 depth/1305031939.700124.png +1305031939.736750 rgb/1305031939.736750.png 1305031939.735464 depth/1305031939.735464.png +1305031939.768919 rgb/1305031939.768919.png 1305031939.767882 depth/1305031939.767882.png +1305031939.803671 rgb/1305031939.803671.png 1305031939.803685 depth/1305031939.803685.png +1305031939.837145 rgb/1305031939.837145.png 1305031939.835759 depth/1305031939.835759.png +1305031939.869215 rgb/1305031939.869215.png 1305031939.863918 depth/1305031939.863918.png +1305031939.903633 rgb/1305031939.903633.png 1305031939.903642 depth/1305031939.903642.png +1305031939.937192 rgb/1305031939.937192.png 1305031939.936002 depth/1305031939.936002.png +1305031939.968904 rgb/1305031939.968904.png 1305031939.967674 depth/1305031939.967674.png +1305031940.005582 rgb/1305031940.005582.png 1305031940.005613 depth/1305031940.005613.png +1305031940.037088 rgb/1305031940.037088.png 1305031940.031897 depth/1305031940.031897.png +1305031940.068783 rgb/1305031940.068783.png 1305031940.067499 depth/1305031940.067499.png +1305031940.104265 rgb/1305031940.104265.png 1305031940.104322 depth/1305031940.104322.png +1305031940.136746 rgb/1305031940.136746.png 1305031940.135843 depth/1305031940.135843.png +1305031940.168737 rgb/1305031940.168737.png 1305031940.168748 depth/1305031940.168748.png +1305031940.200829 rgb/1305031940.200829.png 1305031940.200119 depth/1305031940.200119.png +1305031940.236742 rgb/1305031940.236742.png 1305031940.235303 depth/1305031940.235303.png +1305031940.269041 rgb/1305031940.269041.png 1305031940.267548 depth/1305031940.267548.png +1305031940.301146 rgb/1305031940.301146.png 1305031940.300057 depth/1305031940.300057.png +1305031940.336732 rgb/1305031940.336732.png 1305031940.335962 depth/1305031940.335962.png +1305031940.369236 rgb/1305031940.369236.png 1305031940.367240 depth/1305031940.367240.png +1305031940.403665 rgb/1305031940.403665.png 1305031940.403701 depth/1305031940.403701.png +1305031940.436756 rgb/1305031940.436756.png 1305031940.435753 depth/1305031940.435753.png +1305031940.468746 rgb/1305031940.468746.png 1305031940.467066 depth/1305031940.467066.png +1305031940.503804 rgb/1305031940.503804.png 1305031940.503814 depth/1305031940.503814.png +1305031940.536724 rgb/1305031940.536724.png 1305031940.535239 depth/1305031940.535239.png +1305031940.568758 rgb/1305031940.568758.png 1305031940.566964 depth/1305031940.566964.png +1305031940.603364 rgb/1305031940.603364.png 1305031940.603395 depth/1305031940.603395.png +1305031940.636761 rgb/1305031940.636761.png 1305031940.635226 depth/1305031940.635226.png +1305031940.668762 rgb/1305031940.668762.png 1305031940.666993 depth/1305031940.666993.png +1305031940.703222 rgb/1305031940.703222.png 1305031940.703234 depth/1305031940.703234.png +1305031940.736947 rgb/1305031940.736947.png 1305031940.735222 depth/1305031940.735222.png +1305031940.768772 rgb/1305031940.768772.png 1305031940.766929 depth/1305031940.766929.png +1305031940.803047 rgb/1305031940.803047.png 1305031940.803100 depth/1305031940.803100.png +1305031940.836755 rgb/1305031940.836755.png 1305031940.835097 depth/1305031940.835097.png +1305031940.869689 rgb/1305031940.869689.png 1305031940.867019 depth/1305031940.867019.png +1305031940.903305 rgb/1305031940.903305.png 1305031940.903314 depth/1305031940.903314.png +1305031940.937034 rgb/1305031940.937034.png 1305031940.935305 depth/1305031940.935305.png +1305031940.968758 rgb/1305031940.968758.png 1305031940.967150 depth/1305031940.967150.png +1305031941.003160 rgb/1305031941.003160.png 1305031941.003186 depth/1305031941.003186.png +1305031941.036777 rgb/1305031941.036777.png 1305031941.035260 depth/1305031941.035260.png +1305031941.071057 rgb/1305031941.071057.png 1305031941.071076 depth/1305031941.071076.png +1305031941.103422 rgb/1305031941.103422.png 1305031941.103456 depth/1305031941.103456.png +1305031941.136774 rgb/1305031941.136774.png 1305031941.135554 depth/1305031941.135554.png +1305031941.171144 rgb/1305031941.171144.png 1305031941.171171 depth/1305031941.171171.png +1305031941.203508 rgb/1305031941.203508.png 1305031941.203532 depth/1305031941.203532.png +1305031941.236705 rgb/1305031941.236705.png 1305031941.235196 depth/1305031941.235196.png +1305031941.271129 rgb/1305031941.271129.png 1305031941.271139 depth/1305031941.271139.png +1305031941.303362 rgb/1305031941.303362.png 1305031941.303377 depth/1305031941.303377.png +1305031941.336734 rgb/1305031941.336734.png 1305031941.335303 depth/1305031941.335303.png +1305031941.371607 rgb/1305031941.371607.png 1305031941.371617 depth/1305031941.371617.png +1305031941.403845 rgb/1305031941.403845.png 1305031941.403877 depth/1305031941.403877.png +1305031941.436799 rgb/1305031941.436799.png 1305031941.435687 depth/1305031941.435687.png +1305031941.469611 rgb/1305031941.469611.png 1305031941.469619 depth/1305031941.469619.png +1305031941.501458 rgb/1305031941.501458.png 1305031941.501518 depth/1305031941.501518.png +1305031941.537220 rgb/1305031941.537220.png 1305031941.534653 depth/1305031941.534653.png +1305031941.570287 rgb/1305031941.570287.png 1305031941.570302 depth/1305031941.570302.png +1305031941.603047 rgb/1305031941.603047.png 1305031941.603072 depth/1305031941.603072.png +1305031941.636822 rgb/1305031941.636822.png 1305031941.635675 depth/1305031941.635675.png +1305031941.671554 rgb/1305031941.671554.png 1305031941.671562 depth/1305031941.671562.png +1305031941.703763 rgb/1305031941.703763.png 1305031941.703773 depth/1305031941.703773.png +1305031941.736866 rgb/1305031941.736866.png 1305031941.735592 depth/1305031941.735592.png +1305031941.768815 rgb/1305031941.768815.png 1305031941.767812 depth/1305031941.767812.png +1305031941.800820 rgb/1305031941.800820.png 1305031941.800828 depth/1305031941.800828.png +1305031941.836848 rgb/1305031941.836848.png 1305031941.832014 depth/1305031941.832014.png +1305031941.871813 rgb/1305031941.871813.png 1305031941.871824 depth/1305031941.871824.png +1305031941.902976 rgb/1305031941.902976.png 1305031941.903043 depth/1305031941.903043.png +1305031941.936760 rgb/1305031941.936760.png 1305031941.935190 depth/1305031941.935190.png +1305031941.971057 rgb/1305031941.971057.png 1305031941.971085 depth/1305031941.971085.png +1305031942.003141 rgb/1305031942.003141.png 1305031942.003159 depth/1305031942.003159.png +1305031942.036729 rgb/1305031942.036729.png 1305031942.035444 depth/1305031942.035444.png +1305031942.071082 rgb/1305031942.071082.png 1305031942.071092 depth/1305031942.071092.png +1305031942.100691 rgb/1305031942.100691.png 1305031942.099769 depth/1305031942.099769.png +1305031942.136758 rgb/1305031942.136758.png 1305031942.135205 depth/1305031942.135205.png +1305031942.170749 rgb/1305031942.170749.png 1305031942.170762 depth/1305031942.170762.png +1305031942.203108 rgb/1305031942.203108.png 1305031942.203125 depth/1305031942.203125.png +1305031942.238994 rgb/1305031942.238994.png 1305031942.239026 depth/1305031942.239026.png +1305031942.271105 rgb/1305031942.271105.png 1305031942.271143 depth/1305031942.271143.png +1305031942.303257 rgb/1305031942.303257.png 1305031942.303198 depth/1305031942.303198.png +1305031942.337047 rgb/1305031942.337047.png 1305031942.335609 depth/1305031942.335609.png +1305031942.370761 rgb/1305031942.370761.png 1305031942.370779 depth/1305031942.370779.png +1305031942.402939 rgb/1305031942.402939.png 1305031942.402950 depth/1305031942.402950.png +1305031942.439262 rgb/1305031942.439262.png 1305031942.439272 depth/1305031942.439272.png +1305031942.471958 rgb/1305031942.471958.png 1305031942.472314 depth/1305031942.472314.png +1305031942.503553 rgb/1305031942.503553.png 1305031942.503687 depth/1305031942.503687.png +1305031942.539453 rgb/1305031942.539453.png 1305031942.539471 depth/1305031942.539471.png +1305031942.571867 rgb/1305031942.571867.png 1305031942.571873 depth/1305031942.571873.png +1305031942.601448 rgb/1305031942.601448.png 1305031942.601458 depth/1305031942.601458.png +1305031942.639942 rgb/1305031942.639942.png 1305031942.639952 depth/1305031942.639952.png +1305031942.669006 rgb/1305031942.669006.png 1305031942.667679 depth/1305031942.667679.png +1305031942.704015 rgb/1305031942.704015.png 1305031942.704026 depth/1305031942.704026.png +1305031942.739812 rgb/1305031942.739812.png 1305031942.739823 depth/1305031942.739823.png +1305031942.771708 rgb/1305031942.771708.png 1305031942.771728 depth/1305031942.771728.png +1305031942.801557 rgb/1305031942.801557.png 1305031942.801585 depth/1305031942.801585.png +1305031942.841042 rgb/1305031942.841042.png 1305031942.841069 depth/1305031942.841069.png +1305031942.868828 rgb/1305031942.868828.png 1305031942.867914 depth/1305031942.867914.png +1305031942.903960 rgb/1305031942.903960.png 1305031942.903971 depth/1305031942.903971.png +1305031942.936816 rgb/1305031942.936816.png 1305031942.936255 depth/1305031942.936255.png +1305031942.970936 rgb/1305031942.970936.png 1305031942.970947 depth/1305031942.970947.png +1305031943.001103 rgb/1305031943.001103.png 1305031943.001126 depth/1305031943.001126.png +1305031943.039961 rgb/1305031943.039961.png 1305031943.039973 depth/1305031943.039973.png +1305031943.071743 rgb/1305031943.071743.png 1305031943.071764 depth/1305031943.071764.png +1305031943.104177 rgb/1305031943.104177.png 1305031943.104196 depth/1305031943.104196.png +1305031943.139521 rgb/1305031943.139521.png 1305031943.139631 depth/1305031943.139631.png +1305031943.171912 rgb/1305031943.171912.png 1305031943.171931 depth/1305031943.171931.png +1305031943.201564 rgb/1305031943.201564.png 1305031943.201583 depth/1305031943.201583.png +1305031943.240004 rgb/1305031943.240004.png 1305031943.240026 depth/1305031943.240026.png +1305031943.271805 rgb/1305031943.271805.png 1305031943.272012 depth/1305031943.272012.png +1305031943.303965 rgb/1305031943.303965.png 1305031943.303977 depth/1305031943.303977.png +1305031943.339941 rgb/1305031943.339941.png 1305031943.339953 depth/1305031943.339953.png +1305031943.371774 rgb/1305031943.371774.png 1305031943.371795 depth/1305031943.371795.png +1305031943.404245 rgb/1305031943.404245.png 1305031943.404597 depth/1305031943.404597.png +1305031943.440153 rgb/1305031943.440153.png 1305031943.440230 depth/1305031943.440230.png +1305031943.471431 rgb/1305031943.471431.png 1305031943.471442 depth/1305031943.471442.png +1305031943.501108 rgb/1305031943.501108.png 1305031943.509496 depth/1305031943.509496.png +1305031943.539525 rgb/1305031943.539525.png 1305031943.539543 depth/1305031943.539543.png +1305031943.570021 rgb/1305031943.570021.png 1305031943.570040 depth/1305031943.570040.png +1305031943.607467 rgb/1305031943.607467.png 1305031943.607498 depth/1305031943.607498.png +1305031943.638026 rgb/1305031943.638026.png 1305031943.638034 depth/1305031943.638034.png +1305031943.671504 rgb/1305031943.671504.png 1305031943.671539 depth/1305031943.671539.png +1305031943.707251 rgb/1305031943.707251.png 1305031943.707262 depth/1305031943.707262.png +1305031943.739428 rgb/1305031943.739428.png 1305031943.739461 depth/1305031943.739461.png +1305031943.771329 rgb/1305031943.771329.png 1305031943.771360 depth/1305031943.771360.png +1305031943.806822 rgb/1305031943.806822.png 1305031943.806840 depth/1305031943.806840.png +1305031943.837754 rgb/1305031943.837754.png 1305031943.837771 depth/1305031943.837771.png +1305031943.868873 rgb/1305031943.868873.png 1305031943.867799 depth/1305031943.867799.png +1305031943.907218 rgb/1305031943.907218.png 1305031943.907228 depth/1305031943.907228.png +1305031943.936768 rgb/1305031943.936768.png 1305031943.935818 depth/1305031943.935818.png +1305031943.971278 rgb/1305031943.971278.png 1305031943.971293 depth/1305031943.971293.png +1305031944.007760 rgb/1305031944.007760.png 1305031944.007774 depth/1305031944.007774.png +1305031944.040486 rgb/1305031944.040486.png 1305031944.040559 depth/1305031944.040559.png +1305031944.070886 rgb/1305031944.070886.png 1305031944.070907 depth/1305031944.070907.png +1305031944.107390 rgb/1305031944.107390.png 1305031944.107412 depth/1305031944.107412.png +1305031944.139656 rgb/1305031944.139656.png 1305031944.139679 depth/1305031944.139679.png +1305031944.171370 rgb/1305031944.171370.png 1305031944.171401 depth/1305031944.171401.png +1305031944.206998 rgb/1305031944.206998.png 1305031944.207026 depth/1305031944.207026.png +1305031944.239334 rgb/1305031944.239334.png 1305031944.239359 depth/1305031944.239359.png +1305031944.270963 rgb/1305031944.270963.png 1305031944.270986 depth/1305031944.270986.png +1305031944.306934 rgb/1305031944.306934.png 1305031944.306965 depth/1305031944.306965.png +1305031944.339308 rgb/1305031944.339308.png 1305031944.339327 depth/1305031944.339327.png +1305031944.370745 rgb/1305031944.370745.png 1305031944.370764 depth/1305031944.370764.png +1305031944.406233 rgb/1305031944.406233.png 1305031944.406240 depth/1305031944.406240.png +1305031944.438724 rgb/1305031944.438724.png 1305031944.438740 depth/1305031944.438740.png +1305031944.471304 rgb/1305031944.471304.png 1305031944.471315 depth/1305031944.471315.png +1305031944.506947 rgb/1305031944.506947.png 1305031944.506966 depth/1305031944.506966.png +1305031944.539069 rgb/1305031944.539069.png 1305031944.539090 depth/1305031944.539090.png +1305031944.571530 rgb/1305031944.571530.png 1305031944.571543 depth/1305031944.571543.png +1305031944.607229 rgb/1305031944.607229.png 1305031944.607255 depth/1305031944.607255.png +1305031944.639625 rgb/1305031944.639625.png 1305031944.639988 depth/1305031944.639988.png +1305031944.671779 rgb/1305031944.671779.png 1305031944.671797 depth/1305031944.671797.png +1305031944.707774 rgb/1305031944.707774.png 1305031944.707795 depth/1305031944.707795.png +1305031944.739941 rgb/1305031944.739941.png 1305031944.739963 depth/1305031944.739963.png +1305031944.769058 rgb/1305031944.769058.png 1305031944.780883 depth/1305031944.780883.png +1305031944.807919 rgb/1305031944.807919.png 1305031944.807934 depth/1305031944.807934.png +1305031944.839956 rgb/1305031944.839956.png 1305031944.839961 depth/1305031944.839961.png +1305031944.875719 rgb/1305031944.875719.png 1305031944.875727 depth/1305031944.875727.png +1305031944.904670 rgb/1305031944.904670.png 1305031944.903822 depth/1305031944.903822.png +1305031944.939702 rgb/1305031944.939702.png 1305031944.939709 depth/1305031944.939709.png +1305031944.969076 rgb/1305031944.969076.png 1305031944.979551 depth/1305031944.979551.png +1305031945.007437 rgb/1305031945.007437.png 1305031945.007456 depth/1305031945.007456.png +1305031945.039937 rgb/1305031945.039937.png 1305031945.039953 depth/1305031945.039953.png +1305031945.069177 rgb/1305031945.069177.png 1305031945.079450 depth/1305031945.079450.png +1305031945.107523 rgb/1305031945.107523.png 1305031945.107554 depth/1305031945.107554.png +1305031945.136772 rgb/1305031945.136772.png 1305031945.135938 depth/1305031945.135938.png +1305031945.168992 rgb/1305031945.168992.png 1305031945.179287 depth/1305031945.179287.png +1305031945.207107 rgb/1305031945.207107.png 1305031945.207131 depth/1305031945.207131.png +1305031945.238859 rgb/1305031945.238859.png 1305031945.238880 depth/1305031945.238880.png +1305031945.269070 rgb/1305031945.269070.png 1305031945.276136 depth/1305031945.276136.png +1305031945.306358 rgb/1305031945.306358.png 1305031945.306364 depth/1305031945.306364.png +1305031945.338940 rgb/1305031945.338940.png 1305031945.338954 depth/1305031945.338954.png +1305031945.369056 rgb/1305031945.369056.png 1305031945.374695 depth/1305031945.374695.png +1305031945.406657 rgb/1305031945.406657.png 1305031945.406595 depth/1305031945.406595.png +1305031945.436818 rgb/1305031945.436818.png 1305031945.435557 depth/1305031945.435557.png +1305031945.469167 rgb/1305031945.469167.png 1305031945.477504 depth/1305031945.477504.png +1305031945.506438 rgb/1305031945.506438.png 1305031945.506448 depth/1305031945.506448.png +1305031945.538422 rgb/1305031945.538422.png 1305031945.538432 depth/1305031945.538432.png +1305031945.569071 rgb/1305031945.569071.png 1305031945.575422 depth/1305031945.575422.png +1305031945.606029 rgb/1305031945.606029.png 1305031945.606045 depth/1305031945.606045.png +1305031945.638298 rgb/1305031945.638298.png 1305031945.638328 depth/1305031945.638328.png +1305031945.669116 rgb/1305031945.669116.png 1305031945.677317 depth/1305031945.677317.png +1305031945.706215 rgb/1305031945.706215.png 1305031945.706227 depth/1305031945.706227.png +1305031945.738673 rgb/1305031945.738673.png 1305031945.738707 depth/1305031945.738707.png +1305031945.769045 rgb/1305031945.769045.png 1305031945.772817 depth/1305031945.772817.png +1305031945.806240 rgb/1305031945.806240.png 1305031945.806249 depth/1305031945.806249.png +1305031945.838266 rgb/1305031945.838266.png 1305031945.838302 depth/1305031945.838302.png +1305031945.869258 rgb/1305031945.869258.png 1305031945.877342 depth/1305031945.877342.png +1305031945.909177 rgb/1305031945.909177.png 1305031945.909465 depth/1305031945.909465.png +1305031945.936806 rgb/1305031945.936806.png 1305031945.935652 depth/1305031945.935652.png +1305031945.969300 rgb/1305031945.969300.png 1305031945.977263 depth/1305031945.977263.png +1305031946.005983 rgb/1305031946.005983.png 1305031946.005994 depth/1305031946.005994.png +1305031946.037278 rgb/1305031946.037278.png 1305031946.043263 depth/1305031946.043263.png +1305031946.069057 rgb/1305031946.069057.png 1305031946.075402 depth/1305031946.075402.png +1305031946.107140 rgb/1305031946.107140.png 1305031946.107156 depth/1305031946.107156.png +1305031946.137054 rgb/1305031946.137054.png 1305031946.147686 depth/1305031946.147686.png +1305031946.168867 rgb/1305031946.168867.png 1305031946.175861 depth/1305031946.175861.png +1305031946.207043 rgb/1305031946.207043.png 1305031946.207053 depth/1305031946.207053.png +1305031946.237369 rgb/1305031946.237369.png 1305031946.247192 depth/1305031946.247192.png +1305031946.268902 rgb/1305031946.268902.png 1305031946.276972 depth/1305031946.276972.png +1305031946.306775 rgb/1305031946.306775.png 1305031946.306937 depth/1305031946.306937.png +1305031946.337036 rgb/1305031946.337036.png 1305031946.347086 depth/1305031946.347086.png +1305031946.369021 rgb/1305031946.369021.png 1305031946.378747 depth/1305031946.378747.png +1305031946.406520 rgb/1305031946.406520.png 1305031946.406531 depth/1305031946.406531.png +1305031946.437150 rgb/1305031946.437150.png 1305031946.447353 depth/1305031946.447353.png +1305031946.468964 rgb/1305031946.468964.png 1305031946.473076 depth/1305031946.473076.png +1305031946.506586 rgb/1305031946.506586.png 1305031946.506597 depth/1305031946.506597.png +1305031946.537148 rgb/1305031946.537148.png 1305031946.546018 depth/1305031946.546018.png +1305031946.569238 rgb/1305031946.569238.png 1305031946.577280 depth/1305031946.577280.png +1305031946.606469 rgb/1305031946.606469.png 1305031946.606485 depth/1305031946.606485.png +1305031946.637163 rgb/1305031946.637163.png 1305031946.645981 depth/1305031946.645981.png +1305031946.669089 rgb/1305031946.669089.png 1305031946.678050 depth/1305031946.678050.png +1305031946.706515 rgb/1305031946.706515.png 1305031946.706532 depth/1305031946.706532.png +1305031946.737134 rgb/1305031946.737134.png 1305031946.743717 depth/1305031946.743717.png +1305031946.769059 rgb/1305031946.769059.png 1305031946.774660 depth/1305031946.774660.png +1305031946.806647 rgb/1305031946.806647.png 1305031946.806659 depth/1305031946.806659.png +1305031946.837100 rgb/1305031946.837100.png 1305031946.842679 depth/1305031946.842679.png +1305031946.869090 rgb/1305031946.869090.png 1305031946.874721 depth/1305031946.874721.png +1305031946.906602 rgb/1305031946.906602.png 1305031946.906633 depth/1305031946.906633.png +1305031946.937151 rgb/1305031946.937151.png 1305031946.942686 depth/1305031946.942686.png +1305031946.969064 rgb/1305031946.969064.png 1305031946.974825 depth/1305031946.974825.png +1305031947.006827 rgb/1305031947.006827.png 1305031947.006833 depth/1305031947.006833.png +1305031947.037000 rgb/1305031947.037000.png 1305031947.042914 depth/1305031947.042914.png +1305031947.068973 rgb/1305031947.068973.png 1305031947.074589 depth/1305031947.074589.png +1305031947.106644 rgb/1305031947.106644.png 1305031947.106663 depth/1305031947.106663.png +1305031947.137044 rgb/1305031947.137044.png 1305031947.142937 depth/1305031947.142937.png +1305031947.169117 rgb/1305031947.169117.png 1305031947.174651 depth/1305031947.174651.png +1305031947.204982 rgb/1305031947.204982.png 1305031947.210803 depth/1305031947.210803.png +1305031947.237001 rgb/1305031947.237001.png 1305031947.242625 depth/1305031947.242625.png +1305031947.269076 rgb/1305031947.269076.png 1305031947.274786 depth/1305031947.274786.png +1305031947.304951 rgb/1305031947.304951.png 1305031947.309122 depth/1305031947.309122.png +1305031947.336945 rgb/1305031947.336945.png 1305031947.339718 depth/1305031947.339718.png +1305031947.368991 rgb/1305031947.368991.png 1305031947.373087 depth/1305031947.373087.png +1305031947.405013 rgb/1305031947.405013.png 1305031947.407848 depth/1305031947.407848.png +1305031947.437038 rgb/1305031947.437038.png 1305031947.442996 depth/1305031947.442996.png +1305031947.469273 rgb/1305031947.469273.png 1305031947.475248 depth/1305031947.475248.png +1305031947.504994 rgb/1305031947.504994.png 1305031947.511457 depth/1305031947.511457.png +1305031947.537022 rgb/1305031947.537022.png 1305031947.543322 depth/1305031947.543322.png +1305031947.568989 rgb/1305031947.568989.png 1305031947.572475 depth/1305031947.572475.png +1305031947.605177 rgb/1305031947.605177.png 1305031947.611625 depth/1305031947.611625.png +1305031947.637085 rgb/1305031947.637085.png 1305031947.643731 depth/1305031947.643731.png +1305031947.669011 rgb/1305031947.669011.png 1305031947.675360 depth/1305031947.675360.png +1305031947.705153 rgb/1305031947.705153.png 1305031947.711025 depth/1305031947.711025.png +1305031947.736979 rgb/1305031947.736979.png 1305031947.743304 depth/1305031947.743304.png +1305031947.769041 rgb/1305031947.769041.png 1305031947.775461 depth/1305031947.775461.png +1305031947.804941 rgb/1305031947.804941.png 1305031947.811424 depth/1305031947.811424.png +1305031947.837022 rgb/1305031947.837022.png 1305031947.841415 depth/1305031947.841415.png +1305031947.868988 rgb/1305031947.868988.png 1305031947.875442 depth/1305031947.875442.png +1305031947.904995 rgb/1305031947.904995.png 1305031947.911295 depth/1305031947.911295.png +1305031947.937025 rgb/1305031947.937025.png 1305031947.943516 depth/1305031947.943516.png +1305031947.968976 rgb/1305031947.968976.png 1305031947.975273 depth/1305031947.975273.png +1305031948.004911 rgb/1305031948.004911.png 1305031948.011498 depth/1305031948.011498.png +1305031948.037003 rgb/1305031948.037003.png 1305031948.043239 depth/1305031948.043239.png +1305031948.068973 rgb/1305031948.068973.png 1305031948.075218 depth/1305031948.075218.png +1305031948.104993 rgb/1305031948.104993.png 1305031948.111315 depth/1305031948.111315.png +1305031948.136951 rgb/1305031948.136951.png 1305031948.143226 depth/1305031948.143226.png +1305031948.168952 rgb/1305031948.168952.png 1305031948.175007 depth/1305031948.175007.png +1305031948.204992 rgb/1305031948.204992.png 1305031948.211235 depth/1305031948.211235.png +1305031948.237002 rgb/1305031948.237002.png 1305031948.243210 depth/1305031948.243210.png +1305031948.269041 rgb/1305031948.269041.png 1305031948.275446 depth/1305031948.275446.png +1305031948.304939 rgb/1305031948.304939.png 1305031948.311425 depth/1305031948.311425.png +1305031948.337101 rgb/1305031948.337101.png 1305031948.343521 depth/1305031948.343521.png +1305031948.368969 rgb/1305031948.368969.png 1305031948.375447 depth/1305031948.375447.png +1305031948.404989 rgb/1305031948.404989.png 1305031948.411285 depth/1305031948.411285.png +1305031948.436942 rgb/1305031948.436942.png 1305031948.443647 depth/1305031948.443647.png +1305031948.469170 rgb/1305031948.469170.png 1305031948.480437 depth/1305031948.480437.png +1305031948.505024 rgb/1305031948.505024.png 1305031948.514284 depth/1305031948.514284.png +1305031948.537017 rgb/1305031948.537017.png 1305031948.542869 depth/1305031948.542869.png +1305031948.568891 rgb/1305031948.568891.png 1305031948.580687 depth/1305031948.580687.png +1305031948.605001 rgb/1305031948.605001.png 1305031948.611060 depth/1305031948.611060.png +1305031948.636912 rgb/1305031948.636912.png 1305031948.644895 depth/1305031948.644895.png +1305031948.669040 rgb/1305031948.669040.png 1305031948.681662 depth/1305031948.681662.png +1305031948.705075 rgb/1305031948.705075.png 1305031948.714453 depth/1305031948.714453.png +1305031948.737063 rgb/1305031948.737063.png 1305031948.746432 depth/1305031948.746432.png +1305031948.768899 rgb/1305031948.768899.png 1305031948.780858 depth/1305031948.780858.png +1305031948.804975 rgb/1305031948.804975.png 1305031948.812389 depth/1305031948.812389.png +1305031948.837073 rgb/1305031948.837073.png 1305031948.841687 depth/1305031948.841687.png +1305031948.868835 rgb/1305031948.868835.png 1305031948.880529 depth/1305031948.880529.png +1305031948.905077 rgb/1305031948.905077.png 1305031948.915493 depth/1305031948.915493.png +1305031948.936996 rgb/1305031948.936996.png 1305031948.943231 depth/1305031948.943231.png +1305031948.968952 rgb/1305031948.968952.png 1305031948.979038 depth/1305031948.979038.png +1305031949.005006 rgb/1305031949.005006.png 1305031949.014896 depth/1305031949.014896.png +1305031949.037089 rgb/1305031949.037089.png 1305031949.044596 depth/1305031949.044596.png +1305031949.069061 rgb/1305031949.069061.png 1305031949.082201 depth/1305031949.082201.png +1305031949.105077 rgb/1305031949.105077.png 1305031949.114284 depth/1305031949.114284.png +1305031949.137263 rgb/1305031949.137263.png 1305031949.144262 depth/1305031949.144262.png +1305031949.168946 rgb/1305031949.168946.png 1305031949.180779 depth/1305031949.180779.png +1305031949.204940 rgb/1305031949.204940.png 1305031949.214247 depth/1305031949.214247.png +1305031949.237011 rgb/1305031949.237011.png 1305031949.247701 depth/1305031949.247701.png +1305031949.268994 rgb/1305031949.268994.png 1305031949.281444 depth/1305031949.281444.png +1305031949.305254 rgb/1305031949.305254.png 1305031949.311257 depth/1305031949.311257.png +1305031949.337227 rgb/1305031949.337227.png 1305031949.341972 depth/1305031949.341972.png +1305031949.368902 rgb/1305031949.368902.png 1305031949.380234 depth/1305031949.380234.png +1305031949.405064 rgb/1305031949.405064.png 1305031949.410764 depth/1305031949.410764.png +1305031949.437094 rgb/1305031949.437094.png 1305031949.443117 depth/1305031949.443117.png +1305031949.468902 rgb/1305031949.468902.png 1305031949.479260 depth/1305031949.479260.png +1305031949.505002 rgb/1305031949.505002.png 1305031949.510843 depth/1305031949.510843.png +1305031949.537017 rgb/1305031949.537017.png 1305031949.541920 depth/1305031949.541920.png +1305031949.568988 rgb/1305031949.568988.png 1305031949.580836 depth/1305031949.580836.png +1305031949.604798 rgb/1305031949.604798.png 1305031949.614433 depth/1305031949.614433.png +1305031949.637172 rgb/1305031949.637172.png 1305031949.646345 depth/1305031949.646345.png +1305031949.668955 rgb/1305031949.668955.png 1305031949.680760 depth/1305031949.680760.png +1305031949.705003 rgb/1305031949.705003.png 1305031949.714490 depth/1305031949.714490.png +1305031949.736949 rgb/1305031949.736949.png 1305031949.749412 depth/1305031949.749412.png +1305031949.768985 rgb/1305031949.768985.png 1305031949.781235 depth/1305031949.781235.png +1305031949.804939 rgb/1305031949.804939.png 1305031949.811436 depth/1305031949.811436.png +1305031949.836964 rgb/1305031949.836964.png 1305031949.845215 depth/1305031949.845215.png +1305031949.868951 rgb/1305031949.868951.png 1305031949.880626 depth/1305031949.880626.png +1305031949.904851 rgb/1305031949.904851.png 1305031949.914703 depth/1305031949.914703.png +1305031949.936858 rgb/1305031949.936858.png 1305031949.948731 depth/1305031949.948731.png +1305031949.968881 rgb/1305031949.968881.png 1305031949.981207 depth/1305031949.981207.png +1305031950.004952 rgb/1305031950.004952.png 1305031950.011524 depth/1305031950.011524.png +1305031950.036989 rgb/1305031950.036989.png 1305031950.047520 depth/1305031950.047520.png +1305031950.069081 rgb/1305031950.069081.png 1305031950.080195 depth/1305031950.080195.png +1305031950.104966 rgb/1305031950.104966.png 1305031950.111190 depth/1305031950.111190.png +1305031950.136997 rgb/1305031950.136997.png 1305031950.147985 depth/1305031950.147985.png +1305031950.168914 rgb/1305031950.168914.png 1305031950.181754 depth/1305031950.181754.png +1305031950.204933 rgb/1305031950.204933.png 1305031950.211149 depth/1305031950.211149.png +1305031950.237027 rgb/1305031950.237027.png 1305031950.247238 depth/1305031950.247238.png +1305031950.269033 rgb/1305031950.269033.png 1305031950.279213 depth/1305031950.279213.png +1305031950.304978 rgb/1305031950.304978.png 1305031950.307722 depth/1305031950.307722.png +1305031950.337197 rgb/1305031950.337197.png 1305031950.346992 depth/1305031950.346992.png +1305031950.368911 rgb/1305031950.368911.png 1305031950.378386 depth/1305031950.378386.png +1305031950.404939 rgb/1305031950.404939.png 1305031950.410330 depth/1305031950.410330.png +1305031950.436983 rgb/1305031950.436983.png 1305031950.447451 depth/1305031950.447451.png +1305031950.468976 rgb/1305031950.468976.png 1305031950.478952 depth/1305031950.478952.png +1305031950.504938 rgb/1305031950.504938.png 1305031950.510402 depth/1305031950.510402.png +1305031950.536894 rgb/1305031950.536894.png 1305031950.546397 depth/1305031950.546397.png +1305031950.568883 rgb/1305031950.568883.png 1305031950.578462 depth/1305031950.578462.png +1305031950.604862 rgb/1305031950.604862.png 1305031950.610212 depth/1305031950.610212.png +1305031950.637006 rgb/1305031950.637006.png 1305031950.646840 depth/1305031950.646840.png +1305031950.668910 rgb/1305031950.668910.png 1305031950.678650 depth/1305031950.678650.png +1305031950.704873 rgb/1305031950.704873.png 1305031950.707517 depth/1305031950.707517.png +1305031950.736893 rgb/1305031950.736893.png 1305031950.746448 depth/1305031950.746448.png +1305031950.768897 rgb/1305031950.768897.png 1305031950.778662 depth/1305031950.778662.png +1305031950.804899 rgb/1305031950.804899.png 1305031950.810641 depth/1305031950.810641.png +1305031950.837135 rgb/1305031950.837135.png 1305031950.846960 depth/1305031950.846960.png +1305031950.869014 rgb/1305031950.869014.png 1305031950.880523 depth/1305031950.880523.png +1305031950.904883 rgb/1305031950.904883.png 1305031950.914994 depth/1305031950.914994.png +1305031950.936970 rgb/1305031950.936970.png 1305031950.948166 depth/1305031950.948166.png +1305031950.968904 rgb/1305031950.968904.png 1305031950.978853 depth/1305031950.978853.png +1305031951.004836 rgb/1305031951.004836.png 1305031951.016385 depth/1305031951.016385.png +1305031951.036930 rgb/1305031951.036930.png 1305031951.048065 depth/1305031951.048065.png +1305031951.069013 rgb/1305031951.069013.png 1305031951.080859 depth/1305031951.080859.png +1305031951.104800 rgb/1305031951.104800.png 1305031951.116229 depth/1305031951.116229.png +1305031951.136893 rgb/1305031951.136893.png 1305031951.147131 depth/1305031951.147131.png +1305031951.168908 rgb/1305031951.168908.png 1305031951.180627 depth/1305031951.180627.png +1305031951.204914 rgb/1305031951.204914.png 1305031951.215695 depth/1305031951.215695.png +1305031951.236957 rgb/1305031951.236957.png 1305031951.247998 depth/1305031951.247998.png +1305031951.268906 rgb/1305031951.268906.png 1305031951.279729 depth/1305031951.279729.png +1305031951.304862 rgb/1305031951.304862.png 1305031951.316576 depth/1305031951.316576.png +1305031951.336937 rgb/1305031951.336937.png 1305031951.348921 depth/1305031951.348921.png +1305031951.368840 rgb/1305031951.368840.png 1305031951.380780 depth/1305031951.380780.png +1305031951.404865 rgb/1305031951.404865.png 1305031951.415739 depth/1305031951.415739.png +1305031951.436903 rgb/1305031951.436903.png 1305031951.448724 depth/1305031951.448724.png +1305031951.468857 rgb/1305031951.468857.png 1305031951.479264 depth/1305031951.479264.png +1305031951.504916 rgb/1305031951.504916.png 1305031951.514325 depth/1305031951.514325.png +1305031951.536888 rgb/1305031951.536888.png 1305031951.549086 depth/1305031951.549086.png +1305031951.569006 rgb/1305031951.569006.png 1305031951.579884 depth/1305031951.579884.png +1305031951.604927 rgb/1305031951.604927.png 1305031951.616005 depth/1305031951.616005.png +1305031951.636936 rgb/1305031951.636936.png 1305031951.647946 depth/1305031951.647946.png +1305031951.668929 rgb/1305031951.668929.png 1305031951.680049 depth/1305031951.680049.png +1305031951.704880 rgb/1305031951.704880.png 1305031951.715829 depth/1305031951.715829.png +1305031951.736828 rgb/1305031951.736828.png 1305031951.747698 depth/1305031951.747698.png +1305031951.768926 rgb/1305031951.768926.png 1305031951.779676 depth/1305031951.779676.png +1305031951.804886 rgb/1305031951.804886.png 1305031951.813548 depth/1305031951.813548.png +1305031951.836932 rgb/1305031951.836932.png 1305031951.848226 depth/1305031951.848226.png +1305031951.868913 rgb/1305031951.868913.png 1305031951.880079 depth/1305031951.880079.png +1305031951.904907 rgb/1305031951.904907.png 1305031951.915908 depth/1305031951.915908.png +1305031951.936962 rgb/1305031951.936962.png 1305031951.948683 depth/1305031951.948683.png +1305031951.968839 rgb/1305031951.968839.png 1305031951.981889 depth/1305031951.981889.png +1305031952.004839 rgb/1305031952.004839.png 1305031952.016974 depth/1305031952.016974.png +1305031952.037104 rgb/1305031952.037104.png 1305031952.048200 depth/1305031952.048200.png +1305031952.068888 rgb/1305031952.068888.png 1305031952.080085 depth/1305031952.080085.png +1305031952.105135 rgb/1305031952.105135.png 1305031952.116717 depth/1305031952.116717.png +1305031952.136943 rgb/1305031952.136943.png 1305031952.147987 depth/1305031952.147987.png +1305031952.168932 rgb/1305031952.168932.png 1305031952.184234 depth/1305031952.184234.png +1305031952.204914 rgb/1305031952.204914.png 1305031952.216761 depth/1305031952.216761.png +1305031952.236877 rgb/1305031952.236877.png 1305031952.249227 depth/1305031952.249227.png +1305031952.268902 rgb/1305031952.268902.png 1305031952.286014 depth/1305031952.286014.png +1305031952.304888 rgb/1305031952.304888.png 1305031952.316634 depth/1305031952.316634.png +1305031952.336993 rgb/1305031952.336993.png 1305031952.348255 depth/1305031952.348255.png +1305031952.368960 rgb/1305031952.368960.png 1305031952.384145 depth/1305031952.384145.png +1305031952.404918 rgb/1305031952.404918.png 1305031952.416972 depth/1305031952.416972.png +1305031952.437054 rgb/1305031952.437054.png 1305031952.448757 depth/1305031952.448757.png +1305031952.468939 rgb/1305031952.468939.png 1305031952.485298 depth/1305031952.485298.png +1305031952.504868 rgb/1305031952.504868.png 1305031952.517162 depth/1305031952.517162.png +1305031952.536948 rgb/1305031952.536948.png 1305031952.549624 depth/1305031952.549624.png +1305031952.568932 rgb/1305031952.568932.png 1305031952.586036 depth/1305031952.586036.png +1305031952.604926 rgb/1305031952.604926.png 1305031952.616651 depth/1305031952.616651.png +1305031952.636992 rgb/1305031952.636992.png 1305031952.648319 depth/1305031952.648319.png +1305031952.668899 rgb/1305031952.668899.png 1305031952.684311 depth/1305031952.684311.png +1305031952.704918 rgb/1305031952.704918.png 1305031952.716954 depth/1305031952.716954.png +1305031952.736938 rgb/1305031952.736938.png 1305031952.747932 depth/1305031952.747932.png +1305031952.768957 rgb/1305031952.768957.png 1305031952.784923 depth/1305031952.784923.png +1305031952.804919 rgb/1305031952.804919.png 1305031952.815896 depth/1305031952.815896.png +1305031952.836931 rgb/1305031952.836931.png 1305031952.848902 depth/1305031952.848902.png +1305031952.868991 rgb/1305031952.868991.png 1305031952.884506 depth/1305031952.884506.png +1305031952.904920 rgb/1305031952.904920.png 1305031952.916053 depth/1305031952.916053.png +1305031952.936984 rgb/1305031952.936984.png 1305031952.947523 depth/1305031952.947523.png +1305031952.972903 rgb/1305031952.972903.png 1305031952.984578 depth/1305031952.984578.png +1305031953.004869 rgb/1305031953.004869.png 1305031953.016595 depth/1305031953.016595.png +1305031953.036943 rgb/1305031953.036943.png 1305031953.049017 depth/1305031953.049017.png +1305031953.073127 rgb/1305031953.073127.png 1305031953.083674 depth/1305031953.083674.png +1305031953.104909 rgb/1305031953.104909.png 1305031953.115587 depth/1305031953.115587.png +1305031953.137098 rgb/1305031953.137098.png 1305031953.147161 depth/1305031953.147161.png +1305031953.172998 rgb/1305031953.172998.png 1305031953.183058 depth/1305031953.183058.png +1305031953.204992 rgb/1305031953.204992.png 1305031953.215053 depth/1305031953.215053.png +1305031953.237103 rgb/1305031953.237103.png 1305031953.248151 depth/1305031953.248151.png +1305031953.273087 rgb/1305031953.273087.png 1305031953.283786 depth/1305031953.283786.png +1305031953.304968 rgb/1305031953.304968.png 1305031953.316977 depth/1305031953.316977.png +1305031953.337012 rgb/1305031953.337012.png 1305031953.347948 depth/1305031953.347948.png +1305031953.372964 rgb/1305031953.372964.png 1305031953.384173 depth/1305031953.384173.png +1305031953.404920 rgb/1305031953.404920.png 1305031953.415905 depth/1305031953.415905.png +1305031953.436876 rgb/1305031953.436876.png 1305031953.452336 depth/1305031953.452336.png +1305031953.473261 rgb/1305031953.473261.png 1305031953.483838 depth/1305031953.483838.png +1305031953.504919 rgb/1305031953.504919.png 1305031953.515920 depth/1305031953.515920.png +1305031953.536948 rgb/1305031953.536948.png 1305031953.551507 depth/1305031953.551507.png +1305031953.572862 rgb/1305031953.572862.png 1305031953.584439 depth/1305031953.584439.png +1305031953.604882 rgb/1305031953.604882.png 1305031953.618056 depth/1305031953.618056.png +1305031953.636962 rgb/1305031953.636962.png 1305031953.654177 depth/1305031953.654177.png +1305031953.673021 rgb/1305031953.673021.png 1305031953.683774 depth/1305031953.683774.png +1305031953.704929 rgb/1305031953.704929.png 1305031953.715952 depth/1305031953.715952.png +1305031953.736982 rgb/1305031953.736982.png 1305031953.752395 depth/1305031953.752395.png +1305031953.772886 rgb/1305031953.772886.png 1305031953.782908 depth/1305031953.782908.png +1305031953.804859 rgb/1305031953.804859.png 1305031953.816480 depth/1305031953.816480.png +1305031953.836840 rgb/1305031953.836840.png 1305031953.852417 depth/1305031953.852417.png +1305031953.872987 rgb/1305031953.872987.png 1305031953.884444 depth/1305031953.884444.png +1305031953.904912 rgb/1305031953.904912.png 1305031953.916154 depth/1305031953.916154.png +1305031953.936924 rgb/1305031953.936924.png 1305031953.952308 depth/1305031953.952308.png +1305031953.972857 rgb/1305031953.972857.png 1305031953.985028 depth/1305031953.985028.png +1305031954.004852 rgb/1305031954.004852.png 1305031954.017015 depth/1305031954.017015.png +1305031954.036921 rgb/1305031954.036921.png 1305031954.051816 depth/1305031954.051816.png +1305031954.072918 rgb/1305031954.072918.png 1305031954.085429 depth/1305031954.085429.png +1305031954.104933 rgb/1305031954.104933.png 1305031954.115779 depth/1305031954.115779.png +1305031954.136939 rgb/1305031954.136939.png 1305031954.152181 depth/1305031954.152181.png +1305031954.172997 rgb/1305031954.172997.png 1305031954.184964 depth/1305031954.184964.png +1305031954.204838 rgb/1305031954.204838.png 1305031954.217228 depth/1305031954.217228.png +1305031954.237023 rgb/1305031954.237023.png 1305031954.252057 depth/1305031954.252057.png +1305031954.272870 rgb/1305031954.272870.png 1305031954.285809 depth/1305031954.285809.png +1305031954.304869 rgb/1305031954.304869.png 1305031954.317325 depth/1305031954.317325.png +1305031954.336921 rgb/1305031954.336921.png 1305031954.348938 depth/1305031954.348938.png +1305031954.372872 rgb/1305031954.372872.png 1305031954.384479 depth/1305031954.384479.png +1305031954.404711 rgb/1305031954.404711.png 1305031954.416646 depth/1305031954.416646.png +1305031954.436896 rgb/1305031954.436896.png 1305031954.452249 depth/1305031954.452249.png +1305031954.472974 rgb/1305031954.472974.png 1305031954.483636 depth/1305031954.483636.png +1305031954.504827 rgb/1305031954.504827.png 1305031954.514991 depth/1305031954.514991.png +1305031954.536934 rgb/1305031954.536934.png 1305031954.552961 depth/1305031954.552961.png +1305031954.572946 rgb/1305031954.572946.png 1305031954.583506 depth/1305031954.583506.png +1305031954.604885 rgb/1305031954.604885.png 1305031954.616389 depth/1305031954.616389.png +1305031954.636862 rgb/1305031954.636862.png 1305031954.651711 depth/1305031954.651711.png +1305031954.672891 rgb/1305031954.672891.png 1305031954.683635 depth/1305031954.683635.png +1305031954.704892 rgb/1305031954.704892.png 1305031954.720557 depth/1305031954.720557.png +1305031954.736939 rgb/1305031954.736939.png 1305031954.751545 depth/1305031954.751545.png +1305031954.773183 rgb/1305031954.773183.png 1305031954.783603 depth/1305031954.783603.png +1305031954.804833 rgb/1305031954.804833.png 1305031954.820887 depth/1305031954.820887.png +1305031954.836924 rgb/1305031954.836924.png 1305031954.851912 depth/1305031954.851912.png +1305031954.873001 rgb/1305031954.873001.png 1305031954.883976 depth/1305031954.883976.png +1305031954.904866 rgb/1305031954.904866.png 1305031954.919388 depth/1305031954.919388.png +1305031954.937022 rgb/1305031954.937022.png 1305031954.951822 depth/1305031954.951822.png +1305031954.972931 rgb/1305031954.972931.png 1305031954.983417 depth/1305031954.983417.png +1305031955.004936 rgb/1305031955.004936.png 1305031955.019886 depth/1305031955.019886.png +1305031955.036969 rgb/1305031955.036969.png 1305031955.051198 depth/1305031955.051198.png +1305031955.073048 rgb/1305031955.073048.png 1305031955.083486 depth/1305031955.083486.png +1305031955.104929 rgb/1305031955.104929.png 1305031955.119530 depth/1305031955.119530.png +1305031955.136878 rgb/1305031955.136878.png 1305031955.150462 depth/1305031955.150462.png +1305031955.173003 rgb/1305031955.173003.png 1305031955.182670 depth/1305031955.182670.png +1305031955.204960 rgb/1305031955.204960.png 1305031955.219463 depth/1305031955.219463.png +1305031955.236857 rgb/1305031955.236857.png 1305031955.252519 depth/1305031955.252519.png +1305031955.272905 rgb/1305031955.272905.png 1305031955.283877 depth/1305031955.283877.png +1305031955.304880 rgb/1305031955.304880.png 1305031955.321200 depth/1305031955.321200.png +1305031955.337035 rgb/1305031955.337035.png 1305031955.350590 depth/1305031955.350590.png +1305031955.372861 rgb/1305031955.372861.png 1305031955.385074 depth/1305031955.385074.png +1305031955.404928 rgb/1305031955.404928.png 1305031955.418493 depth/1305031955.418493.png +1305031955.436909 rgb/1305031955.436909.png 1305031955.453866 depth/1305031955.453866.png +1305031955.472931 rgb/1305031955.472931.png 1305031955.484155 depth/1305031955.484155.png +1305031955.504893 rgb/1305031955.504893.png 1305031955.520645 depth/1305031955.520645.png +1305031955.536891 rgb/1305031955.536891.png 1305031955.552015 depth/1305031955.552015.png +1305031955.572893 rgb/1305031955.572893.png 1305031955.585017 depth/1305031955.585017.png +1305031955.604944 rgb/1305031955.604944.png 1305031955.621372 depth/1305031955.621372.png +1305031955.636881 rgb/1305031955.636881.png 1305031955.652029 depth/1305031955.652029.png +1305031955.672837 rgb/1305031955.672837.png 1305031955.685832 depth/1305031955.685832.png +1305031955.704890 rgb/1305031955.704890.png 1305031955.719498 depth/1305031955.719498.png +1305031955.736903 rgb/1305031955.736903.png 1305031955.751498 depth/1305031955.751498.png +1305031955.772963 rgb/1305031955.772963.png 1305031955.784581 depth/1305031955.784581.png +1305031955.804902 rgb/1305031955.804902.png 1305031955.820489 depth/1305031955.820489.png +1305031955.837019 rgb/1305031955.837019.png 1305031955.851625 depth/1305031955.851625.png +1305031955.872917 rgb/1305031955.872917.png 1305031955.887875 depth/1305031955.887875.png +1305031955.904911 rgb/1305031955.904911.png 1305031955.921521 depth/1305031955.921521.png +1305031955.937291 rgb/1305031955.937291.png 1305031955.951838 depth/1305031955.951838.png +1305031955.973194 rgb/1305031955.973194.png 1305031955.987663 depth/1305031955.987663.png +1305031956.004870 rgb/1305031956.004870.png 1305031956.020120 depth/1305031956.020120.png +1305031956.036937 rgb/1305031956.036937.png 1305031956.050008 depth/1305031956.050008.png +1305031956.073037 rgb/1305031956.073037.png 1305031956.087830 depth/1305031956.087830.png +1305031956.104901 rgb/1305031956.104901.png 1305031956.119493 depth/1305031956.119493.png diff --git a/Examples/RGB-D/associations/fr1_xyz.txt b/Examples/RGB-D/associations/fr1_xyz.txt new file mode 100644 index 0000000000..29451f9026 --- /dev/null +++ b/Examples/RGB-D/associations/fr1_xyz.txt @@ -0,0 +1,792 @@ +1305031102.175304 rgb/1305031102.175304.png 1305031102.160407 depth/1305031102.160407.png +1305031102.211214 rgb/1305031102.211214.png 1305031102.226738 depth/1305031102.226738.png +1305031102.275326 rgb/1305031102.275326.png 1305031102.262886 depth/1305031102.262886.png +1305031102.311267 rgb/1305031102.311267.png 1305031102.295279 depth/1305031102.295279.png +1305031102.343233 rgb/1305031102.343233.png 1305031102.329195 depth/1305031102.329195.png +1305031102.375329 rgb/1305031102.375329.png 1305031102.363013 depth/1305031102.363013.png +1305031102.411258 rgb/1305031102.411258.png 1305031102.394772 depth/1305031102.394772.png +1305031102.443271 rgb/1305031102.443271.png 1305031102.427815 depth/1305031102.427815.png +1305031102.475318 rgb/1305031102.475318.png 1305031102.462395 depth/1305031102.462395.png +1305031102.511219 rgb/1305031102.511219.png 1305031102.526330 depth/1305031102.526330.png +1305031102.575286 rgb/1305031102.575286.png 1305031102.562224 depth/1305031102.562224.png +1305031102.611233 rgb/1305031102.611233.png 1305031102.626818 depth/1305031102.626818.png +1305031102.675285 rgb/1305031102.675285.png 1305031102.663273 depth/1305031102.663273.png +1305031102.711263 rgb/1305031102.711263.png 1305031102.695165 depth/1305031102.695165.png +1305031102.743234 rgb/1305031102.743234.png 1305031102.728423 depth/1305031102.728423.png +1305031102.775472 rgb/1305031102.775472.png 1305031102.763549 depth/1305031102.763549.png +1305031102.811232 rgb/1305031102.811232.png 1305031102.794978 depth/1305031102.794978.png +1305031102.843290 rgb/1305031102.843290.png 1305031102.828537 depth/1305031102.828537.png +1305031102.875363 rgb/1305031102.875363.png 1305031102.862808 depth/1305031102.862808.png +1305031102.911185 rgb/1305031102.911185.png 1305031102.926851 depth/1305031102.926851.png +1305031102.975203 rgb/1305031102.975203.png 1305031102.962137 depth/1305031102.962137.png +1305031103.011215 rgb/1305031103.011215.png 1305031102.994164 depth/1305031102.994164.png +1305031103.043227 rgb/1305031103.043227.png 1305031103.027881 depth/1305031103.027881.png +1305031103.075319 rgb/1305031103.075319.png 1305031103.062273 depth/1305031103.062273.png +1305031103.111240 rgb/1305031103.111240.png 1305031103.094040 depth/1305031103.094040.png +1305031103.143318 rgb/1305031103.143318.png 1305031103.129109 depth/1305031103.129109.png +1305031103.175452 rgb/1305031103.175452.png 1305031103.162795 depth/1305031103.162795.png +1305031103.243216 rgb/1305031103.243216.png 1305031103.227845 depth/1305031103.227845.png +1305031103.275370 rgb/1305031103.275370.png 1305031103.262576 depth/1305031103.262576.png +1305031103.311210 rgb/1305031103.311210.png 1305031103.294208 depth/1305031103.294208.png +1305031103.343223 rgb/1305031103.343223.png 1305031103.327550 depth/1305031103.327550.png +1305031103.375327 rgb/1305031103.375327.png 1305031103.362405 depth/1305031103.362405.png +1305031103.411260 rgb/1305031103.411260.png 1305031103.394162 depth/1305031103.394162.png +1305031103.443280 rgb/1305031103.443280.png 1305031103.428437 depth/1305031103.428437.png +1305031103.475274 rgb/1305031103.475274.png 1305031103.463886 depth/1305031103.463886.png +1305031103.511333 rgb/1305031103.511333.png 1305031103.494472 depth/1305031103.494472.png +1305031103.543444 rgb/1305031103.543444.png 1305031103.531502 depth/1305031103.531502.png +1305031103.575474 rgb/1305031103.575474.png 1305031103.562651 depth/1305031103.562651.png +1305031103.611223 rgb/1305031103.611223.png 1305031103.595310 depth/1305031103.595310.png +1305031103.643445 rgb/1305031103.643445.png 1305031103.631376 depth/1305031103.631376.png +1305031103.675523 rgb/1305031103.675523.png 1305031103.663594 depth/1305031103.663594.png +1305031103.711610 rgb/1305031103.711610.png 1305031103.694695 depth/1305031103.694695.png +1305031103.743326 rgb/1305031103.743326.png 1305031103.731542 depth/1305031103.731542.png +1305031103.775342 rgb/1305031103.775342.png 1305031103.762865 depth/1305031103.762865.png +1305031103.811242 rgb/1305031103.811242.png 1305031103.794329 depth/1305031103.794329.png +1305031103.843251 rgb/1305031103.843251.png 1305031103.830367 depth/1305031103.830367.png +1305031103.875361 rgb/1305031103.875361.png 1305031103.862379 depth/1305031103.862379.png +1305031103.911221 rgb/1305031103.911221.png 1305031103.894237 depth/1305031103.894237.png +1305031103.943211 rgb/1305031103.943211.png 1305031103.930503 depth/1305031103.930503.png +1305031103.975373 rgb/1305031103.975373.png 1305031103.962461 depth/1305031103.962461.png +1305031104.011232 rgb/1305031104.011232.png 1305031103.994365 depth/1305031103.994365.png +1305031104.043249 rgb/1305031104.043249.png 1305031104.030279 depth/1305031104.030279.png +1305031104.075425 rgb/1305031104.075425.png 1305031104.062542 depth/1305031104.062542.png +1305031104.111235 rgb/1305031104.111235.png 1305031104.095305 depth/1305031104.095305.png +1305031104.143230 rgb/1305031104.143230.png 1305031104.131292 depth/1305031104.131292.png +1305031104.175424 rgb/1305031104.175424.png 1305031104.163440 depth/1305031104.163440.png +1305031104.211283 rgb/1305031104.211283.png 1305031104.194053 depth/1305031104.194053.png +1305031104.243196 rgb/1305031104.243196.png 1305031104.227247 depth/1305031104.227247.png +1305031104.275546 rgb/1305031104.275546.png 1305031104.263335 depth/1305031104.263335.png +1305031104.311219 rgb/1305031104.311219.png 1305031104.294957 depth/1305031104.294957.png +1305031104.343342 rgb/1305031104.343342.png 1305031104.331403 depth/1305031104.331403.png +1305031104.375837 rgb/1305031104.375837.png 1305031104.363345 depth/1305031104.363345.png +1305031104.411509 rgb/1305031104.411509.png 1305031104.395019 depth/1305031104.395019.png +1305031104.443288 rgb/1305031104.443288.png 1305031104.431435 depth/1305031104.431435.png +1305031104.475456 rgb/1305031104.475456.png 1305031104.463413 depth/1305031104.463413.png +1305031104.511329 rgb/1305031104.511329.png 1305031104.495673 depth/1305031104.495673.png +1305031104.543368 rgb/1305031104.543368.png 1305031104.531450 depth/1305031104.531450.png +1305031104.575343 rgb/1305031104.575343.png 1305031104.563149 depth/1305031104.563149.png +1305031104.611336 rgb/1305031104.611336.png 1305031104.595033 depth/1305031104.595033.png +1305031104.643243 rgb/1305031104.643243.png 1305031104.631368 depth/1305031104.631368.png +1305031104.675525 rgb/1305031104.675525.png 1305031104.659863 depth/1305031104.659863.png +1305031104.711277 rgb/1305031104.711277.png 1305031104.695185 depth/1305031104.695185.png +1305031104.743280 rgb/1305031104.743280.png 1305031104.730936 depth/1305031104.730936.png +1305031104.775327 rgb/1305031104.775327.png 1305031104.763178 depth/1305031104.763178.png +1305031104.811465 rgb/1305031104.811465.png 1305031104.799499 depth/1305031104.799499.png +1305031104.843258 rgb/1305031104.843258.png 1305031104.830961 depth/1305031104.830961.png +1305031104.875350 rgb/1305031104.875350.png 1305031104.863256 depth/1305031104.863256.png +1305031104.911534 rgb/1305031104.911534.png 1305031104.899165 depth/1305031104.899165.png +1305031104.943262 rgb/1305031104.943262.png 1305031104.931091 depth/1305031104.931091.png +1305031104.975202 rgb/1305031104.975202.png 1305031104.959750 depth/1305031104.959750.png +1305031105.011290 rgb/1305031105.011290.png 1305031104.998342 depth/1305031104.998342.png +1305031105.043373 rgb/1305031105.043373.png 1305031105.030427 depth/1305031105.030427.png +1305031105.075320 rgb/1305031105.075320.png 1305031105.062445 depth/1305031105.062445.png +1305031105.111299 rgb/1305031105.111299.png 1305031105.097639 depth/1305031105.097639.png +1305031105.143106 rgb/1305031105.143106.png 1305031105.130269 depth/1305031105.130269.png +1305031105.175159 rgb/1305031105.175159.png 1305031105.159979 depth/1305031105.159979.png +1305031105.211268 rgb/1305031105.211268.png 1305031105.198212 depth/1305031105.198212.png +1305031105.243270 rgb/1305031105.243270.png 1305031105.228250 depth/1305031105.228250.png +1305031105.275288 rgb/1305031105.275288.png 1305031105.262389 depth/1305031105.262389.png +1305031105.311290 rgb/1305031105.311290.png 1305031105.298501 depth/1305031105.298501.png +1305031105.343302 rgb/1305031105.343302.png 1305031105.328878 depth/1305031105.328878.png +1305031105.375338 rgb/1305031105.375338.png 1305031105.362286 depth/1305031105.362286.png +1305031105.411286 rgb/1305031105.411286.png 1305031105.398191 depth/1305031105.398191.png +1305031105.443316 rgb/1305031105.443316.png 1305031105.430336 depth/1305031105.430336.png +1305031105.475280 rgb/1305031105.475280.png 1305031105.461421 depth/1305031105.461421.png +1305031105.511332 rgb/1305031105.511332.png 1305031105.497931 depth/1305031105.497931.png +1305031105.543282 rgb/1305031105.543282.png 1305031105.529583 depth/1305031105.529583.png +1305031105.575449 rgb/1305031105.575449.png 1305031105.562109 depth/1305031105.562109.png +1305031105.611378 rgb/1305031105.611378.png 1305031105.597193 depth/1305031105.597193.png +1305031105.643273 rgb/1305031105.643273.png 1305031105.659104 depth/1305031105.659104.png +1305031105.711309 rgb/1305031105.711309.png 1305031105.698235 depth/1305031105.698235.png +1305031105.743312 rgb/1305031105.743312.png 1305031105.730336 depth/1305031105.730336.png +1305031105.775339 rgb/1305031105.775339.png 1305031105.762384 depth/1305031105.762384.png +1305031105.811283 rgb/1305031105.811283.png 1305031105.798056 depth/1305031105.798056.png +1305031105.843271 rgb/1305031105.843271.png 1305031105.830008 depth/1305031105.830008.png +1305031105.875337 rgb/1305031105.875337.png 1305031105.862238 depth/1305031105.862238.png +1305031105.911262 rgb/1305031105.911262.png 1305031105.898018 depth/1305031105.898018.png +1305031105.943272 rgb/1305031105.943272.png 1305031105.929855 depth/1305031105.929855.png +1305031105.975329 rgb/1305031105.975329.png 1305031105.966193 depth/1305031105.966193.png +1305031106.011285 rgb/1305031106.011285.png 1305031105.998271 depth/1305031105.998271.png +1305031106.043355 rgb/1305031106.043355.png 1305031106.030147 depth/1305031106.030147.png +1305031106.075330 rgb/1305031106.075330.png 1305031106.066060 depth/1305031106.066060.png +1305031106.111327 rgb/1305031106.111327.png 1305031106.096295 depth/1305031106.096295.png +1305031106.143355 rgb/1305031106.143355.png 1305031106.130445 depth/1305031106.130445.png +1305031106.175534 rgb/1305031106.175534.png 1305031106.166330 depth/1305031106.166330.png +1305031106.211275 rgb/1305031106.211275.png 1305031106.195074 depth/1305031106.195074.png +1305031106.243267 rgb/1305031106.243267.png 1305031106.230058 depth/1305031106.230058.png +1305031106.276385 rgb/1305031106.276385.png 1305031106.265976 depth/1305031106.265976.png +1305031106.311238 rgb/1305031106.311238.png 1305031106.298174 depth/1305031106.298174.png +1305031106.343258 rgb/1305031106.343258.png 1305031106.330215 depth/1305031106.330215.png +1305031106.375388 rgb/1305031106.375388.png 1305031106.366158 depth/1305031106.366158.png +1305031106.411320 rgb/1305031106.411320.png 1305031106.398281 depth/1305031106.398281.png +1305031106.443278 rgb/1305031106.443278.png 1305031106.430639 depth/1305031106.430639.png +1305031106.475345 rgb/1305031106.475345.png 1305031106.466046 depth/1305031106.466046.png +1305031106.511129 rgb/1305031106.511129.png 1305031106.498096 depth/1305031106.498096.png +1305031106.543302 rgb/1305031106.543302.png 1305031106.528267 depth/1305031106.528267.png +1305031106.575282 rgb/1305031106.575282.png 1305031106.564414 depth/1305031106.564414.png +1305031106.611151 rgb/1305031106.611151.png 1305031106.597879 depth/1305031106.597879.png +1305031106.643207 rgb/1305031106.643207.png 1305031106.630776 depth/1305031106.630776.png +1305031106.675279 rgb/1305031106.675279.png 1305031106.667282 depth/1305031106.667282.png +1305031106.711508 rgb/1305031106.711508.png 1305031106.699110 depth/1305031106.699110.png +1305031106.743341 rgb/1305031106.743341.png 1305031106.729550 depth/1305031106.729550.png +1305031106.775390 rgb/1305031106.775390.png 1305031106.767126 depth/1305031106.767126.png +1305031106.811289 rgb/1305031106.811289.png 1305031106.798309 depth/1305031106.798309.png +1305031106.843416 rgb/1305031106.843416.png 1305031106.830652 depth/1305031106.830652.png +1305031106.875905 rgb/1305031106.875905.png 1305031106.866893 depth/1305031106.866893.png +1305031106.911243 rgb/1305031106.911243.png 1305031106.897828 depth/1305031106.897828.png +1305031106.943439 rgb/1305031106.943439.png 1305031106.930797 depth/1305031106.930797.png +1305031106.975547 rgb/1305031106.975547.png 1305031106.967232 depth/1305031106.967232.png +1305031107.011576 rgb/1305031107.011576.png 1305031106.998876 depth/1305031106.998876.png +1305031107.043281 rgb/1305031107.043281.png 1305031107.030348 depth/1305031107.030348.png +1305031107.075432 rgb/1305031107.075432.png 1305031107.066405 depth/1305031107.066405.png +1305031107.111229 rgb/1305031107.111229.png 1305031107.098268 depth/1305031107.098268.png +1305031107.143260 rgb/1305031107.143260.png 1305031107.130308 depth/1305031107.130308.png +1305031107.175399 rgb/1305031107.175399.png 1305031107.165964 depth/1305031107.165964.png +1305031107.211358 rgb/1305031107.211358.png 1305031107.198208 depth/1305031107.198208.png +1305031107.243378 rgb/1305031107.243378.png 1305031107.235026 depth/1305031107.235026.png +1305031107.275398 rgb/1305031107.275398.png 1305031107.267071 depth/1305031107.267071.png +1305031107.311226 rgb/1305031107.311226.png 1305031107.299273 depth/1305031107.299273.png +1305031107.343509 rgb/1305031107.343509.png 1305031107.334800 depth/1305031107.334800.png +1305031107.375413 rgb/1305031107.375413.png 1305031107.367183 depth/1305031107.367183.png +1305031107.411271 rgb/1305031107.411271.png 1305031107.399345 depth/1305031107.399345.png +1305031107.443419 rgb/1305031107.443419.png 1305031107.434926 depth/1305031107.434926.png +1305031107.475377 rgb/1305031107.475377.png 1305031107.467141 depth/1305031107.467141.png +1305031107.511352 rgb/1305031107.511352.png 1305031107.498426 depth/1305031107.498426.png +1305031107.543605 rgb/1305031107.543605.png 1305031107.534830 depth/1305031107.534830.png +1305031107.575454 rgb/1305031107.575454.png 1305031107.567015 depth/1305031107.567015.png +1305031107.611271 rgb/1305031107.611271.png 1305031107.598904 depth/1305031107.598904.png +1305031107.643323 rgb/1305031107.643323.png 1305031107.634944 depth/1305031107.634944.png +1305031107.675568 rgb/1305031107.675568.png 1305031107.667179 depth/1305031107.667179.png +1305031107.711307 rgb/1305031107.711307.png 1305031107.699390 depth/1305031107.699390.png +1305031107.743538 rgb/1305031107.743538.png 1305031107.735041 depth/1305031107.735041.png +1305031107.775802 rgb/1305031107.775802.png 1305031107.767895 depth/1305031107.767895.png +1305031107.811596 rgb/1305031107.811596.png 1305031107.799544 depth/1305031107.799544.png +1305031107.843332 rgb/1305031107.843332.png 1305031107.835751 depth/1305031107.835751.png +1305031107.875358 rgb/1305031107.875358.png 1305031107.863505 depth/1305031107.863505.png +1305031107.911541 rgb/1305031107.911541.png 1305031107.899222 depth/1305031107.899222.png +1305031107.943122 rgb/1305031107.943122.png 1305031107.933609 depth/1305031107.933609.png +1305031107.975807 rgb/1305031107.975807.png 1305031107.964840 depth/1305031107.964840.png +1305031108.011320 rgb/1305031108.011320.png 1305031107.998469 depth/1305031107.998469.png +1305031108.043418 rgb/1305031108.043418.png 1305031108.034824 depth/1305031108.034824.png +1305031108.075352 rgb/1305031108.075352.png 1305031108.067271 depth/1305031108.067271.png +1305031108.111378 rgb/1305031108.111378.png 1305031108.099365 depth/1305031108.099365.png +1305031108.143334 rgb/1305031108.143334.png 1305031108.135281 depth/1305031108.135281.png +1305031108.176058 rgb/1305031108.176058.png 1305031108.167357 depth/1305031108.167357.png +1305031108.211475 rgb/1305031108.211475.png 1305031108.199225 depth/1305031108.199225.png +1305031108.243347 rgb/1305031108.243347.png 1305031108.235213 depth/1305031108.235213.png +1305031108.275358 rgb/1305031108.275358.png 1305031108.267660 depth/1305031108.267660.png +1305031108.311332 rgb/1305031108.311332.png 1305031108.299547 depth/1305031108.299547.png +1305031108.343278 rgb/1305031108.343278.png 1305031108.335019 depth/1305031108.335019.png +1305031108.375410 rgb/1305031108.375410.png 1305031108.367285 depth/1305031108.367285.png +1305031108.411361 rgb/1305031108.411361.png 1305031108.399284 depth/1305031108.399284.png +1305031108.443610 rgb/1305031108.443610.png 1305031108.435023 depth/1305031108.435023.png +1305031108.475471 rgb/1305031108.475471.png 1305031108.467680 depth/1305031108.467680.png +1305031108.511378 rgb/1305031108.511378.png 1305031108.503548 depth/1305031108.503548.png +1305031108.543737 rgb/1305031108.543737.png 1305031108.534811 depth/1305031108.534811.png +1305031108.575414 rgb/1305031108.575414.png 1305031108.567154 depth/1305031108.567154.png +1305031108.611407 rgb/1305031108.611407.png 1305031108.603547 depth/1305031108.603547.png +1305031108.643303 rgb/1305031108.643303.png 1305031108.634212 depth/1305031108.634212.png +1305031108.675375 rgb/1305031108.675375.png 1305031108.667189 depth/1305031108.667189.png +1305031108.711411 rgb/1305031108.711411.png 1305031108.703346 depth/1305031108.703346.png +1305031108.743502 rgb/1305031108.743502.png 1305031108.735052 depth/1305031108.735052.png +1305031108.775493 rgb/1305031108.775493.png 1305031108.767031 depth/1305031108.767031.png +1305031108.811244 rgb/1305031108.811244.png 1305031108.803370 depth/1305031108.803370.png +1305031108.843264 rgb/1305031108.843264.png 1305031108.835163 depth/1305031108.835163.png +1305031108.876515 rgb/1305031108.876515.png 1305031108.867534 depth/1305031108.867534.png +1305031108.911364 rgb/1305031108.911364.png 1305031108.903540 depth/1305031108.903540.png +1305031108.943243 rgb/1305031108.943243.png 1305031108.935116 depth/1305031108.935116.png +1305031108.975268 rgb/1305031108.975268.png 1305031108.967245 depth/1305031108.967245.png +1305031109.011269 rgb/1305031109.011269.png 1305031109.003064 depth/1305031109.003064.png +1305031109.043277 rgb/1305031109.043277.png 1305031109.034955 depth/1305031109.034955.png +1305031109.075410 rgb/1305031109.075410.png 1305031109.067091 depth/1305031109.067091.png +1305031109.111282 rgb/1305031109.111282.png 1305031109.103294 depth/1305031109.103294.png +1305031109.143334 rgb/1305031109.143334.png 1305031109.134968 depth/1305031109.134968.png +1305031109.175464 rgb/1305031109.175464.png 1305031109.165848 depth/1305031109.165848.png +1305031109.211379 rgb/1305031109.211379.png 1305031109.203388 depth/1305031109.203388.png +1305031109.243290 rgb/1305031109.243290.png 1305031109.234324 depth/1305031109.234324.png +1305031109.275308 rgb/1305031109.275308.png 1305031109.266325 depth/1305031109.266325.png +1305031109.311329 rgb/1305031109.311329.png 1305031109.303457 depth/1305031109.303457.png +1305031109.343248 rgb/1305031109.343248.png 1305031109.334602 depth/1305031109.334602.png +1305031109.375397 rgb/1305031109.375397.png 1305031109.364882 depth/1305031109.364882.png +1305031109.411329 rgb/1305031109.411329.png 1305031109.403386 depth/1305031109.403386.png +1305031109.443302 rgb/1305031109.443302.png 1305031109.434469 depth/1305031109.434469.png +1305031109.475363 rgb/1305031109.475363.png 1305031109.467362 depth/1305031109.467362.png +1305031109.511273 rgb/1305031109.511273.png 1305031109.503193 depth/1305031109.503193.png +1305031109.543294 rgb/1305031109.543294.png 1305031109.535715 depth/1305031109.535715.png +1305031109.575362 rgb/1305031109.575362.png 1305031109.567452 depth/1305031109.567452.png +1305031109.611310 rgb/1305031109.611310.png 1305031109.603601 depth/1305031109.603601.png +1305031109.643229 rgb/1305031109.643229.png 1305031109.635323 depth/1305031109.635323.png +1305031109.675263 rgb/1305031109.675263.png 1305031109.667570 depth/1305031109.667570.png +1305031109.711312 rgb/1305031109.711312.png 1305031109.703265 depth/1305031109.703265.png +1305031109.743274 rgb/1305031109.743274.png 1305031109.735059 depth/1305031109.735059.png +1305031109.775277 rgb/1305031109.775277.png 1305031109.767470 depth/1305031109.767470.png +1305031109.811371 rgb/1305031109.811371.png 1305031109.803396 depth/1305031109.803396.png +1305031109.843296 rgb/1305031109.843296.png 1305031109.834910 depth/1305031109.834910.png +1305031109.875306 rgb/1305031109.875306.png 1305031109.871271 depth/1305031109.871271.png +1305031109.911265 rgb/1305031109.911265.png 1305031109.900535 depth/1305031109.900535.png +1305031109.943299 rgb/1305031109.943299.png 1305031109.934960 depth/1305031109.934960.png +1305031109.975258 rgb/1305031109.975258.png 1305031109.970213 depth/1305031109.970213.png +1305031110.011256 rgb/1305031110.011256.png 1305031109.999657 depth/1305031109.999657.png +1305031110.043299 rgb/1305031110.043299.png 1305031110.031356 depth/1305031110.031356.png +1305031110.075319 rgb/1305031110.075319.png 1305031110.068125 depth/1305031110.068125.png +1305031110.111325 rgb/1305031110.111325.png 1305031110.101397 depth/1305031110.101397.png +1305031110.143432 rgb/1305031110.143432.png 1305031110.132317 depth/1305031110.132317.png +1305031110.175641 rgb/1305031110.175641.png 1305031110.168323 depth/1305031110.168323.png +1305031110.211637 rgb/1305031110.211637.png 1305031110.203162 depth/1305031110.203162.png +1305031110.243323 rgb/1305031110.243323.png 1305031110.234909 depth/1305031110.234909.png +1305031110.279321 rgb/1305031110.279321.png 1305031110.271394 depth/1305031110.271394.png +1305031110.311404 rgb/1305031110.311404.png 1305031110.303648 depth/1305031110.303648.png +1305031110.343355 rgb/1305031110.343355.png 1305031110.331570 depth/1305031110.331570.png +1305031110.379281 rgb/1305031110.379281.png 1305031110.371607 depth/1305031110.371607.png +1305031110.411469 rgb/1305031110.411469.png 1305031110.403480 depth/1305031110.403480.png +1305031110.443260 rgb/1305031110.443260.png 1305031110.435647 depth/1305031110.435647.png +1305031110.479331 rgb/1305031110.479331.png 1305031110.470588 depth/1305031110.470588.png +1305031110.511429 rgb/1305031110.511429.png 1305031110.502539 depth/1305031110.502539.png +1305031110.543408 rgb/1305031110.543408.png 1305031110.534532 depth/1305031110.534532.png +1305031110.579426 rgb/1305031110.579426.png 1305031110.571676 depth/1305031110.571676.png +1305031110.611307 rgb/1305031110.611307.png 1305031110.604289 depth/1305031110.604289.png +1305031110.643418 rgb/1305031110.643418.png 1305031110.635485 depth/1305031110.635485.png +1305031110.679606 rgb/1305031110.679606.png 1305031110.671775 depth/1305031110.671775.png +1305031110.711412 rgb/1305031110.711412.png 1305031110.699957 depth/1305031110.699957.png +1305031110.743249 rgb/1305031110.743249.png 1305031110.735440 depth/1305031110.735440.png +1305031110.779193 rgb/1305031110.779193.png 1305031110.769734 depth/1305031110.769734.png +1305031110.811386 rgb/1305031110.811386.png 1305031110.799684 depth/1305031110.799684.png +1305031110.843218 rgb/1305031110.843218.png 1305031110.835248 depth/1305031110.835248.png +1305031110.879313 rgb/1305031110.879313.png 1305031110.871293 depth/1305031110.871293.png +1305031110.911333 rgb/1305031110.911333.png 1305031110.901900 depth/1305031110.901900.png +1305031110.943862 rgb/1305031110.943862.png 1305031110.938668 depth/1305031110.938668.png +1305031110.979345 rgb/1305031110.979345.png 1305031110.971316 depth/1305031110.971316.png +1305031111.011431 rgb/1305031111.011431.png 1305031111.003669 depth/1305031111.003669.png +1305031111.043327 rgb/1305031111.043327.png 1305031111.039669 depth/1305031111.039669.png +1305031111.079283 rgb/1305031111.079283.png 1305031111.071605 depth/1305031111.071605.png +1305031111.111508 rgb/1305031111.111508.png 1305031111.103658 depth/1305031111.103658.png +1305031111.143257 rgb/1305031111.143257.png 1305031111.139211 depth/1305031111.139211.png +1305031111.179326 rgb/1305031111.179326.png 1305031111.170937 depth/1305031111.170937.png +1305031111.211433 rgb/1305031111.211433.png 1305031111.199395 depth/1305031111.199395.png +1305031111.243236 rgb/1305031111.243236.png 1305031111.236670 depth/1305031111.236670.png +1305031111.279308 rgb/1305031111.279308.png 1305031111.269939 depth/1305031111.269939.png +1305031111.311547 rgb/1305031111.311547.png 1305031111.302311 depth/1305031111.302311.png +1305031111.343397 rgb/1305031111.343397.png 1305031111.339460 depth/1305031111.339460.png +1305031111.379134 rgb/1305031111.379134.png 1305031111.370908 depth/1305031111.370908.png +1305031111.411296 rgb/1305031111.411296.png 1305031111.402911 depth/1305031111.402911.png +1305031111.443386 rgb/1305031111.443386.png 1305031111.438948 depth/1305031111.438948.png +1305031111.479259 rgb/1305031111.479259.png 1305031111.470919 depth/1305031111.470919.png +1305031111.511264 rgb/1305031111.511264.png 1305031111.503531 depth/1305031111.503531.png +1305031111.543250 rgb/1305031111.543250.png 1305031111.539482 depth/1305031111.539482.png +1305031111.579237 rgb/1305031111.579237.png 1305031111.571320 depth/1305031111.571320.png +1305031111.611271 rgb/1305031111.611271.png 1305031111.603391 depth/1305031111.603391.png +1305031111.643395 rgb/1305031111.643395.png 1305031111.639405 depth/1305031111.639405.png +1305031111.679320 rgb/1305031111.679320.png 1305031111.671252 depth/1305031111.671252.png +1305031111.711760 rgb/1305031111.711760.png 1305031111.703791 depth/1305031111.703791.png +1305031111.743386 rgb/1305031111.743386.png 1305031111.739504 depth/1305031111.739504.png +1305031111.779423 rgb/1305031111.779423.png 1305031111.771228 depth/1305031111.771228.png +1305031111.811406 rgb/1305031111.811406.png 1305031111.800077 depth/1305031111.800077.png +1305031111.843299 rgb/1305031111.843299.png 1305031111.839333 depth/1305031111.839333.png +1305031111.879442 rgb/1305031111.879442.png 1305031111.870985 depth/1305031111.870985.png +1305031111.911354 rgb/1305031111.911354.png 1305031111.903356 depth/1305031111.903356.png +1305031111.943300 rgb/1305031111.943300.png 1305031111.939680 depth/1305031111.939680.png +1305031111.979449 rgb/1305031111.979449.png 1305031111.971494 depth/1305031111.971494.png +1305031112.011433 rgb/1305031112.011433.png 1305031112.003596 depth/1305031112.003596.png +1305031112.043270 rgb/1305031112.043270.png 1305031112.039412 depth/1305031112.039412.png +1305031112.079339 rgb/1305031112.079339.png 1305031112.070731 depth/1305031112.070731.png +1305031112.111423 rgb/1305031112.111423.png 1305031112.102495 depth/1305031112.102495.png +1305031112.144342 rgb/1305031112.144342.png 1305031112.139107 depth/1305031112.139107.png +1305031112.179390 rgb/1305031112.179390.png 1305031112.169345 depth/1305031112.169345.png +1305031112.211254 rgb/1305031112.211254.png 1305031112.207733 depth/1305031112.207733.png +1305031112.243369 rgb/1305031112.243369.png 1305031112.235657 depth/1305031112.235657.png +1305031112.279353 rgb/1305031112.279353.png 1305031112.269488 depth/1305031112.269488.png +1305031112.311312 rgb/1305031112.311312.png 1305031112.303591 depth/1305031112.303591.png +1305031112.343323 rgb/1305031112.343323.png 1305031112.335789 depth/1305031112.335789.png +1305031112.379360 rgb/1305031112.379360.png 1305031112.371231 depth/1305031112.371231.png +1305031112.411442 rgb/1305031112.411442.png 1305031112.407491 depth/1305031112.407491.png +1305031112.443391 rgb/1305031112.443391.png 1305031112.439064 depth/1305031112.439064.png +1305031112.479418 rgb/1305031112.479418.png 1305031112.471066 depth/1305031112.471066.png +1305031112.511504 rgb/1305031112.511504.png 1305031112.506669 depth/1305031112.506669.png +1305031112.543212 rgb/1305031112.543212.png 1305031112.538310 depth/1305031112.538310.png +1305031112.579252 rgb/1305031112.579252.png 1305031112.567470 depth/1305031112.567470.png +1305031112.611261 rgb/1305031112.611261.png 1305031112.606742 depth/1305031112.606742.png +1305031112.643246 rgb/1305031112.643246.png 1305031112.639418 depth/1305031112.639418.png +1305031112.679952 rgb/1305031112.679952.png 1305031112.671325 depth/1305031112.671325.png +1305031112.711251 rgb/1305031112.711251.png 1305031112.707325 depth/1305031112.707325.png +1305031112.743245 rgb/1305031112.743245.png 1305031112.739546 depth/1305031112.739546.png +1305031112.779310 rgb/1305031112.779310.png 1305031112.771523 depth/1305031112.771523.png +1305031112.811310 rgb/1305031112.811310.png 1305031112.807539 depth/1305031112.807539.png +1305031112.843286 rgb/1305031112.843286.png 1305031112.839560 depth/1305031112.839560.png +1305031112.879421 rgb/1305031112.879421.png 1305031112.871083 depth/1305031112.871083.png +1305031112.911411 rgb/1305031112.911411.png 1305031112.907246 depth/1305031112.907246.png +1305031112.943321 rgb/1305031112.943321.png 1305031112.939323 depth/1305031112.939323.png +1305031112.979278 rgb/1305031112.979278.png 1305031112.971164 depth/1305031112.971164.png +1305031113.011353 rgb/1305031113.011353.png 1305031113.007166 depth/1305031113.007166.png +1305031113.043231 rgb/1305031113.043231.png 1305031113.039492 depth/1305031113.039492.png +1305031113.079251 rgb/1305031113.079251.png 1305031113.071210 depth/1305031113.071210.png +1305031113.111316 rgb/1305031113.111316.png 1305031113.107662 depth/1305031113.107662.png +1305031113.143306 rgb/1305031113.143306.png 1305031113.139664 depth/1305031113.139664.png +1305031113.179343 rgb/1305031113.179343.png 1305031113.171088 depth/1305031113.171088.png +1305031113.211259 rgb/1305031113.211259.png 1305031113.207181 depth/1305031113.207181.png +1305031113.243227 rgb/1305031113.243227.png 1305031113.239732 depth/1305031113.239732.png +1305031113.279312 rgb/1305031113.279312.png 1305031113.271470 depth/1305031113.271470.png +1305031113.311452 rgb/1305031113.311452.png 1305031113.307323 depth/1305031113.307323.png +1305031113.343252 rgb/1305031113.343252.png 1305031113.339396 depth/1305031113.339396.png +1305031113.379312 rgb/1305031113.379312.png 1305031113.371377 depth/1305031113.371377.png +1305031113.411625 rgb/1305031113.411625.png 1305031113.407351 depth/1305031113.407351.png +1305031113.443266 rgb/1305031113.443266.png 1305031113.439787 depth/1305031113.439787.png +1305031113.479311 rgb/1305031113.479311.png 1305031113.475657 depth/1305031113.475657.png +1305031113.511523 rgb/1305031113.511523.png 1305031113.507987 depth/1305031113.507987.png +1305031113.543242 rgb/1305031113.543242.png 1305031113.539417 depth/1305031113.539417.png +1305031113.579301 rgb/1305031113.579301.png 1305031113.574964 depth/1305031113.574964.png +1305031113.611268 rgb/1305031113.611268.png 1305031113.607216 depth/1305031113.607216.png +1305031113.643222 rgb/1305031113.643222.png 1305031113.638418 depth/1305031113.638418.png +1305031113.679288 rgb/1305031113.679288.png 1305031113.674244 depth/1305031113.674244.png +1305031113.711931 rgb/1305031113.711931.png 1305031113.704256 depth/1305031113.704256.png +1305031113.743590 rgb/1305031113.743590.png 1305031113.736263 depth/1305031113.736263.png +1305031113.779320 rgb/1305031113.779320.png 1305031113.774168 depth/1305031113.774168.png +1305031113.811237 rgb/1305031113.811237.png 1305031113.805795 depth/1305031113.805795.png +1305031113.843295 rgb/1305031113.843295.png 1305031113.838437 depth/1305031113.838437.png +1305031113.879281 rgb/1305031113.879281.png 1305031113.874200 depth/1305031113.874200.png +1305031113.911290 rgb/1305031113.911290.png 1305031113.906361 depth/1305031113.906361.png +1305031113.943291 rgb/1305031113.943291.png 1305031113.938561 depth/1305031113.938561.png +1305031113.979293 rgb/1305031113.979293.png 1305031113.974245 depth/1305031113.974245.png +1305031114.011257 rgb/1305031114.011257.png 1305031114.007082 depth/1305031114.007082.png +1305031114.043301 rgb/1305031114.043301.png 1305031114.038546 depth/1305031114.038546.png +1305031114.079285 rgb/1305031114.079285.png 1305031114.074298 depth/1305031114.074298.png +1305031114.111263 rgb/1305031114.111263.png 1305031114.106402 depth/1305031114.106402.png +1305031114.143284 rgb/1305031114.143284.png 1305031114.138562 depth/1305031114.138562.png +1305031114.179337 rgb/1305031114.179337.png 1305031114.174114 depth/1305031114.174114.png +1305031114.211303 rgb/1305031114.211303.png 1305031114.206255 depth/1305031114.206255.png +1305031114.243337 rgb/1305031114.243337.png 1305031114.238473 depth/1305031114.238473.png +1305031114.279390 rgb/1305031114.279390.png 1305031114.271075 depth/1305031114.271075.png +1305031114.311429 rgb/1305031114.311429.png 1305031114.306710 depth/1305031114.306710.png +1305031114.343331 rgb/1305031114.343331.png 1305031114.338919 depth/1305031114.338919.png +1305031114.379320 rgb/1305031114.379320.png 1305031114.374307 depth/1305031114.374307.png +1305031114.411397 rgb/1305031114.411397.png 1305031114.406591 depth/1305031114.406591.png +1305031114.443345 rgb/1305031114.443345.png 1305031114.438540 depth/1305031114.438540.png +1305031114.479332 rgb/1305031114.479332.png 1305031114.474489 depth/1305031114.474489.png +1305031114.511266 rgb/1305031114.511266.png 1305031114.506573 depth/1305031114.506573.png +1305031114.543236 rgb/1305031114.543236.png 1305031114.539953 depth/1305031114.539953.png +1305031114.579237 rgb/1305031114.579237.png 1305031114.575185 depth/1305031114.575185.png +1305031114.611391 rgb/1305031114.611391.png 1305031114.607560 depth/1305031114.607560.png +1305031114.644136 rgb/1305031114.644136.png 1305031114.644150 depth/1305031114.644150.png +1305031114.679251 rgb/1305031114.679251.png 1305031114.675655 depth/1305031114.675655.png +1305031114.711306 rgb/1305031114.711306.png 1305031114.706141 depth/1305031114.706141.png +1305031114.743200 rgb/1305031114.743200.png 1305031114.743276 depth/1305031114.743276.png +1305031114.779289 rgb/1305031114.779289.png 1305031114.774847 depth/1305031114.774847.png +1305031114.811303 rgb/1305031114.811303.png 1305031114.807310 depth/1305031114.807310.png +1305031114.843208 rgb/1305031114.843208.png 1305031114.842137 depth/1305031114.842137.png +1305031114.879281 rgb/1305031114.879281.png 1305031114.875056 depth/1305031114.875056.png +1305031114.912879 rgb/1305031114.912879.png 1305031114.907504 depth/1305031114.907504.png +1305031114.943234 rgb/1305031114.943234.png 1305031114.943264 depth/1305031114.943264.png +1305031114.979280 rgb/1305031114.979280.png 1305031114.975411 depth/1305031114.975411.png +1305031115.011300 rgb/1305031115.011300.png 1305031115.007179 depth/1305031115.007179.png +1305031115.043508 rgb/1305031115.043508.png 1305031115.043530 depth/1305031115.043530.png +1305031115.079238 rgb/1305031115.079238.png 1305031115.071577 depth/1305031115.071577.png +1305031115.111230 rgb/1305031115.111230.png 1305031115.107074 depth/1305031115.107074.png +1305031115.143275 rgb/1305031115.143275.png 1305031115.143294 depth/1305031115.143294.png +1305031115.179440 rgb/1305031115.179440.png 1305031115.172642 depth/1305031115.172642.png +1305031115.211374 rgb/1305031115.211374.png 1305031115.206453 depth/1305031115.206453.png +1305031115.243297 rgb/1305031115.243297.png 1305031115.240975 depth/1305031115.240975.png +1305031115.279966 rgb/1305031115.279966.png 1305031115.273468 depth/1305031115.273468.png +1305031115.311704 rgb/1305031115.311704.png 1305031115.305534 depth/1305031115.305534.png +1305031115.343235 rgb/1305031115.343235.png 1305031115.343426 depth/1305031115.343426.png +1305031115.379166 rgb/1305031115.379166.png 1305031115.375054 depth/1305031115.375054.png +1305031115.411237 rgb/1305031115.411237.png 1305031115.406164 depth/1305031115.406164.png +1305031115.443159 rgb/1305031115.443159.png 1305031115.443040 depth/1305031115.443040.png +1305031115.479241 rgb/1305031115.479241.png 1305031115.474863 depth/1305031115.474863.png +1305031115.511253 rgb/1305031115.511253.png 1305031115.507440 depth/1305031115.507440.png +1305031115.543604 rgb/1305031115.543604.png 1305031115.543620 depth/1305031115.543620.png +1305031115.579315 rgb/1305031115.579315.png 1305031115.575290 depth/1305031115.575290.png +1305031115.611424 rgb/1305031115.611424.png 1305031115.607428 depth/1305031115.607428.png +1305031115.643254 rgb/1305031115.643254.png 1305031115.643254 depth/1305031115.643254.png +1305031115.679241 rgb/1305031115.679241.png 1305031115.675106 depth/1305031115.675106.png +1305031115.711320 rgb/1305031115.711320.png 1305031115.706301 depth/1305031115.706301.png +1305031115.743250 rgb/1305031115.743250.png 1305031115.742905 depth/1305031115.742905.png +1305031115.779425 rgb/1305031115.779425.png 1305031115.774329 depth/1305031115.774329.png +1305031115.811277 rgb/1305031115.811277.png 1305031115.806425 depth/1305031115.806425.png +1305031115.843224 rgb/1305031115.843224.png 1305031115.841936 depth/1305031115.841936.png +1305031115.879198 rgb/1305031115.879198.png 1305031115.875347 depth/1305031115.875347.png +1305031115.911118 rgb/1305031115.911118.png 1305031115.910716 depth/1305031115.910716.png +1305031115.943311 rgb/1305031115.943311.png 1305031115.942015 depth/1305031115.942015.png +1305031115.980740 rgb/1305031115.980740.png 1305031115.973799 depth/1305031115.973799.png +1305031116.011379 rgb/1305031116.011379.png 1305031116.010843 depth/1305031116.010843.png +1305031116.043164 rgb/1305031116.043164.png 1305031116.042618 depth/1305031116.042618.png +1305031116.080030 rgb/1305031116.080030.png 1305031116.071527 depth/1305031116.071527.png +1305031116.111300 rgb/1305031116.111300.png 1305031116.108247 depth/1305031116.108247.png +1305031116.143441 rgb/1305031116.143441.png 1305031116.143447 depth/1305031116.143447.png +1305031116.179572 rgb/1305031116.179572.png 1305031116.174891 depth/1305031116.174891.png +1305031116.211299 rgb/1305031116.211299.png 1305031116.211320 depth/1305031116.211320.png +1305031116.243320 rgb/1305031116.243320.png 1305031116.242720 depth/1305031116.242720.png +1305031116.279385 rgb/1305031116.279385.png 1305031116.274421 depth/1305031116.274421.png +1305031116.311336 rgb/1305031116.311336.png 1305031116.310686 depth/1305031116.310686.png +1305031116.343292 rgb/1305031116.343292.png 1305031116.342459 depth/1305031116.342459.png +1305031116.379384 rgb/1305031116.379384.png 1305031116.374490 depth/1305031116.374490.png +1305031116.411333 rgb/1305031116.411333.png 1305031116.409631 depth/1305031116.409631.png +1305031116.443369 rgb/1305031116.443369.png 1305031116.442496 depth/1305031116.442496.png +1305031116.479850 rgb/1305031116.479850.png 1305031116.473394 depth/1305031116.473394.png +1305031116.511205 rgb/1305031116.511205.png 1305031116.510576 depth/1305031116.510576.png +1305031116.543262 rgb/1305031116.543262.png 1305031116.542695 depth/1305031116.542695.png +1305031116.579313 rgb/1305031116.579313.png 1305031116.574389 depth/1305031116.574389.png +1305031116.611261 rgb/1305031116.611261.png 1305031116.610891 depth/1305031116.610891.png +1305031116.643355 rgb/1305031116.643355.png 1305031116.642664 depth/1305031116.642664.png +1305031116.679281 rgb/1305031116.679281.png 1305031116.674523 depth/1305031116.674523.png +1305031116.711634 rgb/1305031116.711634.png 1305031116.710942 depth/1305031116.710942.png +1305031116.743291 rgb/1305031116.743291.png 1305031116.740575 depth/1305031116.740575.png +1305031116.779298 rgb/1305031116.779298.png 1305031116.775059 depth/1305031116.775059.png +1305031116.811318 rgb/1305031116.811318.png 1305031116.811343 depth/1305031116.811343.png +1305031116.846089 rgb/1305031116.846089.png 1305031116.840370 depth/1305031116.840370.png +1305031116.880165 rgb/1305031116.880165.png 1305031116.871726 depth/1305031116.871726.png +1305031116.912044 rgb/1305031116.912044.png 1305031116.907955 depth/1305031116.907955.png +1305031116.943296 rgb/1305031116.943296.png 1305031116.940626 depth/1305031116.940626.png +1305031116.979351 rgb/1305031116.979351.png 1305031116.974656 depth/1305031116.974656.png +1305031117.011382 rgb/1305031117.011382.png 1305031117.008812 depth/1305031117.008812.png +1305031117.043261 rgb/1305031117.043261.png 1305031117.042065 depth/1305031117.042065.png +1305031117.079520 rgb/1305031117.079520.png 1305031117.071181 depth/1305031117.071181.png +1305031117.111238 rgb/1305031117.111238.png 1305031117.110454 depth/1305031117.110454.png +1305031117.143218 rgb/1305031117.143218.png 1305031117.142383 depth/1305031117.142383.png +1305031117.179264 rgb/1305031117.179264.png 1305031117.175059 depth/1305031117.175059.png +1305031117.211361 rgb/1305031117.211361.png 1305031117.207753 depth/1305031117.207753.png +1305031117.243277 rgb/1305031117.243277.png 1305031117.241340 depth/1305031117.241340.png +1305031117.279299 rgb/1305031117.279299.png 1305031117.276516 depth/1305031117.276516.png +1305031117.311200 rgb/1305031117.311200.png 1305031117.310121 depth/1305031117.310121.png +1305031117.343243 rgb/1305031117.343243.png 1305031117.341044 depth/1305031117.341044.png +1305031117.379454 rgb/1305031117.379454.png 1305031117.375067 depth/1305031117.375067.png +1305031117.411221 rgb/1305031117.411221.png 1305031117.408538 depth/1305031117.408538.png +1305031117.443274 rgb/1305031117.443274.png 1305031117.442208 depth/1305031117.442208.png +1305031117.479403 rgb/1305031117.479403.png 1305031117.475651 depth/1305031117.475651.png +1305031117.511325 rgb/1305031117.511325.png 1305031117.508882 depth/1305031117.508882.png +1305031117.544285 rgb/1305031117.544285.png 1305031117.539736 depth/1305031117.539736.png +1305031117.579155 rgb/1305031117.579155.png 1305031117.577860 depth/1305031117.577860.png +1305031117.611159 rgb/1305031117.611159.png 1305031117.607777 depth/1305031117.607777.png +1305031117.643252 rgb/1305031117.643252.png 1305031117.643284 depth/1305031117.643284.png +1305031117.679262 rgb/1305031117.679262.png 1305031117.675483 depth/1305031117.675483.png +1305031117.711184 rgb/1305031117.711184.png 1305031117.711215 depth/1305031117.711215.png +1305031117.743184 rgb/1305031117.743184.png 1305031117.742995 depth/1305031117.742995.png +1305031117.779467 rgb/1305031117.779467.png 1305031117.778969 depth/1305031117.778969.png +1305031117.811320 rgb/1305031117.811320.png 1305031117.811060 depth/1305031117.811060.png +1305031117.843291 rgb/1305031117.843291.png 1305031117.843307 depth/1305031117.843307.png +1305031117.879451 rgb/1305031117.879451.png 1305031117.879467 depth/1305031117.879467.png +1305031117.911407 rgb/1305031117.911407.png 1305031117.908762 depth/1305031117.908762.png +1305031117.943253 rgb/1305031117.943253.png 1305031117.943272 depth/1305031117.943272.png +1305031117.979228 rgb/1305031117.979228.png 1305031117.979263 depth/1305031117.979263.png +1305031118.011228 rgb/1305031118.011228.png 1305031118.011013 depth/1305031118.011013.png +1305031118.043521 rgb/1305031118.043521.png 1305031118.043549 depth/1305031118.043549.png +1305031118.079334 rgb/1305031118.079334.png 1305031118.079369 depth/1305031118.079369.png +1305031118.111217 rgb/1305031118.111217.png 1305031118.110863 depth/1305031118.110863.png +1305031118.143256 rgb/1305031118.143256.png 1305031118.142285 depth/1305031118.142285.png +1305031118.179323 rgb/1305031118.179323.png 1305031118.178170 depth/1305031118.178170.png +1305031118.211202 rgb/1305031118.211202.png 1305031118.210782 depth/1305031118.210782.png +1305031118.243173 rgb/1305031118.243173.png 1305031118.242948 depth/1305031118.242948.png +1305031118.279194 rgb/1305031118.279194.png 1305031118.278991 depth/1305031118.278991.png +1305031118.311299 rgb/1305031118.311299.png 1305031118.310731 depth/1305031118.310731.png +1305031118.343324 rgb/1305031118.343324.png 1305031118.342079 depth/1305031118.342079.png +1305031118.379208 rgb/1305031118.379208.png 1305031118.377003 depth/1305031118.377003.png +1305031118.411296 rgb/1305031118.411296.png 1305031118.408818 depth/1305031118.408818.png +1305031118.445692 rgb/1305031118.445692.png 1305031118.445703 depth/1305031118.445703.png +1305031118.479285 rgb/1305031118.479285.png 1305031118.477869 depth/1305031118.477869.png +1305031118.511255 rgb/1305031118.511255.png 1305031118.510201 depth/1305031118.510201.png +1305031118.544414 rgb/1305031118.544414.png 1305031118.545199 depth/1305031118.545199.png +1305031118.579285 rgb/1305031118.579285.png 1305031118.576377 depth/1305031118.576377.png +1305031118.616142 rgb/1305031118.616142.png 1305031118.610869 depth/1305031118.610869.png +1305031118.645325 rgb/1305031118.645325.png 1305031118.645331 depth/1305031118.645331.png +1305031118.679295 rgb/1305031118.679295.png 1305031118.675082 depth/1305031118.675082.png +1305031118.711421 rgb/1305031118.711421.png 1305031118.710140 depth/1305031118.710140.png +1305031118.746770 rgb/1305031118.746770.png 1305031118.746801 depth/1305031118.746801.png +1305031118.779277 rgb/1305031118.779277.png 1305031118.778790 depth/1305031118.778790.png +1305031118.811221 rgb/1305031118.811221.png 1305031118.810703 depth/1305031118.810703.png +1305031118.846753 rgb/1305031118.846753.png 1305031118.846774 depth/1305031118.846774.png +1305031118.879208 rgb/1305031118.879208.png 1305031118.875402 depth/1305031118.875402.png +1305031118.911177 rgb/1305031118.911177.png 1305031118.909608 depth/1305031118.909608.png +1305031118.946974 rgb/1305031118.946974.png 1305031118.947009 depth/1305031118.947009.png +1305031118.979374 rgb/1305031118.979374.png 1305031118.979394 depth/1305031118.979394.png +1305031119.011363 rgb/1305031119.011363.png 1305031119.009712 depth/1305031119.009712.png +1305031119.047172 rgb/1305031119.047172.png 1305031119.047180 depth/1305031119.047180.png +1305031119.079223 rgb/1305031119.079223.png 1305031119.078966 depth/1305031119.078966.png +1305031119.111328 rgb/1305031119.111328.png 1305031119.110884 depth/1305031119.110884.png +1305031119.147616 rgb/1305031119.147616.png 1305031119.147629 depth/1305031119.147629.png +1305031119.179226 rgb/1305031119.179226.png 1305031119.179262 depth/1305031119.179262.png +1305031119.211364 rgb/1305031119.211364.png 1305031119.210906 depth/1305031119.210906.png +1305031119.247399 rgb/1305031119.247399.png 1305031119.247660 depth/1305031119.247660.png +1305031119.279212 rgb/1305031119.279212.png 1305031119.279244 depth/1305031119.279244.png +1305031119.311212 rgb/1305031119.311212.png 1305031119.310755 depth/1305031119.310755.png +1305031119.347741 rgb/1305031119.347741.png 1305031119.347750 depth/1305031119.347750.png +1305031119.379239 rgb/1305031119.379239.png 1305031119.378631 depth/1305031119.378631.png +1305031119.411484 rgb/1305031119.411484.png 1305031119.411492 depth/1305031119.411492.png +1305031119.447706 rgb/1305031119.447706.png 1305031119.447726 depth/1305031119.447726.png +1305031119.479267 rgb/1305031119.479267.png 1305031119.477682 depth/1305031119.477682.png +1305031119.511240 rgb/1305031119.511240.png 1305031119.511258 depth/1305031119.511258.png +1305031119.547382 rgb/1305031119.547382.png 1305031119.547414 depth/1305031119.547414.png +1305031119.579559 rgb/1305031119.579559.png 1305031119.579569 depth/1305031119.579569.png +1305031119.615017 rgb/1305031119.615017.png 1305031119.615024 depth/1305031119.615024.png +1305031119.647903 rgb/1305031119.647903.png 1305031119.648889 depth/1305031119.648889.png +1305031119.679208 rgb/1305031119.679208.png 1305031119.675566 depth/1305031119.675566.png +1305031119.715232 rgb/1305031119.715232.png 1305031119.715249 depth/1305031119.715249.png +1305031119.747193 rgb/1305031119.747193.png 1305031119.744886 depth/1305031119.744886.png +1305031119.779169 rgb/1305031119.779169.png 1305031119.778628 depth/1305031119.778628.png +1305031119.814537 rgb/1305031119.814537.png 1305031119.814571 depth/1305031119.814571.png +1305031119.847429 rgb/1305031119.847429.png 1305031119.847445 depth/1305031119.847445.png +1305031119.879214 rgb/1305031119.879214.png 1305031119.879232 depth/1305031119.879232.png +1305031119.911401 rgb/1305031119.911401.png 1305031119.911424 depth/1305031119.911424.png +1305031119.947392 rgb/1305031119.947392.png 1305031119.947462 depth/1305031119.947462.png +1305031119.979537 rgb/1305031119.979537.png 1305031119.979546 depth/1305031119.979546.png +1305031120.015264 rgb/1305031120.015264.png 1305031120.015283 depth/1305031120.015283.png +1305031120.047290 rgb/1305031120.047290.png 1305031120.047310 depth/1305031120.047310.png +1305031120.079418 rgb/1305031120.079418.png 1305031120.075690 depth/1305031120.075690.png +1305031120.115232 rgb/1305031120.115232.png 1305031120.115249 depth/1305031120.115249.png +1305031120.148157 rgb/1305031120.148157.png 1305031120.148175 depth/1305031120.148175.png +1305031120.179246 rgb/1305031120.179246.png 1305031120.179261 depth/1305031120.179261.png +1305031120.215249 rgb/1305031120.215249.png 1305031120.215260 depth/1305031120.215260.png +1305031120.248003 rgb/1305031120.248003.png 1305031120.248018 depth/1305031120.248018.png +1305031120.279430 rgb/1305031120.279430.png 1305031120.279441 depth/1305031120.279441.png +1305031120.315196 rgb/1305031120.315196.png 1305031120.315213 depth/1305031120.315213.png +1305031120.347787 rgb/1305031120.347787.png 1305031120.347797 depth/1305031120.347797.png +1305031120.379437 rgb/1305031120.379437.png 1305031120.379446 depth/1305031120.379446.png +1305031120.415445 rgb/1305031120.415445.png 1305031120.415490 depth/1305031120.415490.png +1305031120.447417 rgb/1305031120.447417.png 1305031120.447433 depth/1305031120.447433.png +1305031120.479432 rgb/1305031120.479432.png 1305031120.475582 depth/1305031120.475582.png +1305031120.514819 rgb/1305031120.514819.png 1305031120.514877 depth/1305031120.514877.png +1305031120.547736 rgb/1305031120.547736.png 1305031120.547807 depth/1305031120.547807.png +1305031120.579551 rgb/1305031120.579551.png 1305031120.579559 depth/1305031120.579559.png +1305031120.615236 rgb/1305031120.615236.png 1305031120.615271 depth/1305031120.615271.png +1305031120.647354 rgb/1305031120.647354.png 1305031120.646607 depth/1305031120.646607.png +1305031120.679318 rgb/1305031120.679318.png 1305031120.678467 depth/1305031120.678467.png +1305031120.714522 rgb/1305031120.714522.png 1305031120.714553 depth/1305031120.714553.png +1305031120.747369 rgb/1305031120.747369.png 1305031120.747396 depth/1305031120.747396.png +1305031120.779894 rgb/1305031120.779894.png 1305031120.779908 depth/1305031120.779908.png +1305031120.814944 rgb/1305031120.814944.png 1305031120.814905 depth/1305031120.814905.png +1305031120.847921 rgb/1305031120.847921.png 1305031120.847942 depth/1305031120.847942.png +1305031120.883435 rgb/1305031120.883435.png 1305031120.883454 depth/1305031120.883454.png +1305031120.915444 rgb/1305031120.915444.png 1305031120.915454 depth/1305031120.915454.png +1305031120.947488 rgb/1305031120.947488.png 1305031120.947509 depth/1305031120.947509.png +1305031120.983366 rgb/1305031120.983366.png 1305031120.983390 depth/1305031120.983390.png +1305031121.015019 rgb/1305031121.015019.png 1305031121.015029 depth/1305031121.015029.png +1305031121.047498 rgb/1305031121.047498.png 1305031121.047755 depth/1305031121.047755.png +1305031121.083099 rgb/1305031121.083099.png 1305031121.083117 depth/1305031121.083117.png +1305031121.114696 rgb/1305031121.114696.png 1305031121.114878 depth/1305031121.114878.png +1305031121.147331 rgb/1305031121.147331.png 1305031121.147355 depth/1305031121.147355.png +1305031121.183271 rgb/1305031121.183271.png 1305031121.183281 depth/1305031121.183281.png +1305031121.211420 rgb/1305031121.211420.png 1305031121.211431 depth/1305031121.211431.png +1305031121.247194 rgb/1305031121.247194.png 1305031121.247201 depth/1305031121.247201.png +1305031121.282876 rgb/1305031121.282876.png 1305031121.282822 depth/1305031121.282822.png +1305031121.313568 rgb/1305031121.313568.png 1305031121.313588 depth/1305031121.313588.png +1305031121.347517 rgb/1305031121.347517.png 1305031121.347540 depth/1305031121.347540.png +1305031121.383226 rgb/1305031121.383226.png 1305031121.383248 depth/1305031121.383248.png +1305031121.414318 rgb/1305031121.414318.png 1305031121.414328 depth/1305031121.414328.png +1305031121.447319 rgb/1305031121.447319.png 1305031121.447024 depth/1305031121.447024.png +1305031121.482964 rgb/1305031121.482964.png 1305031121.483015 depth/1305031121.483015.png +1305031121.514107 rgb/1305031121.514107.png 1305031121.514164 depth/1305031121.514164.png +1305031121.547270 rgb/1305031121.547270.png 1305031121.546810 depth/1305031121.546810.png +1305031121.583204 rgb/1305031121.583204.png 1305031121.583213 depth/1305031121.583213.png +1305031121.614700 rgb/1305031121.614700.png 1305031121.614719 depth/1305031121.614719.png +1305031121.647183 rgb/1305031121.647183.png 1305031121.646966 depth/1305031121.646966.png +1305031121.683200 rgb/1305031121.683200.png 1305031121.683211 depth/1305031121.683211.png +1305031121.714520 rgb/1305031121.714520.png 1305031121.714528 depth/1305031121.714528.png +1305031121.747145 rgb/1305031121.747145.png 1305031121.746484 depth/1305031121.746484.png +1305031121.782835 rgb/1305031121.782835.png 1305031121.782871 depth/1305031121.782871.png +1305031121.811540 rgb/1305031121.811540.png 1305031121.811545 depth/1305031121.811545.png +1305031121.847335 rgb/1305031121.847335.png 1305031121.846870 depth/1305031121.846870.png +1305031121.882060 rgb/1305031121.882060.png 1305031121.882123 depth/1305031121.882123.png +1305031121.914931 rgb/1305031121.914931.png 1305031121.914943 depth/1305031121.914943.png +1305031121.947288 rgb/1305031121.947288.png 1305031121.947318 depth/1305031121.947318.png +1305031121.982926 rgb/1305031121.982926.png 1305031121.982935 depth/1305031121.982935.png +1305031122.014256 rgb/1305031122.014256.png 1305031122.014424 depth/1305031122.014424.png +1305031122.047306 rgb/1305031122.047306.png 1305031122.046908 depth/1305031122.046908.png +1305031122.082959 rgb/1305031122.082959.png 1305031122.082969 depth/1305031122.082969.png +1305031122.114672 rgb/1305031122.114672.png 1305031122.114688 depth/1305031122.114688.png +1305031122.150725 rgb/1305031122.150725.png 1305031122.150748 depth/1305031122.150748.png +1305031122.183042 rgb/1305031122.183042.png 1305031122.183052 depth/1305031122.183052.png +1305031122.214959 rgb/1305031122.214959.png 1305031122.214969 depth/1305031122.214969.png +1305031122.251319 rgb/1305031122.251319.png 1305031122.251355 depth/1305031122.251355.png +1305031122.283560 rgb/1305031122.283560.png 1305031122.283866 depth/1305031122.283866.png +1305031122.314289 rgb/1305031122.314289.png 1305031122.314309 depth/1305031122.314309.png +1305031122.351327 rgb/1305031122.351327.png 1305031122.351351 depth/1305031122.351351.png +1305031122.382630 rgb/1305031122.382630.png 1305031122.382678 depth/1305031122.382678.png +1305031122.414997 rgb/1305031122.414997.png 1305031122.415008 depth/1305031122.415008.png +1305031122.451257 rgb/1305031122.451257.png 1305031122.451272 depth/1305031122.451272.png +1305031122.483360 rgb/1305031122.483360.png 1305031122.483388 depth/1305031122.483388.png +1305031122.515097 rgb/1305031122.515097.png 1305031122.515135 depth/1305031122.515135.png +1305031122.551490 rgb/1305031122.551490.png 1305031122.551510 depth/1305031122.551510.png +1305031122.583208 rgb/1305031122.583208.png 1305031122.583217 depth/1305031122.583217.png +1305031122.614980 rgb/1305031122.614980.png 1305031122.615017 depth/1305031122.615017.png +1305031122.648788 rgb/1305031122.648788.png 1305031122.648810 depth/1305031122.648810.png +1305031122.683402 rgb/1305031122.683402.png 1305031122.683420 depth/1305031122.683420.png +1305031122.715208 rgb/1305031122.715208.png 1305031122.715219 depth/1305031122.715219.png +1305031122.751298 rgb/1305031122.751298.png 1305031122.751309 depth/1305031122.751309.png +1305031122.783423 rgb/1305031122.783423.png 1305031122.783438 depth/1305031122.783438.png +1305031122.812555 rgb/1305031122.812555.png 1305031122.812565 depth/1305031122.812565.png +1305031122.851418 rgb/1305031122.851418.png 1305031122.851486 depth/1305031122.851486.png +1305031122.883754 rgb/1305031122.883754.png 1305031122.883775 depth/1305031122.883775.png +1305031122.914571 rgb/1305031122.914571.png 1305031122.914585 depth/1305031122.914585.png +1305031122.951341 rgb/1305031122.951341.png 1305031122.951413 depth/1305031122.951413.png +1305031122.982815 rgb/1305031122.982815.png 1305031122.983000 depth/1305031122.983000.png +1305031123.015450 rgb/1305031123.015450.png 1305031123.015462 depth/1305031123.015462.png +1305031123.051827 rgb/1305031123.051827.png 1305031123.051838 depth/1305031123.051838.png +1305031123.082975 rgb/1305031123.082975.png 1305031123.082992 depth/1305031123.082992.png +1305031123.113873 rgb/1305031123.113873.png 1305031123.113939 depth/1305031123.113939.png +1305031123.150822 rgb/1305031123.150822.png 1305031123.150840 depth/1305031123.150840.png +1305031123.182155 rgb/1305031123.182155.png 1305031123.182176 depth/1305031123.182176.png +1305031123.214704 rgb/1305031123.214704.png 1305031123.214724 depth/1305031123.214724.png +1305031123.250618 rgb/1305031123.250618.png 1305031123.250641 depth/1305031123.250641.png +1305031123.282347 rgb/1305031123.282347.png 1305031123.282363 depth/1305031123.282363.png +1305031123.311327 rgb/1305031123.311327.png 1305031123.320992 depth/1305031123.320992.png +1305031123.350481 rgb/1305031123.350481.png 1305031123.350493 depth/1305031123.350493.png +1305031123.382255 rgb/1305031123.382255.png 1305031123.382263 depth/1305031123.382263.png +1305031123.411363 rgb/1305031123.411363.png 1305031123.421343 depth/1305031123.421343.png +1305031123.451255 rgb/1305031123.451255.png 1305031123.451266 depth/1305031123.451266.png +1305031123.483594 rgb/1305031123.483594.png 1305031123.483605 depth/1305031123.483605.png +1305031123.511360 rgb/1305031123.511360.png 1305031123.519725 depth/1305031123.519725.png +1305031123.551513 rgb/1305031123.551513.png 1305031123.551573 depth/1305031123.551573.png +1305031123.579583 rgb/1305031123.579583.png 1305031123.579616 depth/1305031123.579616.png +1305031123.611335 rgb/1305031123.611335.png 1305031123.620387 depth/1305031123.620387.png +1305031123.652411 rgb/1305031123.652411.png 1305031123.652430 depth/1305031123.652430.png +1305031123.683753 rgb/1305031123.683753.png 1305031123.683785 depth/1305031123.683785.png +1305031123.711323 rgb/1305031123.711323.png 1305031123.719975 depth/1305031123.719975.png +1305031123.751723 rgb/1305031123.751723.png 1305031123.751980 depth/1305031123.751980.png +1305031123.783858 rgb/1305031123.783858.png 1305031123.784138 depth/1305031123.784138.png +1305031123.811608 rgb/1305031123.811608.png 1305031123.819696 depth/1305031123.819696.png +1305031123.851444 rgb/1305031123.851444.png 1305031123.851551 depth/1305031123.851551.png +1305031123.883786 rgb/1305031123.883786.png 1305031123.883819 depth/1305031123.883819.png +1305031123.911243 rgb/1305031123.911243.png 1305031123.915794 depth/1305031123.915794.png +1305031123.951442 rgb/1305031123.951442.png 1305031123.951530 depth/1305031123.951530.png +1305031123.983415 rgb/1305031123.983415.png 1305031123.983421 depth/1305031123.983421.png +1305031124.011302 rgb/1305031124.011302.png 1305031124.019737 depth/1305031124.019737.png +1305031124.051505 rgb/1305031124.051505.png 1305031124.051531 depth/1305031124.051531.png +1305031124.083837 rgb/1305031124.083837.png 1305031124.083902 depth/1305031124.083902.png +1305031124.111331 rgb/1305031124.111331.png 1305031124.119669 depth/1305031124.119669.png +1305031124.147446 rgb/1305031124.147446.png 1305031124.147458 depth/1305031124.147458.png +1305031124.182694 rgb/1305031124.182694.png 1305031124.182707 depth/1305031124.182707.png +1305031124.211396 rgb/1305031124.211396.png 1305031124.217179 depth/1305031124.217179.png +1305031124.249327 rgb/1305031124.249327.png 1305031124.249340 depth/1305031124.249340.png +1305031124.282545 rgb/1305031124.282545.png 1305031124.282555 depth/1305031124.282555.png +1305031124.311361 rgb/1305031124.311361.png 1305031124.316782 depth/1305031124.316782.png +1305031124.350354 rgb/1305031124.350354.png 1305031124.350371 depth/1305031124.350371.png +1305031124.382420 rgb/1305031124.382420.png 1305031124.382432 depth/1305031124.382432.png +1305031124.411439 rgb/1305031124.411439.png 1305031124.418555 depth/1305031124.418555.png +1305031124.450245 rgb/1305031124.450245.png 1305031124.450256 depth/1305031124.450256.png +1305031124.480099 rgb/1305031124.480099.png 1305031124.480126 depth/1305031124.480126.png +1305031124.511324 rgb/1305031124.511324.png 1305031124.516737 depth/1305031124.516737.png +1305031124.550437 rgb/1305031124.550437.png 1305031124.550503 depth/1305031124.550503.png +1305031124.579404 rgb/1305031124.579404.png 1305031124.584606 depth/1305031124.584606.png +1305031124.611358 rgb/1305031124.611358.png 1305031124.617653 depth/1305031124.617653.png +1305031124.651271 rgb/1305031124.651271.png 1305031124.651313 depth/1305031124.651313.png +1305031124.679362 rgb/1305031124.679362.png 1305031124.685473 depth/1305031124.685473.png +1305031124.711251 rgb/1305031124.711251.png 1305031124.715791 depth/1305031124.715791.png +1305031124.749890 rgb/1305031124.749890.png 1305031124.749941 depth/1305031124.749941.png +1305031124.779365 rgb/1305031124.779365.png 1305031124.785178 depth/1305031124.785178.png +1305031124.811360 rgb/1305031124.811360.png 1305031124.816641 depth/1305031124.816641.png +1305031124.850535 rgb/1305031124.850535.png 1305031124.850559 depth/1305031124.850559.png +1305031124.879355 rgb/1305031124.879355.png 1305031124.883594 depth/1305031124.883594.png +1305031124.911448 rgb/1305031124.911448.png 1305031124.918770 depth/1305031124.918770.png +1305031124.950730 rgb/1305031124.950730.png 1305031124.950748 depth/1305031124.950748.png +1305031124.979438 rgb/1305031124.979438.png 1305031124.986460 depth/1305031124.986460.png +1305031125.011454 rgb/1305031125.011454.png 1305031125.019467 depth/1305031125.019467.png +1305031125.050763 rgb/1305031125.050763.png 1305031125.050798 depth/1305031125.050798.png +1305031125.079364 rgb/1305031125.079364.png 1305031125.083480 depth/1305031125.083480.png +1305031125.111364 rgb/1305031125.111364.png 1305031125.119029 depth/1305031125.119029.png +1305031125.151013 rgb/1305031125.151013.png 1305031125.151037 depth/1305031125.151037.png +1305031125.179353 rgb/1305031125.179353.png 1305031125.187064 depth/1305031125.187064.png +1305031125.211320 rgb/1305031125.211320.png 1305031125.219018 depth/1305031125.219018.png +1305031125.250632 rgb/1305031125.250632.png 1305031125.250642 depth/1305031125.250642.png +1305031125.279467 rgb/1305031125.279467.png 1305031125.286396 depth/1305031125.286396.png +1305031125.311493 rgb/1305031125.311493.png 1305031125.319140 depth/1305031125.319140.png +1305031125.348880 rgb/1305031125.348880.png 1305031125.348899 depth/1305031125.348899.png +1305031125.379401 rgb/1305031125.379401.png 1305031125.386792 depth/1305031125.386792.png +1305031125.411335 rgb/1305031125.411335.png 1305031125.419574 depth/1305031125.419574.png +1305031125.451195 rgb/1305031125.451195.png 1305031125.451232 depth/1305031125.451232.png +1305031125.479424 rgb/1305031125.479424.png 1305031125.486999 depth/1305031125.486999.png +1305031125.511316 rgb/1305031125.511316.png 1305031125.519354 depth/1305031125.519354.png +1305031125.551020 rgb/1305031125.551020.png 1305031125.551050 depth/1305031125.551050.png +1305031125.579308 rgb/1305031125.579308.png 1305031125.585303 depth/1305031125.585303.png +1305031125.611533 rgb/1305031125.611533.png 1305031125.617870 depth/1305031125.617870.png +1305031125.650575 rgb/1305031125.650575.png 1305031125.650354 depth/1305031125.650354.png +1305031125.679328 rgb/1305031125.679328.png 1305031125.684602 depth/1305031125.684602.png +1305031125.711443 rgb/1305031125.711443.png 1305031125.715669 depth/1305031125.715669.png +1305031125.751260 rgb/1305031125.751260.png 1305031125.751292 depth/1305031125.751292.png +1305031125.779348 rgb/1305031125.779348.png 1305031125.786805 depth/1305031125.786805.png +1305031125.811573 rgb/1305031125.811573.png 1305031125.819450 depth/1305031125.819450.png +1305031125.847412 rgb/1305031125.847412.png 1305031125.854774 depth/1305031125.854774.png +1305031125.879318 rgb/1305031125.879318.png 1305031125.886645 depth/1305031125.886645.png +1305031125.911305 rgb/1305031125.911305.png 1305031125.919334 depth/1305031125.919334.png +1305031125.947343 rgb/1305031125.947343.png 1305031125.955252 depth/1305031125.955252.png +1305031125.979324 rgb/1305031125.979324.png 1305031125.987094 depth/1305031125.987094.png +1305031126.011333 rgb/1305031126.011333.png 1305031126.019572 depth/1305031126.019572.png +1305031126.047324 rgb/1305031126.047324.png 1305031126.055038 depth/1305031126.055038.png +1305031126.079356 rgb/1305031126.079356.png 1305031126.087076 depth/1305031126.087076.png +1305031126.111370 rgb/1305031126.111370.png 1305031126.119452 depth/1305031126.119452.png +1305031126.147432 rgb/1305031126.147432.png 1305031126.155000 depth/1305031126.155000.png +1305031126.179384 rgb/1305031126.179384.png 1305031126.187174 depth/1305031126.187174.png +1305031126.211319 rgb/1305031126.211319.png 1305031126.219473 depth/1305031126.219473.png +1305031126.247298 rgb/1305031126.247298.png 1305031126.255236 depth/1305031126.255236.png +1305031126.279363 rgb/1305031126.279363.png 1305031126.287105 depth/1305031126.287105.png +1305031126.311332 rgb/1305031126.311332.png 1305031126.319787 depth/1305031126.319787.png +1305031126.347363 rgb/1305031126.347363.png 1305031126.355415 depth/1305031126.355415.png +1305031126.379423 rgb/1305031126.379423.png 1305031126.387483 depth/1305031126.387483.png +1305031126.411465 rgb/1305031126.411465.png 1305031126.419793 depth/1305031126.419793.png +1305031126.447361 rgb/1305031126.447361.png 1305031126.455380 depth/1305031126.455380.png +1305031126.479533 rgb/1305031126.479533.png 1305031126.490386 depth/1305031126.490386.png +1305031126.511410 rgb/1305031126.511410.png 1305031126.522321 depth/1305031126.522321.png +1305031126.547374 rgb/1305031126.547374.png 1305031126.558209 depth/1305031126.558209.png +1305031126.579454 rgb/1305031126.579454.png 1305031126.590176 depth/1305031126.590176.png +1305031126.611528 rgb/1305031126.611528.png 1305031126.618687 depth/1305031126.618687.png +1305031126.647376 rgb/1305031126.647376.png 1305031126.654474 depth/1305031126.654474.png +1305031126.679479 rgb/1305031126.679479.png 1305031126.690022 depth/1305031126.690022.png +1305031126.711583 rgb/1305031126.711583.png 1305031126.715770 depth/1305031126.715770.png +1305031126.747316 rgb/1305031126.747316.png 1305031126.755374 depth/1305031126.755374.png +1305031126.779379 rgb/1305031126.779379.png 1305031126.787565 depth/1305031126.787565.png +1305031126.811602 rgb/1305031126.811602.png 1305031126.819929 depth/1305031126.819929.png +1305031126.847343 rgb/1305031126.847343.png 1305031126.858378 depth/1305031126.858378.png +1305031126.879357 rgb/1305031126.879357.png 1305031126.888154 depth/1305031126.888154.png +1305031126.911364 rgb/1305031126.911364.png 1305031126.919409 depth/1305031126.919409.png +1305031126.947437 rgb/1305031126.947437.png 1305031126.955501 depth/1305031126.955501.png +1305031126.979337 rgb/1305031126.979337.png 1305031126.987316 depth/1305031126.987316.png +1305031127.011371 rgb/1305031127.011371.png 1305031127.019524 depth/1305031127.019524.png +1305031127.047297 rgb/1305031127.047297.png 1305031127.053318 depth/1305031127.053318.png +1305031127.079299 rgb/1305031127.079299.png 1305031127.088649 depth/1305031127.088649.png +1305031127.111435 rgb/1305031127.111435.png 1305031127.120963 depth/1305031127.120963.png +1305031127.147307 rgb/1305031127.147307.png 1305031127.157692 depth/1305031127.157692.png +1305031127.179349 rgb/1305031127.179349.png 1305031127.187500 depth/1305031127.187500.png +1305031127.211700 rgb/1305031127.211700.png 1305031127.221831 depth/1305031127.221831.png +1305031127.247374 rgb/1305031127.247374.png 1305031127.259761 depth/1305031127.259761.png +1305031127.279465 rgb/1305031127.279465.png 1305031127.287038 depth/1305031127.287038.png +1305031127.311362 rgb/1305031127.311362.png 1305031127.320468 depth/1305031127.320468.png +1305031127.347356 rgb/1305031127.347356.png 1305031127.353407 depth/1305031127.353407.png +1305031127.379262 rgb/1305031127.379262.png 1305031127.383713 depth/1305031127.383713.png +1305031127.411371 rgb/1305031127.411371.png 1305031127.419650 depth/1305031127.419650.png +1305031127.447333 rgb/1305031127.447333.png 1305031127.454246 depth/1305031127.454246.png +1305031127.479362 rgb/1305031127.479362.png 1305031127.487200 depth/1305031127.487200.png +1305031127.511356 rgb/1305031127.511356.png 1305031127.521900 depth/1305031127.521900.png +1305031127.547348 rgb/1305031127.547348.png 1305031127.553725 depth/1305031127.553725.png +1305031127.579345 rgb/1305031127.579345.png 1305031127.586632 depth/1305031127.586632.png +1305031127.611271 rgb/1305031127.611271.png 1305031127.620657 depth/1305031127.620657.png +1305031127.647358 rgb/1305031127.647358.png 1305031127.654656 depth/1305031127.654656.png +1305031127.679298 rgb/1305031127.679298.png 1305031127.687110 depth/1305031127.687110.png +1305031127.711375 rgb/1305031127.711375.png 1305031127.723210 depth/1305031127.723210.png +1305031127.747304 rgb/1305031127.747304.png 1305031127.754694 depth/1305031127.754694.png +1305031127.779346 rgb/1305031127.779346.png 1305031127.787641 depth/1305031127.787641.png +1305031127.811829 rgb/1305031127.811829.png 1305031127.820128 depth/1305031127.820128.png +1305031127.847366 rgb/1305031127.847366.png 1305031127.855132 depth/1305031127.855132.png +1305031127.879380 rgb/1305031127.879380.png 1305031127.887122 depth/1305031127.887122.png +1305031127.911476 rgb/1305031127.911476.png 1305031127.922560 depth/1305031127.922560.png +1305031127.947366 rgb/1305031127.947366.png 1305031127.955088 depth/1305031127.955088.png +1305031127.979371 rgb/1305031127.979371.png 1305031127.987093 depth/1305031127.987093.png +1305031128.011427 rgb/1305031128.011427.png 1305031128.021776 depth/1305031128.021776.png +1305031128.047369 rgb/1305031128.047369.png 1305031128.055718 depth/1305031128.055718.png +1305031128.079334 rgb/1305031128.079334.png 1305031128.087206 depth/1305031128.087206.png +1305031128.111391 rgb/1305031128.111391.png 1305031128.124746 depth/1305031128.124746.png +1305031128.147418 rgb/1305031128.147418.png 1305031128.157782 depth/1305031128.157782.png +1305031128.179350 rgb/1305031128.179350.png 1305031128.187221 depth/1305031128.187221.png +1305031128.211447 rgb/1305031128.211447.png 1305031128.225442 depth/1305031128.225442.png +1305031128.247480 rgb/1305031128.247480.png 1305031128.256007 depth/1305031128.256007.png +1305031128.279336 rgb/1305031128.279336.png 1305031128.291275 depth/1305031128.291275.png +1305031128.311483 rgb/1305031128.311483.png 1305031128.324170 depth/1305031128.324170.png +1305031128.347423 rgb/1305031128.347423.png 1305031128.355206 depth/1305031128.355206.png +1305031128.379404 rgb/1305031128.379404.png 1305031128.391397 depth/1305031128.391397.png +1305031128.411337 rgb/1305031128.411337.png 1305031128.423609 depth/1305031128.423609.png +1305031128.447296 rgb/1305031128.447296.png 1305031128.455499 depth/1305031128.455499.png +1305031128.479296 rgb/1305031128.479296.png 1305031128.489523 depth/1305031128.489523.png +1305031128.511433 rgb/1305031128.511433.png 1305031128.523604 depth/1305031128.523604.png +1305031128.547399 rgb/1305031128.547399.png 1305031128.555639 depth/1305031128.555639.png +1305031128.579455 rgb/1305031128.579455.png 1305031128.591460 depth/1305031128.591460.png +1305031128.611395 rgb/1305031128.611395.png 1305031128.623368 depth/1305031128.623368.png +1305031128.647352 rgb/1305031128.647352.png 1305031128.655554 depth/1305031128.655554.png +1305031128.679282 rgb/1305031128.679282.png 1305031128.690449 depth/1305031128.690449.png +1305031128.711457 rgb/1305031128.711457.png 1305031128.722976 depth/1305031128.722976.png +1305031128.747363 rgb/1305031128.747363.png 1305031128.754646 depth/1305031128.754646.png diff --git a/Examples/RGB-D/associations/fr2_desk.txt b/Examples/RGB-D/associations/fr2_desk.txt new file mode 100644 index 0000000000..39d6ca2eec --- /dev/null +++ b/Examples/RGB-D/associations/fr2_desk.txt @@ -0,0 +1,2893 @@ +1311868164.363181 rgb/1311868164.363181.png 1311868164.373557 depth/1311868164.373557.png +1311868164.399026 rgb/1311868164.399026.png 1311868164.407784 depth/1311868164.407784.png +1311868164.430940 rgb/1311868164.430940.png 1311868164.437021 depth/1311868164.437021.png +1311868164.463055 rgb/1311868164.463055.png 1311868164.477039 depth/1311868164.477039.png +1311868164.499130 rgb/1311868164.499130.png 1311868164.507698 depth/1311868164.507698.png +1311868164.531025 rgb/1311868164.531025.png 1311868164.539395 depth/1311868164.539395.png +1311868164.563004 rgb/1311868164.563004.png 1311868164.573050 depth/1311868164.573050.png +1311868164.599061 rgb/1311868164.599061.png 1311868164.607892 depth/1311868164.607892.png +1311868164.631140 rgb/1311868164.631140.png 1311868164.637394 depth/1311868164.637394.png +1311868164.663105 rgb/1311868164.663105.png 1311868164.677534 depth/1311868164.677534.png +1311868164.698987 rgb/1311868164.698987.png 1311868164.709615 depth/1311868164.709615.png +1311868164.731046 rgb/1311868164.731046.png 1311868164.737662 depth/1311868164.737662.png +1311868164.763098 rgb/1311868164.763098.png 1311868164.779225 depth/1311868164.779225.png +1311868164.799138 rgb/1311868164.799138.png 1311868164.809404 depth/1311868164.809404.png +1311868164.831006 rgb/1311868164.831006.png 1311868164.842880 depth/1311868164.842880.png +1311868164.863058 rgb/1311868164.863058.png 1311868164.874612 depth/1311868164.874612.png +1311868164.899132 rgb/1311868164.899132.png 1311868164.905168 depth/1311868164.905168.png +1311868164.930933 rgb/1311868164.930933.png 1311868164.941784 depth/1311868164.941784.png +1311868164.963119 rgb/1311868164.963119.png 1311868164.975315 depth/1311868164.975315.png +1311868164.999037 rgb/1311868164.999037.png 1311868165.006447 depth/1311868165.006447.png +1311868165.031122 rgb/1311868165.031122.png 1311868165.043301 depth/1311868165.043301.png +1311868165.063108 rgb/1311868165.063108.png 1311868165.077013 depth/1311868165.077013.png +1311868165.099162 rgb/1311868165.099162.png 1311868165.107584 depth/1311868165.107584.png +1311868165.131014 rgb/1311868165.131014.png 1311868165.140672 depth/1311868165.140672.png +1311868165.163146 rgb/1311868165.163146.png 1311868165.173990 depth/1311868165.173990.png +1311868165.199145 rgb/1311868165.199145.png 1311868165.207186 depth/1311868165.207186.png +1311868165.231193 rgb/1311868165.231193.png 1311868165.241540 depth/1311868165.241540.png +1311868165.263005 rgb/1311868165.263005.png 1311868165.276310 depth/1311868165.276310.png +1311868165.299103 rgb/1311868165.299103.png 1311868165.309970 depth/1311868165.309970.png +1311868165.331226 rgb/1311868165.331226.png 1311868165.341279 depth/1311868165.341279.png +1311868165.363060 rgb/1311868165.363060.png 1311868165.373166 depth/1311868165.373166.png +1311868165.399160 rgb/1311868165.399160.png 1311868165.409979 depth/1311868165.409979.png +1311868165.430962 rgb/1311868165.430962.png 1311868165.441768 depth/1311868165.441768.png +1311868165.463114 rgb/1311868165.463114.png 1311868165.476336 depth/1311868165.476336.png +1311868165.499179 rgb/1311868165.499179.png 1311868165.507271 depth/1311868165.507271.png +1311868165.531124 rgb/1311868165.531124.png 1311868165.546047 depth/1311868165.546047.png +1311868165.563054 rgb/1311868165.563054.png 1311868165.574653 depth/1311868165.574653.png +1311868165.599188 rgb/1311868165.599188.png 1311868165.607633 depth/1311868165.607633.png +1311868165.631159 rgb/1311868165.631159.png 1311868165.645161 depth/1311868165.645161.png +1311868165.663251 rgb/1311868165.663251.png 1311868165.678824 depth/1311868165.678824.png +1311868165.699187 rgb/1311868165.699187.png 1311868165.704839 depth/1311868165.704839.png +1311868165.731234 rgb/1311868165.731234.png 1311868165.744880 depth/1311868165.744880.png +1311868165.763100 rgb/1311868165.763100.png 1311868165.773032 depth/1311868165.773032.png +1311868165.799107 rgb/1311868165.799107.png 1311868165.812385 depth/1311868165.812385.png +1311868165.831186 rgb/1311868165.831186.png 1311868165.841804 depth/1311868165.841804.png +1311868165.863220 rgb/1311868165.863220.png 1311868165.877856 depth/1311868165.877856.png +1311868165.899162 rgb/1311868165.899162.png 1311868165.906859 depth/1311868165.906859.png +1311868165.931154 rgb/1311868165.931154.png 1311868165.940588 depth/1311868165.940588.png +1311868165.963154 rgb/1311868165.963154.png 1311868165.976324 depth/1311868165.976324.png +1311868165.999133 rgb/1311868165.999133.png 1311868166.007658 depth/1311868166.007658.png +1311868166.031204 rgb/1311868166.031204.png 1311868166.045983 depth/1311868166.045983.png +1311868166.063111 rgb/1311868166.063111.png 1311868166.076013 depth/1311868166.076013.png +1311868166.099206 rgb/1311868166.099206.png 1311868166.114132 depth/1311868166.114132.png +1311868166.131254 rgb/1311868166.131254.png 1311868166.142743 depth/1311868166.142743.png +1311868166.163189 rgb/1311868166.163189.png 1311868166.179610 depth/1311868166.179610.png +1311868166.199211 rgb/1311868166.199211.png 1311868166.210624 depth/1311868166.210624.png +1311868166.231050 rgb/1311868166.231050.png 1311868166.247913 depth/1311868166.247913.png +1311868166.263177 rgb/1311868166.263177.png 1311868166.277838 depth/1311868166.277838.png +1311868166.299209 rgb/1311868166.299209.png 1311868166.315342 depth/1311868166.315342.png +1311868166.331189 rgb/1311868166.331189.png 1311868166.343165 depth/1311868166.343165.png +1311868166.363122 rgb/1311868166.363122.png 1311868166.377872 depth/1311868166.377872.png +1311868166.399232 rgb/1311868166.399232.png 1311868166.412308 depth/1311868166.412308.png +1311868166.431171 rgb/1311868166.431171.png 1311868166.446657 depth/1311868166.446657.png +1311868166.463018 rgb/1311868166.463018.png 1311868166.473009 depth/1311868166.473009.png +1311868166.499195 rgb/1311868166.499195.png 1311868166.513359 depth/1311868166.513359.png +1311868166.531252 rgb/1311868166.531252.png 1311868166.548698 depth/1311868166.548698.png +1311868166.563132 rgb/1311868166.563132.png 1311868166.575428 depth/1311868166.575428.png +1311868166.599207 rgb/1311868166.599207.png 1311868166.615820 depth/1311868166.615820.png +1311868166.631287 rgb/1311868166.631287.png 1311868166.646341 depth/1311868166.646341.png +1311868166.663284 rgb/1311868166.663284.png 1311868166.674028 depth/1311868166.674028.png +1311868166.699270 rgb/1311868166.699270.png 1311868166.715787 depth/1311868166.715787.png +1311868166.731105 rgb/1311868166.731105.png 1311868166.742696 depth/1311868166.742696.png +1311868166.763333 rgb/1311868166.763333.png 1311868166.778154 depth/1311868166.778154.png +1311868166.799225 rgb/1311868166.799225.png 1311868166.815856 depth/1311868166.815856.png +1311868166.831229 rgb/1311868166.831229.png 1311868166.842696 depth/1311868166.842696.png +1311868166.863222 rgb/1311868166.863222.png 1311868166.878523 depth/1311868166.878523.png +1311868166.899308 rgb/1311868166.899308.png 1311868166.912315 depth/1311868166.912315.png +1311868166.931160 rgb/1311868166.931160.png 1311868166.944305 depth/1311868166.944305.png +1311868166.963312 rgb/1311868166.963312.png 1311868166.974973 depth/1311868166.974973.png +1311868166.999289 rgb/1311868166.999289.png 1311868167.013110 depth/1311868167.013110.png +1311868167.031127 rgb/1311868167.031127.png 1311868167.042581 depth/1311868167.042581.png +1311868167.063209 rgb/1311868167.063209.png 1311868167.078817 depth/1311868167.078817.png +1311868167.099303 rgb/1311868167.099303.png 1311868167.113263 depth/1311868167.113263.png +1311868167.163230 rgb/1311868167.163230.png 1311868167.147601 depth/1311868167.147601.png +1311868167.199258 rgb/1311868167.199258.png 1311868167.213735 depth/1311868167.213735.png +1311868167.231267 rgb/1311868167.231267.png 1311868167.244725 depth/1311868167.244725.png +1311868167.263251 rgb/1311868167.263251.png 1311868167.274291 depth/1311868167.274291.png +1311868167.299141 rgb/1311868167.299141.png 1311868167.313892 depth/1311868167.313892.png +1311868167.331145 rgb/1311868167.331145.png 1311868167.343051 depth/1311868167.343051.png +1311868167.363275 rgb/1311868167.363275.png 1311868167.382523 depth/1311868167.382523.png +1311868167.399226 rgb/1311868167.399226.png 1311868167.412495 depth/1311868167.412495.png +1311868167.431237 rgb/1311868167.431237.png 1311868167.443001 depth/1311868167.443001.png +1311868167.463303 rgb/1311868167.463303.png 1311868167.480198 depth/1311868167.480198.png +1311868167.499121 rgb/1311868167.499121.png 1311868167.512612 depth/1311868167.512612.png +1311868167.531321 rgb/1311868167.531321.png 1311868167.545938 depth/1311868167.545938.png +1311868167.563160 rgb/1311868167.563160.png 1311868167.579040 depth/1311868167.579040.png +1311868167.599230 rgb/1311868167.599230.png 1311868167.613541 depth/1311868167.613541.png +1311868167.631495 rgb/1311868167.631495.png 1311868167.646201 depth/1311868167.646201.png +1311868167.663360 rgb/1311868167.663360.png 1311868167.682062 depth/1311868167.682062.png +1311868167.699226 rgb/1311868167.699226.png 1311868167.711828 depth/1311868167.711828.png +1311868167.731241 rgb/1311868167.731241.png 1311868167.747549 depth/1311868167.747549.png +1311868167.763281 rgb/1311868167.763281.png 1311868167.778192 depth/1311868167.778192.png +1311868167.799224 rgb/1311868167.799224.png 1311868167.811077 depth/1311868167.811077.png +1311868167.863098 rgb/1311868167.863098.png 1311868167.847649 depth/1311868167.847649.png +1311868167.899376 rgb/1311868167.899376.png 1311868167.914863 depth/1311868167.914863.png +1311868167.931184 rgb/1311868167.931184.png 1311868167.944131 depth/1311868167.944131.png +1311868167.999325 rgb/1311868167.999325.png 1311868168.014342 depth/1311868168.014342.png +1311868168.031266 rgb/1311868168.031266.png 1311868168.047735 depth/1311868168.047735.png +1311868168.063183 rgb/1311868168.063183.png 1311868168.076594 depth/1311868168.076594.png +1311868168.099296 rgb/1311868168.099296.png 1311868168.115940 depth/1311868168.115940.png +1311868168.131162 rgb/1311868168.131162.png 1311868168.141624 depth/1311868168.141624.png +1311868168.163282 rgb/1311868168.163282.png 1311868168.180912 depth/1311868168.180912.png +1311868168.199247 rgb/1311868168.199247.png 1311868168.210991 depth/1311868168.210991.png +1311868168.263256 rgb/1311868168.263256.png 1311868168.247820 depth/1311868168.247820.png +1311868168.299606 rgb/1311868168.299606.png 1311868168.318349 depth/1311868168.318349.png +1311868168.331222 rgb/1311868168.331222.png 1311868168.342592 depth/1311868168.342592.png +1311868168.363180 rgb/1311868168.363180.png 1311868168.379082 depth/1311868168.379082.png +1311868168.399360 rgb/1311868168.399360.png 1311868168.414678 depth/1311868168.414678.png +1311868168.431214 rgb/1311868168.431214.png 1311868168.442322 depth/1311868168.442322.png +1311868168.463333 rgb/1311868168.463333.png 1311868168.480727 depth/1311868168.480727.png +1311868168.499268 rgb/1311868168.499268.png 1311868168.511764 depth/1311868168.511764.png +1311868168.563319 rgb/1311868168.563319.png 1311868168.549203 depth/1311868168.549203.png +1311868168.599366 rgb/1311868168.599366.png 1311868168.613771 depth/1311868168.613771.png +1311868168.663320 rgb/1311868168.663320.png 1311868168.647259 depth/1311868168.647259.png +1311868168.699557 rgb/1311868168.699557.png 1311868168.712769 depth/1311868168.712769.png +1311868168.763305 rgb/1311868168.763305.png 1311868168.747597 depth/1311868168.747597.png +1311868168.799362 rgb/1311868168.799362.png 1311868168.813606 depth/1311868168.813606.png +1311868168.831176 rgb/1311868168.831176.png 1311868168.846276 depth/1311868168.846276.png +1311868168.899300 rgb/1311868168.899300.png 1311868168.881883 depth/1311868168.881883.png +1311868168.931215 rgb/1311868168.931215.png 1311868168.916265 depth/1311868168.916265.png +1311868168.963348 rgb/1311868168.963348.png 1311868168.947866 depth/1311868168.947866.png +1311868168.999373 rgb/1311868168.999373.png 1311868169.015053 depth/1311868169.015053.png +1311868169.031214 rgb/1311868169.031214.png 1311868169.046000 depth/1311868169.046000.png +1311868169.063354 rgb/1311868169.063354.png 1311868169.080829 depth/1311868169.080829.png +1311868169.099339 rgb/1311868169.099339.png 1311868169.114700 depth/1311868169.114700.png +1311868169.131247 rgb/1311868169.131247.png 1311868169.146187 depth/1311868169.146187.png +1311868169.199452 rgb/1311868169.199452.png 1311868169.212807 depth/1311868169.212807.png +1311868169.231354 rgb/1311868169.231354.png 1311868169.247722 depth/1311868169.247722.png +1311868169.263274 rgb/1311868169.263274.png 1311868169.278346 depth/1311868169.278346.png +1311868169.299529 rgb/1311868169.299529.png 1311868169.314714 depth/1311868169.314714.png +1311868169.331297 rgb/1311868169.331297.png 1311868169.345199 depth/1311868169.345199.png +1311868169.363470 rgb/1311868169.363470.png 1311868169.381298 depth/1311868169.381298.png +1311868169.399437 rgb/1311868169.399437.png 1311868169.415209 depth/1311868169.415209.png +1311868169.431440 rgb/1311868169.431440.png 1311868169.448276 depth/1311868169.448276.png +1311868169.463229 rgb/1311868169.463229.png 1311868169.476415 depth/1311868169.476415.png +1311868169.499263 rgb/1311868169.499263.png 1311868169.510002 depth/1311868169.510002.png +1311868169.531434 rgb/1311868169.531434.png 1311868169.546064 depth/1311868169.546064.png +1311868169.563501 rgb/1311868169.563501.png 1311868169.578266 depth/1311868169.578266.png +1311868169.599378 rgb/1311868169.599378.png 1311868169.611451 depth/1311868169.611451.png +1311868169.631327 rgb/1311868169.631327.png 1311868169.645864 depth/1311868169.645864.png +1311868169.663240 rgb/1311868169.663240.png 1311868169.676560 depth/1311868169.676560.png +1311868169.699466 rgb/1311868169.699466.png 1311868169.710206 depth/1311868169.710206.png +1311868169.731279 rgb/1311868169.731279.png 1311868169.744399 depth/1311868169.744399.png +1311868169.763417 rgb/1311868169.763417.png 1311868169.777125 depth/1311868169.777125.png +1311868169.799368 rgb/1311868169.799368.png 1311868169.813053 depth/1311868169.813053.png +1311868169.831415 rgb/1311868169.831415.png 1311868169.844213 depth/1311868169.844213.png +1311868169.863396 rgb/1311868169.863396.png 1311868169.876056 depth/1311868169.876056.png +1311868169.899390 rgb/1311868169.899390.png 1311868169.914497 depth/1311868169.914497.png +1311868169.931272 rgb/1311868169.931272.png 1311868169.944115 depth/1311868169.944115.png +1311868169.963415 rgb/1311868169.963415.png 1311868169.976205 depth/1311868169.976205.png +1311868169.999399 rgb/1311868169.999399.png 1311868170.014513 depth/1311868170.014513.png +1311868170.031274 rgb/1311868170.031274.png 1311868170.044946 depth/1311868170.044946.png +1311868170.063469 rgb/1311868170.063469.png 1311868170.076136 depth/1311868170.076136.png +1311868170.099394 rgb/1311868170.099394.png 1311868170.114660 depth/1311868170.114660.png +1311868170.131345 rgb/1311868170.131345.png 1311868170.144070 depth/1311868170.144070.png +1311868170.163416 rgb/1311868170.163416.png 1311868170.177624 depth/1311868170.177624.png +1311868170.199317 rgb/1311868170.199317.png 1311868170.213439 depth/1311868170.213439.png +1311868170.231467 rgb/1311868170.231467.png 1311868170.244916 depth/1311868170.244916.png +1311868170.263521 rgb/1311868170.263521.png 1311868170.276960 depth/1311868170.276960.png +1311868170.299432 rgb/1311868170.299432.png 1311868170.314762 depth/1311868170.314762.png +1311868170.331325 rgb/1311868170.331325.png 1311868170.344164 depth/1311868170.344164.png +1311868170.363400 rgb/1311868170.363400.png 1311868170.376729 depth/1311868170.376729.png +1311868170.399421 rgb/1311868170.399421.png 1311868170.413810 depth/1311868170.413810.png +1311868170.431288 rgb/1311868170.431288.png 1311868170.444929 depth/1311868170.444929.png +1311868170.463383 rgb/1311868170.463383.png 1311868170.476958 depth/1311868170.476958.png +1311868170.499476 rgb/1311868170.499476.png 1311868170.512513 depth/1311868170.512513.png +1311868170.531505 rgb/1311868170.531505.png 1311868170.546334 depth/1311868170.546334.png +1311868170.563345 rgb/1311868170.563345.png 1311868170.576738 depth/1311868170.576738.png +1311868170.599324 rgb/1311868170.599324.png 1311868170.614201 depth/1311868170.614201.png +1311868170.631485 rgb/1311868170.631485.png 1311868170.646250 depth/1311868170.646250.png +1311868170.663430 rgb/1311868170.663430.png 1311868170.678133 depth/1311868170.678133.png +1311868170.699432 rgb/1311868170.699432.png 1311868170.713182 depth/1311868170.713182.png +1311868170.731397 rgb/1311868170.731397.png 1311868170.745234 depth/1311868170.745234.png +1311868170.763453 rgb/1311868170.763453.png 1311868170.776288 depth/1311868170.776288.png +1311868170.799446 rgb/1311868170.799446.png 1311868170.814542 depth/1311868170.814542.png +1311868170.831309 rgb/1311868170.831309.png 1311868170.845482 depth/1311868170.845482.png +1311868170.863446 rgb/1311868170.863446.png 1311868170.877100 depth/1311868170.877100.png +1311868170.899435 rgb/1311868170.899435.png 1311868170.912926 depth/1311868170.912926.png +1311868170.931374 rgb/1311868170.931374.png 1311868170.945932 depth/1311868170.945932.png +1311868170.963440 rgb/1311868170.963440.png 1311868170.978389 depth/1311868170.978389.png +1311868170.999483 rgb/1311868170.999483.png 1311868171.012870 depth/1311868171.012870.png +1311868171.031493 rgb/1311868171.031493.png 1311868171.044724 depth/1311868171.044724.png +1311868171.063438 rgb/1311868171.063438.png 1311868171.081318 depth/1311868171.081318.png +1311868171.099448 rgb/1311868171.099448.png 1311868171.114152 depth/1311868171.114152.png +1311868171.131477 rgb/1311868171.131477.png 1311868171.145946 depth/1311868171.145946.png +1311868171.163447 rgb/1311868171.163447.png 1311868171.180214 depth/1311868171.180214.png +1311868171.199444 rgb/1311868171.199444.png 1311868171.214478 depth/1311868171.214478.png +1311868171.231391 rgb/1311868171.231391.png 1311868171.244574 depth/1311868171.244574.png +1311868171.263404 rgb/1311868171.263404.png 1311868171.281359 depth/1311868171.281359.png +1311868171.299368 rgb/1311868171.299368.png 1311868171.313542 depth/1311868171.313542.png +1311868171.331406 rgb/1311868171.331406.png 1311868171.345769 depth/1311868171.345769.png +1311868171.363479 rgb/1311868171.363479.png 1311868171.382663 depth/1311868171.382663.png +1311868171.399409 rgb/1311868171.399409.png 1311868171.413153 depth/1311868171.413153.png +1311868171.463459 rgb/1311868171.463459.png 1311868171.448332 depth/1311868171.448332.png +1311868171.499514 rgb/1311868171.499514.png 1311868171.514658 depth/1311868171.514658.png +1311868171.531471 rgb/1311868171.531471.png 1311868171.545883 depth/1311868171.545883.png +1311868171.563381 rgb/1311868171.563381.png 1311868171.580276 depth/1311868171.580276.png +1311868171.599490 rgb/1311868171.599490.png 1311868171.615486 depth/1311868171.615486.png +1311868171.631528 rgb/1311868171.631528.png 1311868171.644392 depth/1311868171.644392.png +1311868171.663411 rgb/1311868171.663411.png 1311868171.680537 depth/1311868171.680537.png +1311868171.699419 rgb/1311868171.699419.png 1311868171.712723 depth/1311868171.712723.png +1311868171.731499 rgb/1311868171.731499.png 1311868171.744488 depth/1311868171.744488.png +1311868171.763455 rgb/1311868171.763455.png 1311868171.780348 depth/1311868171.780348.png +1311868171.799464 rgb/1311868171.799464.png 1311868171.813158 depth/1311868171.813158.png +1311868171.831419 rgb/1311868171.831419.png 1311868171.845207 depth/1311868171.845207.png +1311868171.899575 rgb/1311868171.899575.png 1311868171.914819 depth/1311868171.914819.png +1311868171.931516 rgb/1311868171.931516.png 1311868171.945714 depth/1311868171.945714.png +1311868171.999580 rgb/1311868171.999580.png 1311868171.982100 depth/1311868171.982100.png +1311868172.031533 rgb/1311868172.031533.png 1311868172.016948 depth/1311868172.016948.png +1311868172.063426 rgb/1311868172.063426.png 1311868172.048421 depth/1311868172.048421.png +1311868172.099529 rgb/1311868172.099529.png 1311868172.113830 depth/1311868172.113830.png +1311868172.131546 rgb/1311868172.131546.png 1311868172.147015 depth/1311868172.147015.png +1311868172.163558 rgb/1311868172.163558.png 1311868172.181956 depth/1311868172.181956.png +1311868172.199781 rgb/1311868172.199781.png 1311868172.214983 depth/1311868172.214983.png +1311868172.263475 rgb/1311868172.263475.png 1311868172.248620 depth/1311868172.248620.png +1311868172.299544 rgb/1311868172.299544.png 1311868172.315192 depth/1311868172.315192.png +1311868172.363479 rgb/1311868172.363479.png 1311868172.350013 depth/1311868172.350013.png +1311868172.399483 rgb/1311868172.399483.png 1311868172.413939 depth/1311868172.413939.png +1311868172.463477 rgb/1311868172.463477.png 1311868172.449692 depth/1311868172.449692.png +1311868172.499467 rgb/1311868172.499467.png 1311868172.515495 depth/1311868172.515495.png +1311868172.563601 rgb/1311868172.563601.png 1311868172.549992 depth/1311868172.549992.png +1311868172.599590 rgb/1311868172.599590.png 1311868172.580944 depth/1311868172.580944.png +1311868172.631587 rgb/1311868172.631587.png 1311868172.615769 depth/1311868172.615769.png +1311868172.663612 rgb/1311868172.663612.png 1311868172.650102 depth/1311868172.650102.png +1311868172.699619 rgb/1311868172.699619.png 1311868172.713134 depth/1311868172.713134.png +1311868172.763469 rgb/1311868172.763469.png 1311868172.751196 depth/1311868172.751196.png +1311868172.799623 rgb/1311868172.799623.png 1311868172.815509 depth/1311868172.815509.png +1311868172.863483 rgb/1311868172.863483.png 1311868172.849287 depth/1311868172.849287.png +1311868172.899539 rgb/1311868172.899539.png 1311868172.882805 depth/1311868172.882805.png +1311868172.931607 rgb/1311868172.931607.png 1311868172.915927 depth/1311868172.915927.png +1311868172.963571 rgb/1311868172.963571.png 1311868172.950756 depth/1311868172.950756.png +1311868172.999602 rgb/1311868172.999602.png 1311868173.013773 depth/1311868173.013773.png +1311868173.067546 rgb/1311868173.067546.png 1311868173.050671 depth/1311868173.050671.png +1311868173.099605 rgb/1311868173.099605.png 1311868173.113327 depth/1311868173.113327.png +1311868173.131499 rgb/1311868173.131499.png 1311868173.149043 depth/1311868173.149043.png +1311868173.167457 rgb/1311868173.167457.png 1311868173.180971 depth/1311868173.180971.png +1311868173.199628 rgb/1311868173.199628.png 1311868173.213652 depth/1311868173.213652.png +1311868173.231487 rgb/1311868173.231487.png 1311868173.250386 depth/1311868173.250386.png +1311868173.267665 rgb/1311868173.267665.png 1311868173.283876 depth/1311868173.283876.png +1311868173.299659 rgb/1311868173.299659.png 1311868173.314048 depth/1311868173.314048.png +1311868173.331533 rgb/1311868173.331533.png 1311868173.349086 depth/1311868173.349086.png +1311868173.367650 rgb/1311868173.367650.png 1311868173.381642 depth/1311868173.381642.png +1311868173.399596 rgb/1311868173.399596.png 1311868173.414811 depth/1311868173.414811.png +1311868173.431624 rgb/1311868173.431624.png 1311868173.449252 depth/1311868173.449252.png +1311868173.467604 rgb/1311868173.467604.png 1311868173.483478 depth/1311868173.483478.png +1311868173.531628 rgb/1311868173.531628.png 1311868173.516984 depth/1311868173.516984.png +1311868173.567616 rgb/1311868173.567616.png 1311868173.581543 depth/1311868173.581543.png +1311868173.631603 rgb/1311868173.631603.png 1311868173.619855 depth/1311868173.619855.png +1311868173.667986 rgb/1311868173.667986.png 1311868173.654306 depth/1311868173.654306.png +1311868173.699670 rgb/1311868173.699670.png 1311868173.683641 depth/1311868173.683641.png +1311868173.731607 rgb/1311868173.731607.png 1311868173.717663 depth/1311868173.717663.png +1311868173.767623 rgb/1311868173.767623.png 1311868173.749076 depth/1311868173.749076.png +1311868173.799549 rgb/1311868173.799549.png 1311868173.784746 depth/1311868173.784746.png +1311868173.831620 rgb/1311868173.831620.png 1311868173.817750 depth/1311868173.817750.png +1311868173.867507 rgb/1311868173.867507.png 1311868173.882437 depth/1311868173.882437.png +1311868173.931642 rgb/1311868173.931642.png 1311868173.918618 depth/1311868173.918618.png +1311868173.967631 rgb/1311868173.967631.png 1311868173.950835 depth/1311868173.950835.png +1311868173.999745 rgb/1311868173.999745.png 1311868173.984224 depth/1311868173.984224.png +1311868174.031740 rgb/1311868174.031740.png 1311868174.017898 depth/1311868174.017898.png +1311868174.067656 rgb/1311868174.067656.png 1311868174.050437 depth/1311868174.050437.png +1311868174.099508 rgb/1311868174.099508.png 1311868174.084693 depth/1311868174.084693.png +1311868174.131747 rgb/1311868174.131747.png 1311868174.116996 depth/1311868174.116996.png +1311868174.167874 rgb/1311868174.167874.png 1311868174.182209 depth/1311868174.182209.png +1311868174.231617 rgb/1311868174.231617.png 1311868174.218679 depth/1311868174.218679.png +1311868174.267791 rgb/1311868174.267791.png 1311868174.250017 depth/1311868174.250017.png +1311868174.299749 rgb/1311868174.299749.png 1311868174.285697 depth/1311868174.285697.png +1311868174.331790 rgb/1311868174.331790.png 1311868174.317804 depth/1311868174.317804.png +1311868174.367988 rgb/1311868174.367988.png 1311868174.350271 depth/1311868174.350271.png +1311868174.399743 rgb/1311868174.399743.png 1311868174.386647 depth/1311868174.386647.png +1311868174.431786 rgb/1311868174.431786.png 1311868174.419476 depth/1311868174.419476.png +1311868174.467566 rgb/1311868174.467566.png 1311868174.452721 depth/1311868174.452721.png +1311868174.499672 rgb/1311868174.499672.png 1311868174.487772 depth/1311868174.487772.png +1311868174.531708 rgb/1311868174.531708.png 1311868174.518982 depth/1311868174.518982.png +1311868174.567585 rgb/1311868174.567585.png 1311868174.554621 depth/1311868174.554621.png +1311868174.599662 rgb/1311868174.599662.png 1311868174.584522 depth/1311868174.584522.png +1311868174.631772 rgb/1311868174.631772.png 1311868174.619814 depth/1311868174.619814.png +1311868174.667800 rgb/1311868174.667800.png 1311868174.651722 depth/1311868174.651722.png +1311868174.699578 rgb/1311868174.699578.png 1311868174.687374 depth/1311868174.687374.png +1311868174.731625 rgb/1311868174.731625.png 1311868174.719933 depth/1311868174.719933.png +1311868174.767680 rgb/1311868174.767680.png 1311868174.751101 depth/1311868174.751101.png +1311868174.799810 rgb/1311868174.799810.png 1311868174.789968 depth/1311868174.789968.png +1311868174.831815 rgb/1311868174.831815.png 1311868174.819171 depth/1311868174.819171.png +1311868174.867798 rgb/1311868174.867798.png 1311868174.849988 depth/1311868174.849988.png +1311868174.899678 rgb/1311868174.899678.png 1311868174.889132 depth/1311868174.889132.png +1311868174.931819 rgb/1311868174.931819.png 1311868174.917050 depth/1311868174.917050.png +1311868174.967694 rgb/1311868174.967694.png 1311868174.952141 depth/1311868174.952141.png +1311868174.999803 rgb/1311868174.999803.png 1311868174.988799 depth/1311868174.988799.png +1311868175.031665 rgb/1311868175.031665.png 1311868175.020776 depth/1311868175.020776.png +1311868175.067713 rgb/1311868175.067713.png 1311868175.048996 depth/1311868175.048996.png +1311868175.099631 rgb/1311868175.099631.png 1311868175.085546 depth/1311868175.085546.png +1311868175.131719 rgb/1311868175.131719.png 1311868175.118690 depth/1311868175.118690.png +1311868175.167807 rgb/1311868175.167807.png 1311868175.151936 depth/1311868175.151936.png +1311868175.199578 rgb/1311868175.199578.png 1311868175.187247 depth/1311868175.187247.png +1311868175.231818 rgb/1311868175.231818.png 1311868175.216686 depth/1311868175.216686.png +1311868175.267750 rgb/1311868175.267750.png 1311868175.254515 depth/1311868175.254515.png +1311868175.299978 rgb/1311868175.299978.png 1311868175.288057 depth/1311868175.288057.png +1311868175.331887 rgb/1311868175.331887.png 1311868175.320182 depth/1311868175.320182.png +1311868175.367738 rgb/1311868175.367738.png 1311868175.351161 depth/1311868175.351161.png +1311868175.400048 rgb/1311868175.400048.png 1311868175.387818 depth/1311868175.387818.png +1311868175.431994 rgb/1311868175.431994.png 1311868175.421391 depth/1311868175.421391.png +1311868175.467702 rgb/1311868175.467702.png 1311868175.449663 depth/1311868175.449663.png +1311868175.499770 rgb/1311868175.499770.png 1311868175.487565 depth/1311868175.487565.png +1311868175.531778 rgb/1311868175.531778.png 1311868175.519943 depth/1311868175.519943.png +1311868175.567800 rgb/1311868175.567800.png 1311868175.550912 depth/1311868175.550912.png +1311868175.599867 rgb/1311868175.599867.png 1311868175.587641 depth/1311868175.587641.png +1311868175.631778 rgb/1311868175.631778.png 1311868175.619756 depth/1311868175.619756.png +1311868175.667696 rgb/1311868175.667696.png 1311868175.649083 depth/1311868175.649083.png +1311868175.699784 rgb/1311868175.699784.png 1311868175.684710 depth/1311868175.684710.png +1311868175.731708 rgb/1311868175.731708.png 1311868175.719057 depth/1311868175.719057.png +1311868175.767584 rgb/1311868175.767584.png 1311868175.750556 depth/1311868175.750556.png +1311868175.799815 rgb/1311868175.799815.png 1311868175.788252 depth/1311868175.788252.png +1311868175.831761 rgb/1311868175.831761.png 1311868175.817245 depth/1311868175.817245.png +1311868175.867687 rgb/1311868175.867687.png 1311868175.850801 depth/1311868175.850801.png +1311868175.899663 rgb/1311868175.899663.png 1311868175.887345 depth/1311868175.887345.png +1311868175.931644 rgb/1311868175.931644.png 1311868175.917749 depth/1311868175.917749.png +1311868175.967871 rgb/1311868175.967871.png 1311868175.955575 depth/1311868175.955575.png +1311868175.999870 rgb/1311868175.999870.png 1311868175.988099 depth/1311868175.988099.png +1311868176.032043 rgb/1311868176.032043.png 1311868176.020287 depth/1311868176.020287.png +1311868176.067949 rgb/1311868176.067949.png 1311868176.055238 depth/1311868176.055238.png +1311868176.099801 rgb/1311868176.099801.png 1311868176.086530 depth/1311868176.086530.png +1311868176.131691 rgb/1311868176.131691.png 1311868176.119897 depth/1311868176.119897.png +1311868176.167963 rgb/1311868176.167963.png 1311868176.154293 depth/1311868176.154293.png +1311868176.199892 rgb/1311868176.199892.png 1311868176.188069 depth/1311868176.188069.png +1311868176.231937 rgb/1311868176.231937.png 1311868176.216891 depth/1311868176.216891.png +1311868176.267779 rgb/1311868176.267779.png 1311868176.254072 depth/1311868176.254072.png +1311868176.299834 rgb/1311868176.299834.png 1311868176.286843 depth/1311868176.286843.png +1311868176.331871 rgb/1311868176.331871.png 1311868176.319890 depth/1311868176.319890.png +1311868176.367752 rgb/1311868176.367752.png 1311868176.354614 depth/1311868176.354614.png +1311868176.399921 rgb/1311868176.399921.png 1311868176.384871 depth/1311868176.384871.png +1311868176.431678 rgb/1311868176.431678.png 1311868176.420020 depth/1311868176.420020.png +1311868176.467865 rgb/1311868176.467865.png 1311868176.457946 depth/1311868176.457946.png +1311868176.499760 rgb/1311868176.499760.png 1311868176.487950 depth/1311868176.487950.png +1311868176.531915 rgb/1311868176.531915.png 1311868176.519184 depth/1311868176.519184.png +1311868176.567758 rgb/1311868176.567758.png 1311868176.554180 depth/1311868176.554180.png +1311868176.602124 rgb/1311868176.602124.png 1311868176.588064 depth/1311868176.588064.png +1311868176.631719 rgb/1311868176.631719.png 1311868176.618839 depth/1311868176.618839.png +1311868176.667782 rgb/1311868176.667782.png 1311868176.655916 depth/1311868176.655916.png +1311868176.699787 rgb/1311868176.699787.png 1311868176.688107 depth/1311868176.688107.png +1311868176.731819 rgb/1311868176.731819.png 1311868176.718152 depth/1311868176.718152.png +1311868176.767814 rgb/1311868176.767814.png 1311868176.753106 depth/1311868176.753106.png +1311868176.799720 rgb/1311868176.799720.png 1311868176.787889 depth/1311868176.787889.png +1311868176.831887 rgb/1311868176.831887.png 1311868176.818027 depth/1311868176.818027.png +1311868176.867790 rgb/1311868176.867790.png 1311868176.854045 depth/1311868176.854045.png +1311868176.899837 rgb/1311868176.899837.png 1311868176.887985 depth/1311868176.887985.png +1311868176.931762 rgb/1311868176.931762.png 1311868176.917636 depth/1311868176.917636.png +1311868176.967856 rgb/1311868176.967856.png 1311868176.957238 depth/1311868176.957238.png +1311868176.999907 rgb/1311868176.999907.png 1311868176.988067 depth/1311868176.988067.png +1311868177.031966 rgb/1311868177.031966.png 1311868177.019840 depth/1311868177.019840.png +1311868177.067892 rgb/1311868177.067892.png 1311868177.053309 depth/1311868177.053309.png +1311868177.099730 rgb/1311868177.099730.png 1311868177.089594 depth/1311868177.089594.png +1311868177.131895 rgb/1311868177.131895.png 1311868177.117962 depth/1311868177.117962.png +1311868177.168091 rgb/1311868177.168091.png 1311868177.155926 depth/1311868177.155926.png +1311868177.199869 rgb/1311868177.199869.png 1311868177.188287 depth/1311868177.188287.png +1311868177.231903 rgb/1311868177.231903.png 1311868177.224759 depth/1311868177.224759.png +1311868177.267807 rgb/1311868177.267807.png 1311868177.255282 depth/1311868177.255282.png +1311868177.299871 rgb/1311868177.299871.png 1311868177.285963 depth/1311868177.285963.png +1311868177.331730 rgb/1311868177.331730.png 1311868177.322405 depth/1311868177.322405.png +1311868177.367900 rgb/1311868177.367900.png 1311868177.353213 depth/1311868177.353213.png +1311868177.399987 rgb/1311868177.399987.png 1311868177.387680 depth/1311868177.387680.png +1311868177.431827 rgb/1311868177.431827.png 1311868177.422370 depth/1311868177.422370.png +1311868177.467848 rgb/1311868177.467848.png 1311868177.454842 depth/1311868177.454842.png +1311868177.499762 rgb/1311868177.499762.png 1311868177.486612 depth/1311868177.486612.png +1311868177.531751 rgb/1311868177.531751.png 1311868177.521728 depth/1311868177.521728.png +1311868177.567851 rgb/1311868177.567851.png 1311868177.553540 depth/1311868177.553540.png +1311868177.599732 rgb/1311868177.599732.png 1311868177.588770 depth/1311868177.588770.png +1311868177.632083 rgb/1311868177.632083.png 1311868177.622670 depth/1311868177.622670.png +1311868177.667866 rgb/1311868177.667866.png 1311868177.654737 depth/1311868177.654737.png +1311868177.699913 rgb/1311868177.699913.png 1311868177.689225 depth/1311868177.689225.png +1311868177.731996 rgb/1311868177.731996.png 1311868177.722075 depth/1311868177.722075.png +1311868177.767937 rgb/1311868177.767937.png 1311868177.756389 depth/1311868177.756389.png +1311868177.799899 rgb/1311868177.799899.png 1311868177.785944 depth/1311868177.785944.png +1311868177.832005 rgb/1311868177.832005.png 1311868177.823182 depth/1311868177.823182.png +1311868177.867810 rgb/1311868177.867810.png 1311868177.853093 depth/1311868177.853093.png +1311868177.899856 rgb/1311868177.899856.png 1311868177.888965 depth/1311868177.888965.png +1311868177.931937 rgb/1311868177.931937.png 1311868177.922153 depth/1311868177.922153.png +1311868177.967919 rgb/1311868177.967919.png 1311868177.956515 depth/1311868177.956515.png +1311868178.000124 rgb/1311868178.000124.png 1311868177.988488 depth/1311868177.988488.png +1311868178.031988 rgb/1311868178.031988.png 1311868178.023893 depth/1311868178.023893.png +1311868178.068015 rgb/1311868178.068015.png 1311868178.056660 depth/1311868178.056660.png +1311868178.100039 rgb/1311868178.100039.png 1311868178.088612 depth/1311868178.088612.png +1311868178.131987 rgb/1311868178.131987.png 1311868178.123015 depth/1311868178.123015.png +1311868178.167955 rgb/1311868178.167955.png 1311868178.154939 depth/1311868178.154939.png +1311868178.199855 rgb/1311868178.199855.png 1311868178.188497 depth/1311868178.188497.png +1311868178.231966 rgb/1311868178.231966.png 1311868178.223125 depth/1311868178.223125.png +1311868178.267968 rgb/1311868178.267968.png 1311868178.256363 depth/1311868178.256363.png +1311868178.299815 rgb/1311868178.299815.png 1311868178.287054 depth/1311868178.287054.png +1311868178.332180 rgb/1311868178.332180.png 1311868178.326682 depth/1311868178.326682.png +1311868178.367989 rgb/1311868178.367989.png 1311868178.353561 depth/1311868178.353561.png +1311868178.400074 rgb/1311868178.400074.png 1311868178.388761 depth/1311868178.388761.png +1311868178.432167 rgb/1311868178.432167.png 1311868178.421230 depth/1311868178.421230.png +1311868178.467895 rgb/1311868178.467895.png 1311868178.454553 depth/1311868178.454553.png +1311868178.500102 rgb/1311868178.500102.png 1311868178.491175 depth/1311868178.491175.png +1311868178.531933 rgb/1311868178.531933.png 1311868178.521432 depth/1311868178.521432.png +1311868178.567928 rgb/1311868178.567928.png 1311868178.554561 depth/1311868178.554561.png +1311868178.600064 rgb/1311868178.600064.png 1311868178.593215 depth/1311868178.593215.png +1311868178.632030 rgb/1311868178.632030.png 1311868178.623597 depth/1311868178.623597.png +1311868178.668047 rgb/1311868178.668047.png 1311868178.654164 depth/1311868178.654164.png +1311868178.699917 rgb/1311868178.699917.png 1311868178.694880 depth/1311868178.694880.png +1311868178.731905 rgb/1311868178.731905.png 1311868178.721180 depth/1311868178.721180.png +1311868178.767938 rgb/1311868178.767938.png 1311868178.755005 depth/1311868178.755005.png +1311868178.799974 rgb/1311868178.799974.png 1311868178.789192 depth/1311868178.789192.png +1311868178.831967 rgb/1311868178.831967.png 1311868178.826203 depth/1311868178.826203.png +1311868178.867919 rgb/1311868178.867919.png 1311868178.855322 depth/1311868178.855322.png +1311868178.900038 rgb/1311868178.900038.png 1311868178.891570 depth/1311868178.891570.png +1311868178.932267 rgb/1311868178.932267.png 1311868178.926502 depth/1311868178.926502.png +1311868178.967934 rgb/1311868178.967934.png 1311868178.953383 depth/1311868178.953383.png +1311868179.000009 rgb/1311868179.000009.png 1311868178.991764 depth/1311868178.991764.png +1311868179.032182 rgb/1311868179.032182.png 1311868179.024394 depth/1311868179.024394.png +1311868179.067847 rgb/1311868179.067847.png 1311868179.054617 depth/1311868179.054617.png +1311868179.100093 rgb/1311868179.100093.png 1311868179.092608 depth/1311868179.092608.png +1311868179.132026 rgb/1311868179.132026.png 1311868179.123574 depth/1311868179.123574.png +1311868179.167985 rgb/1311868179.167985.png 1311868179.153903 depth/1311868179.153903.png +1311868179.200163 rgb/1311868179.200163.png 1311868179.191009 depth/1311868179.191009.png +1311868179.232011 rgb/1311868179.232011.png 1311868179.222802 depth/1311868179.222802.png +1311868179.268108 rgb/1311868179.268108.png 1311868179.253350 depth/1311868179.253350.png +1311868179.300467 rgb/1311868179.300467.png 1311868179.292764 depth/1311868179.292764.png +1311868179.333050 rgb/1311868179.333050.png 1311868179.324450 depth/1311868179.324450.png +1311868179.368133 rgb/1311868179.368133.png 1311868179.354206 depth/1311868179.354206.png +1311868179.400093 rgb/1311868179.400093.png 1311868179.392777 depth/1311868179.392777.png +1311868179.432203 rgb/1311868179.432203.png 1311868179.423985 depth/1311868179.423985.png +1311868179.467999 rgb/1311868179.467999.png 1311868179.458867 depth/1311868179.458867.png +1311868179.500080 rgb/1311868179.500080.png 1311868179.494098 depth/1311868179.494098.png +1311868179.532184 rgb/1311868179.532184.png 1311868179.523081 depth/1311868179.523081.png +1311868179.567958 rgb/1311868179.567958.png 1311868179.556083 depth/1311868179.556083.png +1311868179.600201 rgb/1311868179.600201.png 1311868179.594582 depth/1311868179.594582.png +1311868179.632001 rgb/1311868179.632001.png 1311868179.622672 depth/1311868179.622672.png +1311868179.668182 rgb/1311868179.668182.png 1311868179.659774 depth/1311868179.659774.png +1311868179.700151 rgb/1311868179.700151.png 1311868179.692799 depth/1311868179.692799.png +1311868179.732177 rgb/1311868179.732177.png 1311868179.722874 depth/1311868179.722874.png +1311868179.768285 rgb/1311868179.768285.png 1311868179.758585 depth/1311868179.758585.png +1311868179.800056 rgb/1311868179.800056.png 1311868179.790177 depth/1311868179.790177.png +1311868179.832089 rgb/1311868179.832089.png 1311868179.822815 depth/1311868179.822815.png +1311868179.867839 rgb/1311868179.867839.png 1311868179.857869 depth/1311868179.857869.png +1311868179.899932 rgb/1311868179.899932.png 1311868179.890505 depth/1311868179.890505.png +1311868179.932050 rgb/1311868179.932050.png 1311868179.921479 depth/1311868179.921479.png +1311868179.968012 rgb/1311868179.968012.png 1311868179.957179 depth/1311868179.957179.png +1311868179.999962 rgb/1311868179.999962.png 1311868179.989437 depth/1311868179.989437.png +1311868180.031945 rgb/1311868180.031945.png 1311868180.021938 depth/1311868180.021938.png +1311868180.068076 rgb/1311868180.068076.png 1311868180.057618 depth/1311868180.057618.png +1311868180.100092 rgb/1311868180.100092.png 1311868180.090030 depth/1311868180.090030.png +1311868180.131924 rgb/1311868180.131924.png 1311868180.121229 depth/1311868180.121229.png +1311868180.168096 rgb/1311868180.168096.png 1311868180.157172 depth/1311868180.157172.png +1311868180.200023 rgb/1311868180.200023.png 1311868180.190922 depth/1311868180.190922.png +1311868180.232155 rgb/1311868180.232155.png 1311868180.221475 depth/1311868180.221475.png +1311868180.268004 rgb/1311868180.268004.png 1311868180.257830 depth/1311868180.257830.png +1311868180.299978 rgb/1311868180.299978.png 1311868180.289335 depth/1311868180.289335.png +1311868180.331912 rgb/1311868180.331912.png 1311868180.321483 depth/1311868180.321483.png +1311868180.368101 rgb/1311868180.368101.png 1311868180.357148 depth/1311868180.357148.png +1311868180.400081 rgb/1311868180.400081.png 1311868180.389488 depth/1311868180.389488.png +1311868180.432000 rgb/1311868180.432000.png 1311868180.421520 depth/1311868180.421520.png +1311868180.468133 rgb/1311868180.468133.png 1311868180.457275 depth/1311868180.457275.png +1311868180.500082 rgb/1311868180.500082.png 1311868180.489377 depth/1311868180.489377.png +1311868180.531936 rgb/1311868180.531936.png 1311868180.521462 depth/1311868180.521462.png +1311868180.568027 rgb/1311868180.568027.png 1311868180.557221 depth/1311868180.557221.png +1311868180.600047 rgb/1311868180.600047.png 1311868180.590522 depth/1311868180.590522.png +1311868180.632105 rgb/1311868180.632105.png 1311868180.621305 depth/1311868180.621305.png +1311868180.668185 rgb/1311868180.668185.png 1311868180.658623 depth/1311868180.658623.png +1311868180.700174 rgb/1311868180.700174.png 1311868180.690541 depth/1311868180.690541.png +1311868180.732090 rgb/1311868180.732090.png 1311868180.722995 depth/1311868180.722995.png +1311868180.768172 rgb/1311868180.768172.png 1311868180.758766 depth/1311868180.758766.png +1311868180.800199 rgb/1311868180.800199.png 1311868180.792653 depth/1311868180.792653.png +1311868180.832010 rgb/1311868180.832010.png 1311868180.822029 depth/1311868180.822029.png +1311868180.867980 rgb/1311868180.867980.png 1311868180.857260 depth/1311868180.857260.png +1311868180.899974 rgb/1311868180.899974.png 1311868180.889509 depth/1311868180.889509.png +1311868180.932135 rgb/1311868180.932135.png 1311868180.925219 depth/1311868180.925219.png +1311868180.968026 rgb/1311868180.968026.png 1311868180.957367 depth/1311868180.957367.png +1311868181.000013 rgb/1311868181.000013.png 1311868180.989517 depth/1311868180.989517.png +1311868181.032168 rgb/1311868181.032168.png 1311868181.025444 depth/1311868181.025444.png +1311868181.068183 rgb/1311868181.068183.png 1311868181.059147 depth/1311868181.059147.png +1311868181.100120 rgb/1311868181.100120.png 1311868181.090930 depth/1311868181.090930.png +1311868181.132035 rgb/1311868181.132035.png 1311868181.125471 depth/1311868181.125471.png +1311868181.168020 rgb/1311868181.168020.png 1311868181.157365 depth/1311868181.157365.png +1311868181.200040 rgb/1311868181.200040.png 1311868181.189422 depth/1311868181.189422.png +1311868181.232080 rgb/1311868181.232080.png 1311868181.225265 depth/1311868181.225265.png +1311868181.268006 rgb/1311868181.268006.png 1311868181.257693 depth/1311868181.257693.png +1311868181.300111 rgb/1311868181.300111.png 1311868181.290158 depth/1311868181.290158.png +1311868181.332051 rgb/1311868181.332051.png 1311868181.325603 depth/1311868181.325603.png +1311868181.367997 rgb/1311868181.367997.png 1311868181.357529 depth/1311868181.357529.png +1311868181.400094 rgb/1311868181.400094.png 1311868181.390080 depth/1311868181.390080.png +1311868181.432419 rgb/1311868181.432419.png 1311868181.427528 depth/1311868181.427528.png +1311868181.468024 rgb/1311868181.468024.png 1311868181.457676 depth/1311868181.457676.png +1311868181.500288 rgb/1311868181.500288.png 1311868181.490154 depth/1311868181.490154.png +1311868181.532183 rgb/1311868181.532183.png 1311868181.526157 depth/1311868181.526157.png +1311868181.568153 rgb/1311868181.568153.png 1311868181.560894 depth/1311868181.560894.png +1311868181.600115 rgb/1311868181.600115.png 1311868181.590195 depth/1311868181.590195.png +1311868181.632435 rgb/1311868181.632435.png 1311868181.625858 depth/1311868181.625858.png +1311868181.668011 rgb/1311868181.668011.png 1311868181.657364 depth/1311868181.657364.png +1311868181.700024 rgb/1311868181.700024.png 1311868181.689655 depth/1311868181.689655.png +1311868181.732563 rgb/1311868181.732563.png 1311868181.725345 depth/1311868181.725345.png +1311868181.768063 rgb/1311868181.768063.png 1311868181.758495 depth/1311868181.758495.png +1311868181.800057 rgb/1311868181.800057.png 1311868181.790125 depth/1311868181.790125.png +1311868181.832157 rgb/1311868181.832157.png 1311868181.825364 depth/1311868181.825364.png +1311868181.868146 rgb/1311868181.868146.png 1311868181.857557 depth/1311868181.857557.png +1311868181.900215 rgb/1311868181.900215.png 1311868181.892701 depth/1311868181.892701.png +1311868181.932068 rgb/1311868181.932068.png 1311868181.925316 depth/1311868181.925316.png +1311868181.968208 rgb/1311868181.968208.png 1311868181.959762 depth/1311868181.959762.png +1311868182.000232 rgb/1311868182.000232.png 1311868181.992505 depth/1311868181.992505.png +1311868182.032194 rgb/1311868182.032194.png 1311868182.027831 depth/1311868182.027831.png +1311868182.068176 rgb/1311868182.068176.png 1311868182.057492 depth/1311868182.057492.png +1311868182.100226 rgb/1311868182.100226.png 1311868182.090848 depth/1311868182.090848.png +1311868182.136196 rgb/1311868182.136196.png 1311868182.125663 depth/1311868182.125663.png +1311868182.168077 rgb/1311868182.168077.png 1311868182.158087 depth/1311868182.158087.png +1311868182.200278 rgb/1311868182.200278.png 1311868182.193465 depth/1311868182.193465.png +1311868182.236167 rgb/1311868182.236167.png 1311868182.227644 depth/1311868182.227644.png +1311868182.268066 rgb/1311868182.268066.png 1311868182.257557 depth/1311868182.257557.png +1311868182.300234 rgb/1311868182.300234.png 1311868182.293645 depth/1311868182.293645.png +1311868182.336153 rgb/1311868182.336153.png 1311868182.325330 depth/1311868182.325330.png +1311868182.368183 rgb/1311868182.368183.png 1311868182.360580 depth/1311868182.360580.png +1311868182.400284 rgb/1311868182.400284.png 1311868182.393420 depth/1311868182.393420.png +1311868182.436053 rgb/1311868182.436053.png 1311868182.425586 depth/1311868182.425586.png +1311868182.468090 rgb/1311868182.468090.png 1311868182.459061 depth/1311868182.459061.png +1311868182.500921 rgb/1311868182.500921.png 1311868182.496222 depth/1311868182.496222.png +1311868182.536127 rgb/1311868182.536127.png 1311868182.525833 depth/1311868182.525833.png +1311868182.568033 rgb/1311868182.568033.png 1311868182.557951 depth/1311868182.557951.png +1311868182.600295 rgb/1311868182.600295.png 1311868182.593603 depth/1311868182.593603.png +1311868182.636312 rgb/1311868182.636312.png 1311868182.625359 depth/1311868182.625359.png +1311868182.668039 rgb/1311868182.668039.png 1311868182.657654 depth/1311868182.657654.png +1311868182.700341 rgb/1311868182.700341.png 1311868182.693647 depth/1311868182.693647.png +1311868182.736220 rgb/1311868182.736220.png 1311868182.726508 depth/1311868182.726508.png +1311868182.768253 rgb/1311868182.768253.png 1311868182.759036 depth/1311868182.759036.png +1311868182.800181 rgb/1311868182.800181.png 1311868182.796353 depth/1311868182.796353.png +1311868182.836155 rgb/1311868182.836155.png 1311868182.825316 depth/1311868182.825316.png +1311868182.868215 rgb/1311868182.868215.png 1311868182.857765 depth/1311868182.857765.png +1311868182.900229 rgb/1311868182.900229.png 1311868182.895733 depth/1311868182.895733.png +1311868182.936274 rgb/1311868182.936274.png 1311868182.925415 depth/1311868182.925415.png +1311868182.968092 rgb/1311868182.968092.png 1311868182.958230 depth/1311868182.958230.png +1311868183.000259 rgb/1311868183.000259.png 1311868182.994413 depth/1311868182.994413.png +1311868183.036254 rgb/1311868183.036254.png 1311868183.028182 depth/1311868183.028182.png +1311868183.068333 rgb/1311868183.068333.png 1311868183.059929 depth/1311868183.059929.png +1311868183.100611 rgb/1311868183.100611.png 1311868183.094902 depth/1311868183.094902.png +1311868183.136176 rgb/1311868183.136176.png 1311868183.125358 depth/1311868183.125358.png +1311868183.168211 rgb/1311868183.168211.png 1311868183.158526 depth/1311868183.158526.png +1311868183.200276 rgb/1311868183.200276.png 1311868183.193940 depth/1311868183.193940.png +1311868183.236295 rgb/1311868183.236295.png 1311868183.226777 depth/1311868183.226777.png +1311868183.268380 rgb/1311868183.268380.png 1311868183.258677 depth/1311868183.258677.png +1311868183.300363 rgb/1311868183.300363.png 1311868183.294638 depth/1311868183.294638.png +1311868183.336308 rgb/1311868183.336308.png 1311868183.325625 depth/1311868183.325625.png +1311868183.368469 rgb/1311868183.368469.png 1311868183.362204 depth/1311868183.362204.png +1311868183.400232 rgb/1311868183.400232.png 1311868183.393435 depth/1311868183.393435.png +1311868183.436153 rgb/1311868183.436153.png 1311868183.427013 depth/1311868183.427013.png +1311868183.468217 rgb/1311868183.468217.png 1311868183.462872 depth/1311868183.462872.png +1311868183.500255 rgb/1311868183.500255.png 1311868183.494510 depth/1311868183.494510.png +1311868183.536275 rgb/1311868183.536275.png 1311868183.526761 depth/1311868183.526761.png +1311868183.568369 rgb/1311868183.568369.png 1311868183.561686 depth/1311868183.561686.png +1311868183.600217 rgb/1311868183.600217.png 1311868183.593533 depth/1311868183.593533.png +1311868183.636216 rgb/1311868183.636216.png 1311868183.626579 depth/1311868183.626579.png +1311868183.668587 rgb/1311868183.668587.png 1311868183.663689 depth/1311868183.663689.png +1311868183.700230 rgb/1311868183.700230.png 1311868183.693292 depth/1311868183.693292.png +1311868183.736414 rgb/1311868183.736414.png 1311868183.725733 depth/1311868183.725733.png +1311868183.768221 rgb/1311868183.768221.png 1311868183.762136 depth/1311868183.762136.png +1311868183.800370 rgb/1311868183.800370.png 1311868183.793340 depth/1311868183.793340.png +1311868183.836230 rgb/1311868183.836230.png 1311868183.825722 depth/1311868183.825722.png +1311868183.868506 rgb/1311868183.868506.png 1311868183.861495 depth/1311868183.861495.png +1311868183.900249 rgb/1311868183.900249.png 1311868183.895185 depth/1311868183.895185.png +1311868183.936316 rgb/1311868183.936316.png 1311868183.925453 depth/1311868183.925453.png +1311868183.968498 rgb/1311868183.968498.png 1311868183.964203 depth/1311868183.964203.png +1311868184.000440 rgb/1311868184.000440.png 1311868183.998854 depth/1311868183.998854.png +1311868184.036316 rgb/1311868184.036316.png 1311868184.029638 depth/1311868184.029638.png +1311868184.070267 rgb/1311868184.070267.png 1311868184.065428 depth/1311868184.065428.png +1311868184.100684 rgb/1311868184.100684.png 1311868184.097360 depth/1311868184.097360.png +1311868184.136827 rgb/1311868184.136827.png 1311868184.131161 depth/1311868184.131161.png +1311868184.169015 rgb/1311868184.169015.png 1311868184.164337 depth/1311868184.164337.png +1311868184.200464 rgb/1311868184.200464.png 1311868184.194772 depth/1311868184.194772.png +1311868184.236434 rgb/1311868184.236434.png 1311868184.227431 depth/1311868184.227431.png +1311868184.268504 rgb/1311868184.268504.png 1311868184.265642 depth/1311868184.265642.png +1311868184.300643 rgb/1311868184.300643.png 1311868184.294755 depth/1311868184.294755.png +1311868184.336293 rgb/1311868184.336293.png 1311868184.325312 depth/1311868184.325312.png +1311868184.368210 rgb/1311868184.368210.png 1311868184.366284 depth/1311868184.366284.png +1311868184.400303 rgb/1311868184.400303.png 1311868184.393954 depth/1311868184.393954.png +1311868184.436272 rgb/1311868184.436272.png 1311868184.426497 depth/1311868184.426497.png +1311868184.468412 rgb/1311868184.468412.png 1311868184.464418 depth/1311868184.464418.png +1311868184.500438 rgb/1311868184.500438.png 1311868184.497646 depth/1311868184.497646.png +1311868184.536326 rgb/1311868184.536326.png 1311868184.528277 depth/1311868184.528277.png +1311868184.568437 rgb/1311868184.568437.png 1311868184.561422 depth/1311868184.561422.png +1311868184.600381 rgb/1311868184.600381.png 1311868184.594532 depth/1311868184.594532.png +1311868184.636350 rgb/1311868184.636350.png 1311868184.632774 depth/1311868184.632774.png +1311868184.668352 rgb/1311868184.668352.png 1311868184.664162 depth/1311868184.664162.png +1311868184.700710 rgb/1311868184.700710.png 1311868184.693635 depth/1311868184.693635.png +1311868184.736501 rgb/1311868184.736501.png 1311868184.731115 depth/1311868184.731115.png +1311868184.768456 rgb/1311868184.768456.png 1311868184.762298 depth/1311868184.762298.png +1311868184.800366 rgb/1311868184.800366.png 1311868184.796163 depth/1311868184.796163.png +1311868184.836324 rgb/1311868184.836324.png 1311868184.833854 depth/1311868184.833854.png +1311868184.868735 rgb/1311868184.868735.png 1311868184.863723 depth/1311868184.863723.png +1311868184.900445 rgb/1311868184.900445.png 1311868184.894504 depth/1311868184.894504.png +1311868184.936308 rgb/1311868184.936308.png 1311868184.929521 depth/1311868184.929521.png +1311868184.968436 rgb/1311868184.968436.png 1311868184.964801 depth/1311868184.964801.png +1311868185.000422 rgb/1311868185.000422.png 1311868184.997771 depth/1311868184.997771.png +1311868185.036432 rgb/1311868185.036432.png 1311868185.032688 depth/1311868185.032688.png +1311868185.068440 rgb/1311868185.068440.png 1311868185.065252 depth/1311868185.065252.png +1311868185.100898 rgb/1311868185.100898.png 1311868185.094927 depth/1311868185.094927.png +1311868185.136538 rgb/1311868185.136538.png 1311868185.131256 depth/1311868185.131256.png +1311868185.168559 rgb/1311868185.168559.png 1311868185.163261 depth/1311868185.163261.png +1311868185.200754 rgb/1311868185.200754.png 1311868185.195260 depth/1311868185.195260.png +1311868185.236390 rgb/1311868185.236390.png 1311868185.230718 depth/1311868185.230718.png +1311868185.268543 rgb/1311868185.268543.png 1311868185.261566 depth/1311868185.261566.png +1311868185.300484 rgb/1311868185.300484.png 1311868185.295784 depth/1311868185.295784.png +1311868185.337903 rgb/1311868185.337903.png 1311868185.330870 depth/1311868185.330870.png +1311868185.368510 rgb/1311868185.368510.png 1311868185.365297 depth/1311868185.365297.png +1311868185.401199 rgb/1311868185.401199.png 1311868185.395355 depth/1311868185.395355.png +1311868185.436438 rgb/1311868185.436438.png 1311868185.430442 depth/1311868185.430442.png +1311868185.468575 rgb/1311868185.468575.png 1311868185.462286 depth/1311868185.462286.png +1311868185.500443 rgb/1311868185.500443.png 1311868185.498438 depth/1311868185.498438.png +1311868185.536414 rgb/1311868185.536414.png 1311868185.529876 depth/1311868185.529876.png +1311868185.568460 rgb/1311868185.568460.png 1311868185.561420 depth/1311868185.561420.png +1311868185.600364 rgb/1311868185.600364.png 1311868185.593407 depth/1311868185.593407.png +1311868185.636409 rgb/1311868185.636409.png 1311868185.631497 depth/1311868185.631497.png +1311868185.668624 rgb/1311868185.668624.png 1311868185.664412 depth/1311868185.664412.png +1311868185.701972 rgb/1311868185.701972.png 1311868185.696702 depth/1311868185.696702.png +1311868185.736700 rgb/1311868185.736700.png 1311868185.729373 depth/1311868185.729373.png +1311868185.768630 rgb/1311868185.768630.png 1311868185.761504 depth/1311868185.761504.png +1311868185.800441 rgb/1311868185.800441.png 1311868185.797812 depth/1311868185.797812.png +1311868185.836824 rgb/1311868185.836824.png 1311868185.831964 depth/1311868185.831964.png +1311868185.868447 rgb/1311868185.868447.png 1311868185.865112 depth/1311868185.865112.png +1311868185.900384 rgb/1311868185.900384.png 1311868185.900213 depth/1311868185.900213.png +1311868185.936471 rgb/1311868185.936471.png 1311868185.930809 depth/1311868185.930809.png +1311868185.968391 rgb/1311868185.968391.png 1311868185.962781 depth/1311868185.962781.png +1311868186.000413 rgb/1311868186.000413.png 1311868186.000459 depth/1311868186.000459.png +1311868186.036453 rgb/1311868186.036453.png 1311868186.029395 depth/1311868186.029395.png +1311868186.068672 rgb/1311868186.068672.png 1311868186.062642 depth/1311868186.062642.png +1311868186.103248 rgb/1311868186.103248.png 1311868186.103255 depth/1311868186.103255.png +1311868186.136633 rgb/1311868186.136633.png 1311868186.131039 depth/1311868186.131039.png +1311868186.168524 rgb/1311868186.168524.png 1311868186.162711 depth/1311868186.162711.png +1311868186.200391 rgb/1311868186.200391.png 1311868186.198710 depth/1311868186.198710.png +1311868186.237659 rgb/1311868186.237659.png 1311868186.231643 depth/1311868186.231643.png +1311868186.268650 rgb/1311868186.268650.png 1311868186.263250 depth/1311868186.263250.png +1311868186.300401 rgb/1311868186.300401.png 1311868186.297487 depth/1311868186.297487.png +1311868186.336402 rgb/1311868186.336402.png 1311868186.332293 depth/1311868186.332293.png +1311868186.368410 rgb/1311868186.368410.png 1311868186.364448 depth/1311868186.364448.png +1311868186.400544 rgb/1311868186.400544.png 1311868186.400205 depth/1311868186.400205.png +1311868186.436523 rgb/1311868186.436523.png 1311868186.431456 depth/1311868186.431456.png +1311868186.468526 rgb/1311868186.468526.png 1311868186.465585 depth/1311868186.465585.png +1311868186.500490 rgb/1311868186.500490.png 1311868186.498497 depth/1311868186.498497.png +1311868186.537052 rgb/1311868186.537052.png 1311868186.529775 depth/1311868186.529775.png +1311868186.568549 rgb/1311868186.568549.png 1311868186.565656 depth/1311868186.565656.png +1311868186.600576 rgb/1311868186.600576.png 1311868186.597659 depth/1311868186.597659.png +1311868186.636497 rgb/1311868186.636497.png 1311868186.632110 depth/1311868186.632110.png +1311868186.668623 rgb/1311868186.668623.png 1311868186.665093 depth/1311868186.665093.png +1311868186.702517 rgb/1311868186.702517.png 1311868186.702525 depth/1311868186.702525.png +1311868186.736720 rgb/1311868186.736720.png 1311868186.730707 depth/1311868186.730707.png +1311868186.768504 rgb/1311868186.768504.png 1311868186.764423 depth/1311868186.764423.png +1311868186.800524 rgb/1311868186.800524.png 1311868186.799103 depth/1311868186.799103.png +1311868186.836721 rgb/1311868186.836721.png 1311868186.832462 depth/1311868186.832462.png +1311868186.869317 rgb/1311868186.869317.png 1311868186.867740 depth/1311868186.867740.png +1311868186.900515 rgb/1311868186.900515.png 1311868186.900525 depth/1311868186.900525.png +1311868186.936400 rgb/1311868186.936400.png 1311868186.930682 depth/1311868186.930682.png +1311868186.968636 rgb/1311868186.968636.png 1311868186.963995 depth/1311868186.963995.png +1311868187.000505 rgb/1311868187.000505.png 1311868186.997592 depth/1311868186.997592.png +1311868187.036707 rgb/1311868187.036707.png 1311868187.032681 depth/1311868187.032681.png +1311868187.068458 rgb/1311868187.068458.png 1311868187.068252 depth/1311868187.068252.png +1311868187.101696 rgb/1311868187.101696.png 1311868187.101780 depth/1311868187.101780.png +1311868187.136587 rgb/1311868187.136587.png 1311868187.129856 depth/1311868187.129856.png +1311868187.169000 rgb/1311868187.169000.png 1311868187.169019 depth/1311868187.169019.png +1311868187.201269 rgb/1311868187.201269.png 1311868187.201451 depth/1311868187.201451.png +1311868187.236433 rgb/1311868187.236433.png 1311868187.229725 depth/1311868187.229725.png +1311868187.268822 rgb/1311868187.268822.png 1311868187.267911 depth/1311868187.267911.png +1311868187.300515 rgb/1311868187.300515.png 1311868187.297598 depth/1311868187.297598.png +1311868187.336611 rgb/1311868187.336611.png 1311868187.329539 depth/1311868187.329539.png +1311868187.368415 rgb/1311868187.368415.png 1311868187.366889 depth/1311868187.366889.png +1311868187.400493 rgb/1311868187.400493.png 1311868187.398190 depth/1311868187.398190.png +1311868187.436706 rgb/1311868187.436706.png 1311868187.429671 depth/1311868187.429671.png +1311868187.468568 rgb/1311868187.468568.png 1311868187.466043 depth/1311868187.466043.png +1311868187.500548 rgb/1311868187.500548.png 1311868187.499103 depth/1311868187.499103.png +1311868187.537564 rgb/1311868187.537564.png 1311868187.533630 depth/1311868187.533630.png +1311868187.568523 rgb/1311868187.568523.png 1311868187.567265 depth/1311868187.567265.png +1311868187.600502 rgb/1311868187.600502.png 1311868187.599855 depth/1311868187.599855.png +1311868187.636477 rgb/1311868187.636477.png 1311868187.630800 depth/1311868187.630800.png +1311868187.668730 rgb/1311868187.668730.png 1311868187.668744 depth/1311868187.668744.png +1311868187.700555 rgb/1311868187.700555.png 1311868187.702510 depth/1311868187.702510.png +1311868187.736522 rgb/1311868187.736522.png 1311868187.730639 depth/1311868187.730639.png +1311868187.768746 rgb/1311868187.768746.png 1311868187.765606 depth/1311868187.765606.png +1311868187.800538 rgb/1311868187.800538.png 1311868187.797602 depth/1311868187.797602.png +1311868187.837466 rgb/1311868187.837466.png 1311868187.831569 depth/1311868187.831569.png +1311868187.868577 rgb/1311868187.868577.png 1311868187.868610 depth/1311868187.868610.png +1311868187.900542 rgb/1311868187.900542.png 1311868187.897895 depth/1311868187.897895.png +1311868187.936595 rgb/1311868187.936595.png 1311868187.930750 depth/1311868187.930750.png +1311868187.968459 rgb/1311868187.968459.png 1311868187.965630 depth/1311868187.965630.png +1311868188.000735 rgb/1311868188.000735.png 1311868187.999806 depth/1311868187.999806.png +1311868188.036686 rgb/1311868188.036686.png 1311868188.032674 depth/1311868188.032674.png +1311868188.068520 rgb/1311868188.068520.png 1311868188.065787 depth/1311868188.065787.png +1311868188.100428 rgb/1311868188.100428.png 1311868188.099538 depth/1311868188.099538.png +1311868188.136705 rgb/1311868188.136705.png 1311868188.129752 depth/1311868188.129752.png +1311868188.169752 rgb/1311868188.169752.png 1311868188.169761 depth/1311868188.169761.png +1311868188.200610 rgb/1311868188.200610.png 1311868188.198653 depth/1311868188.198653.png +1311868188.236529 rgb/1311868188.236529.png 1311868188.231993 depth/1311868188.231993.png +1311868188.268577 rgb/1311868188.268577.png 1311868188.268589 depth/1311868188.268589.png +1311868188.300900 rgb/1311868188.300900.png 1311868188.300915 depth/1311868188.300915.png +1311868188.336811 rgb/1311868188.336811.png 1311868188.336856 depth/1311868188.336856.png +1311868188.368537 rgb/1311868188.368537.png 1311868188.368551 depth/1311868188.368551.png +1311868188.400512 rgb/1311868188.400512.png 1311868188.397902 depth/1311868188.397902.png +1311868188.437067 rgb/1311868188.437067.png 1311868188.437076 depth/1311868188.437076.png +1311868188.468574 rgb/1311868188.468574.png 1311868188.466426 depth/1311868188.466426.png +1311868188.502489 rgb/1311868188.502489.png 1311868188.502757 depth/1311868188.502757.png +1311868188.537539 rgb/1311868188.537539.png 1311868188.537698 depth/1311868188.537698.png +1311868188.568686 rgb/1311868188.568686.png 1311868188.565863 depth/1311868188.565863.png +1311868188.601444 rgb/1311868188.601444.png 1311868188.601456 depth/1311868188.601456.png +1311868188.637504 rgb/1311868188.637504.png 1311868188.637522 depth/1311868188.637522.png +1311868188.668666 rgb/1311868188.668666.png 1311868188.666127 depth/1311868188.666127.png +1311868188.703460 rgb/1311868188.703460.png 1311868188.698743 depth/1311868188.698743.png +1311868188.736639 rgb/1311868188.736639.png 1311868188.736650 depth/1311868188.736650.png +1311868188.768663 rgb/1311868188.768663.png 1311868188.766731 depth/1311868188.766731.png +1311868188.800670 rgb/1311868188.800670.png 1311868188.799224 depth/1311868188.799224.png +1311868188.836521 rgb/1311868188.836521.png 1311868188.834136 depth/1311868188.834136.png +1311868188.868469 rgb/1311868188.868469.png 1311868188.868490 depth/1311868188.868490.png +1311868188.900697 rgb/1311868188.900697.png 1311868188.897980 depth/1311868188.897980.png +1311868188.936521 rgb/1311868188.936521.png 1311868188.936530 depth/1311868188.936530.png +1311868188.968696 rgb/1311868188.968696.png 1311868188.965787 depth/1311868188.965787.png +1311868189.000574 rgb/1311868189.000574.png 1311868188.998315 depth/1311868188.998315.png +1311868189.036870 rgb/1311868189.036870.png 1311868189.042396 depth/1311868189.042396.png +1311868189.068620 rgb/1311868189.068620.png 1311868189.067516 depth/1311868189.067516.png +1311868189.100649 rgb/1311868189.100649.png 1311868189.097816 depth/1311868189.097816.png +1311868189.136620 rgb/1311868189.136620.png 1311868189.136023 depth/1311868189.136023.png +1311868189.168589 rgb/1311868189.168589.png 1311868189.167471 depth/1311868189.167471.png +1311868189.201174 rgb/1311868189.201174.png 1311868189.198871 depth/1311868189.198871.png +1311868189.238292 rgb/1311868189.238292.png 1311868189.244009 depth/1311868189.244009.png +1311868189.268669 rgb/1311868189.268669.png 1311868189.266412 depth/1311868189.266412.png +1311868189.302276 rgb/1311868189.302276.png 1311868189.302764 depth/1311868189.302764.png +1311868189.337870 rgb/1311868189.337870.png 1311868189.335967 depth/1311868189.335967.png +1311868189.368446 rgb/1311868189.368446.png 1311868189.367497 depth/1311868189.367497.png +1311868189.400547 rgb/1311868189.400547.png 1311868189.398091 depth/1311868189.398091.png +1311868189.436651 rgb/1311868189.436651.png 1311868189.433995 depth/1311868189.433995.png +1311868189.468797 rgb/1311868189.468797.png 1311868189.468848 depth/1311868189.468848.png +1311868189.500573 rgb/1311868189.500573.png 1311868189.499832 depth/1311868189.499832.png +1311868189.536633 rgb/1311868189.536633.png 1311868189.535532 depth/1311868189.535532.png +1311868189.568724 rgb/1311868189.568724.png 1311868189.566072 depth/1311868189.566072.png +1311868189.601920 rgb/1311868189.601920.png 1311868189.601927 depth/1311868189.601927.png +1311868189.636729 rgb/1311868189.636729.png 1311868189.636736 depth/1311868189.636736.png +1311868189.668663 rgb/1311868189.668663.png 1311868189.666056 depth/1311868189.666056.png +1311868189.704376 rgb/1311868189.704376.png 1311868189.704390 depth/1311868189.704390.png +1311868189.736593 rgb/1311868189.736593.png 1311868189.733822 depth/1311868189.733822.png +1311868189.768868 rgb/1311868189.768868.png 1311868189.765987 depth/1311868189.765987.png +1311868189.802939 rgb/1311868189.802939.png 1311868189.802943 depth/1311868189.802943.png +1311868189.836562 rgb/1311868189.836562.png 1311868189.835567 depth/1311868189.835567.png +1311868189.868685 rgb/1311868189.868685.png 1311868189.865810 depth/1311868189.865810.png +1311868189.902037 rgb/1311868189.902037.png 1311868189.902057 depth/1311868189.902057.png +1311868189.936714 rgb/1311868189.936714.png 1311868189.934126 depth/1311868189.934126.png +1311868189.968616 rgb/1311868189.968616.png 1311868189.966738 depth/1311868189.966738.png +1311868190.002005 rgb/1311868190.002005.png 1311868190.002015 depth/1311868190.002015.png +1311868190.036745 rgb/1311868190.036745.png 1311868190.033893 depth/1311868190.033893.png +1311868190.068604 rgb/1311868190.068604.png 1311868190.065911 depth/1311868190.065911.png +1311868190.104099 rgb/1311868190.104099.png 1311868190.104109 depth/1311868190.104109.png +1311868190.136685 rgb/1311868190.136685.png 1311868190.133886 depth/1311868190.133886.png +1311868190.168751 rgb/1311868190.168751.png 1311868190.166060 depth/1311868190.166060.png +1311868190.202446 rgb/1311868190.202446.png 1311868190.202456 depth/1311868190.202456.png +1311868190.236836 rgb/1311868190.236836.png 1311868190.233912 depth/1311868190.233912.png +1311868190.268616 rgb/1311868190.268616.png 1311868190.268216 depth/1311868190.268216.png +1311868190.302512 rgb/1311868190.302512.png 1311868190.302524 depth/1311868190.302524.png +1311868190.336668 rgb/1311868190.336668.png 1311868190.334219 depth/1311868190.334219.png +1311868190.369230 rgb/1311868190.369230.png 1311868190.366015 depth/1311868190.366015.png +1311868190.401976 rgb/1311868190.401976.png 1311868190.401989 depth/1311868190.401989.png +1311868190.436649 rgb/1311868190.436649.png 1311868190.433995 depth/1311868190.433995.png +1311868190.468862 rgb/1311868190.468862.png 1311868190.466043 depth/1311868190.466043.png +1311868190.503067 rgb/1311868190.503067.png 1311868190.503079 depth/1311868190.503079.png +1311868190.536577 rgb/1311868190.536577.png 1311868190.535552 depth/1311868190.535552.png +1311868190.568647 rgb/1311868190.568647.png 1311868190.567335 depth/1311868190.567335.png +1311868190.604416 rgb/1311868190.604416.png 1311868190.604442 depth/1311868190.604442.png +1311868190.636584 rgb/1311868190.636584.png 1311868190.634777 depth/1311868190.634777.png +1311868190.668720 rgb/1311868190.668720.png 1311868190.665967 depth/1311868190.665967.png +1311868190.708899 rgb/1311868190.708899.png 1311868190.706805 depth/1311868190.706805.png +1311868190.736730 rgb/1311868190.736730.png 1311868190.735686 depth/1311868190.735686.png +1311868190.771375 rgb/1311868190.771375.png 1311868190.771383 depth/1311868190.771383.png +1311868190.802394 rgb/1311868190.802394.png 1311868190.802404 depth/1311868190.802404.png +1311868190.836629 rgb/1311868190.836629.png 1311868190.834340 depth/1311868190.834340.png +1311868190.870368 rgb/1311868190.870368.png 1311868190.870372 depth/1311868190.870372.png +1311868190.902257 rgb/1311868190.902257.png 1311868190.902535 depth/1311868190.902535.png +1311868190.936594 rgb/1311868190.936594.png 1311868190.934315 depth/1311868190.934315.png +1311868190.970309 rgb/1311868190.970309.png 1311868190.970320 depth/1311868190.970320.png +1311868191.004252 rgb/1311868191.004252.png 1311868191.004259 depth/1311868191.004259.png +1311868191.036646 rgb/1311868191.036646.png 1311868191.034135 depth/1311868191.034135.png +1311868191.074967 rgb/1311868191.074967.png 1311868191.074973 depth/1311868191.074973.png +1311868191.102905 rgb/1311868191.102905.png 1311868191.102919 depth/1311868191.102919.png +1311868191.136667 rgb/1311868191.136667.png 1311868191.134645 depth/1311868191.134645.png +1311868191.170379 rgb/1311868191.170379.png 1311868191.170391 depth/1311868191.170391.png +1311868191.204730 rgb/1311868191.204730.png 1311868191.204203 depth/1311868191.204203.png +1311868191.236855 rgb/1311868191.236855.png 1311868191.234459 depth/1311868191.234459.png +1311868191.270521 rgb/1311868191.270521.png 1311868191.270582 depth/1311868191.270582.png +1311868191.305138 rgb/1311868191.305138.png 1311868191.305161 depth/1311868191.305161.png +1311868191.336788 rgb/1311868191.336788.png 1311868191.335917 depth/1311868191.335917.png +1311868191.370175 rgb/1311868191.370175.png 1311868191.370183 depth/1311868191.370183.png +1311868191.408020 rgb/1311868191.408020.png 1311868191.404166 depth/1311868191.404166.png +1311868191.436687 rgb/1311868191.436687.png 1311868191.434025 depth/1311868191.434025.png +1311868191.470045 rgb/1311868191.470045.png 1311868191.470054 depth/1311868191.470054.png +1311868191.505579 rgb/1311868191.505579.png 1311868191.503245 depth/1311868191.503245.png +1311868191.536752 rgb/1311868191.536752.png 1311868191.534020 depth/1311868191.534020.png +1311868191.570203 rgb/1311868191.570203.png 1311868191.570221 depth/1311868191.570221.png +1311868191.604658 rgb/1311868191.604658.png 1311868191.602059 depth/1311868191.602059.png +1311868191.636913 rgb/1311868191.636913.png 1311868191.635708 depth/1311868191.635708.png +1311868191.670782 rgb/1311868191.670782.png 1311868191.670789 depth/1311868191.670789.png +1311868191.705077 rgb/1311868191.705077.png 1311868191.701998 depth/1311868191.701998.png +1311868191.736754 rgb/1311868191.736754.png 1311868191.734633 depth/1311868191.734633.png +1311868191.771559 rgb/1311868191.771559.png 1311868191.771577 depth/1311868191.771577.png +1311868191.804765 rgb/1311868191.804765.png 1311868191.802566 depth/1311868191.802566.png +1311868191.836740 rgb/1311868191.836740.png 1311868191.834152 depth/1311868191.834152.png +1311868191.872176 rgb/1311868191.872176.png 1311868191.872199 depth/1311868191.872199.png +1311868191.904702 rgb/1311868191.904702.png 1311868191.902089 depth/1311868191.902089.png +1311868191.936673 rgb/1311868191.936673.png 1311868191.934645 depth/1311868191.934645.png +1311868191.970293 rgb/1311868191.970293.png 1311868191.970309 depth/1311868191.970309.png +1311868192.005218 rgb/1311868192.005218.png 1311868192.002518 depth/1311868192.002518.png +1311868192.038266 rgb/1311868192.038266.png 1311868192.038276 depth/1311868192.038276.png +1311868192.070578 rgb/1311868192.070578.png 1311868192.070588 depth/1311868192.070588.png +1311868192.105561 rgb/1311868192.105561.png 1311868192.102192 depth/1311868192.102192.png +1311868192.139401 rgb/1311868192.139401.png 1311868192.139413 depth/1311868192.139413.png +1311868192.173682 rgb/1311868192.173682.png 1311868192.173696 depth/1311868192.173696.png +1311868192.204710 rgb/1311868192.204710.png 1311868192.203139 depth/1311868192.203139.png +1311868192.240525 rgb/1311868192.240525.png 1311868192.240535 depth/1311868192.240535.png +1311868192.271675 rgb/1311868192.271675.png 1311868192.271684 depth/1311868192.271684.png +1311868192.304674 rgb/1311868192.304674.png 1311868192.302347 depth/1311868192.302347.png +1311868192.342496 rgb/1311868192.342496.png 1311868192.342506 depth/1311868192.342506.png +1311868192.370163 rgb/1311868192.370163.png 1311868192.370177 depth/1311868192.370177.png +1311868192.404725 rgb/1311868192.404725.png 1311868192.402524 depth/1311868192.402524.png +1311868192.438459 rgb/1311868192.438459.png 1311868192.438489 depth/1311868192.438489.png +1311868192.471387 rgb/1311868192.471387.png 1311868192.471399 depth/1311868192.471399.png +1311868192.504708 rgb/1311868192.504708.png 1311868192.502226 depth/1311868192.502226.png +1311868192.540878 rgb/1311868192.540878.png 1311868192.540885 depth/1311868192.540885.png +1311868192.571208 rgb/1311868192.571208.png 1311868192.571226 depth/1311868192.571226.png +1311868192.604784 rgb/1311868192.604784.png 1311868192.603057 depth/1311868192.603057.png +1311868192.641130 rgb/1311868192.641130.png 1311868192.640802 depth/1311868192.640802.png +1311868192.670331 rgb/1311868192.670331.png 1311868192.670341 depth/1311868192.670341.png +1311868192.704764 rgb/1311868192.704764.png 1311868192.702955 depth/1311868192.702955.png +1311868192.739392 rgb/1311868192.739392.png 1311868192.739404 depth/1311868192.739404.png +1311868192.770014 rgb/1311868192.770014.png 1311868192.770022 depth/1311868192.770022.png +1311868192.804785 rgb/1311868192.804785.png 1311868192.802140 depth/1311868192.802140.png +1311868192.838042 rgb/1311868192.838042.png 1311868192.838070 depth/1311868192.838070.png +1311868192.870604 rgb/1311868192.870604.png 1311868192.870622 depth/1311868192.870622.png +1311868192.904715 rgb/1311868192.904715.png 1311868192.902442 depth/1311868192.902442.png +1311868192.940507 rgb/1311868192.940507.png 1311868192.940521 depth/1311868192.940521.png +1311868192.970299 rgb/1311868192.970299.png 1311868192.970546 depth/1311868192.970546.png +1311868193.004778 rgb/1311868193.004778.png 1311868193.004227 depth/1311868193.004227.png +1311868193.038080 rgb/1311868193.038080.png 1311868193.038088 depth/1311868193.038088.png +1311868193.070262 rgb/1311868193.070262.png 1311868193.070274 depth/1311868193.070274.png +1311868193.105256 rgb/1311868193.105256.png 1311868193.104514 depth/1311868193.104514.png +1311868193.140696 rgb/1311868193.140696.png 1311868193.140748 depth/1311868193.140748.png +1311868193.172573 rgb/1311868193.172573.png 1311868193.172593 depth/1311868193.172593.png +1311868193.205121 rgb/1311868193.205121.png 1311868193.203431 depth/1311868193.203431.png +1311868193.238476 rgb/1311868193.238476.png 1311868193.238522 depth/1311868193.238522.png +1311868193.270506 rgb/1311868193.270506.png 1311868193.270532 depth/1311868193.270532.png +1311868193.309034 rgb/1311868193.309034.png 1311868193.309045 depth/1311868193.309045.png +1311868193.340807 rgb/1311868193.340807.png 1311868193.340814 depth/1311868193.340814.png +1311868193.370907 rgb/1311868193.370907.png 1311868193.370916 depth/1311868193.370916.png +1311868193.409261 rgb/1311868193.409261.png 1311868193.409280 depth/1311868193.409280.png +1311868193.438985 rgb/1311868193.438985.png 1311868193.438729 depth/1311868193.438729.png +1311868193.473196 rgb/1311868193.473196.png 1311868193.473222 depth/1311868193.473222.png +1311868193.507782 rgb/1311868193.507782.png 1311868193.508086 depth/1311868193.508086.png +1311868193.541208 rgb/1311868193.541208.png 1311868193.541226 depth/1311868193.541226.png +1311868193.573764 rgb/1311868193.573764.png 1311868193.573781 depth/1311868193.573781.png +1311868193.605992 rgb/1311868193.605992.png 1311868193.606002 depth/1311868193.606002.png +1311868193.640297 rgb/1311868193.640297.png 1311868193.640306 depth/1311868193.640306.png +1311868193.670172 rgb/1311868193.670172.png 1311868193.670184 depth/1311868193.670184.png +1311868193.710143 rgb/1311868193.710143.png 1311868193.710151 depth/1311868193.710151.png +1311868193.738312 rgb/1311868193.738312.png 1311868193.738320 depth/1311868193.738320.png +1311868193.771597 rgb/1311868193.771597.png 1311868193.771612 depth/1311868193.771612.png +1311868193.809392 rgb/1311868193.809392.png 1311868193.809409 depth/1311868193.809409.png +1311868193.838095 rgb/1311868193.838095.png 1311868193.838099 depth/1311868193.838099.png +1311868193.873184 rgb/1311868193.873184.png 1311868193.873191 depth/1311868193.873191.png +1311868193.909419 rgb/1311868193.909419.png 1311868193.909428 depth/1311868193.909428.png +1311868193.938105 rgb/1311868193.938105.png 1311868193.938115 depth/1311868193.938115.png +1311868193.972816 rgb/1311868193.972816.png 1311868193.972826 depth/1311868193.972826.png +1311868194.009150 rgb/1311868194.009150.png 1311868194.009159 depth/1311868194.009159.png +1311868194.038215 rgb/1311868194.038215.png 1311868194.038257 depth/1311868194.038257.png +1311868194.071381 rgb/1311868194.071381.png 1311868194.071393 depth/1311868194.071393.png +1311868194.108743 rgb/1311868194.108743.png 1311868194.108767 depth/1311868194.108767.png +1311868194.140638 rgb/1311868194.140638.png 1311868194.140647 depth/1311868194.140647.png +1311868194.172673 rgb/1311868194.172673.png 1311868194.172696 depth/1311868194.172696.png +1311868194.209517 rgb/1311868194.209517.png 1311868194.209560 depth/1311868194.209560.png +1311868194.243018 rgb/1311868194.243018.png 1311868194.243103 depth/1311868194.243103.png +1311868194.270035 rgb/1311868194.270035.png 1311868194.270044 depth/1311868194.270044.png +1311868194.309378 rgb/1311868194.309378.png 1311868194.309425 depth/1311868194.309425.png +1311868194.339184 rgb/1311868194.339184.png 1311868194.339216 depth/1311868194.339216.png +1311868194.370242 rgb/1311868194.370242.png 1311868194.370251 depth/1311868194.370251.png +1311868194.408223 rgb/1311868194.408223.png 1311868194.408235 depth/1311868194.408235.png +1311868194.439940 rgb/1311868194.439940.png 1311868194.439954 depth/1311868194.439954.png +1311868194.468912 rgb/1311868194.468912.png 1311868194.479894 depth/1311868194.479894.png +1311868194.508854 rgb/1311868194.508854.png 1311868194.508914 depth/1311868194.508914.png +1311868194.538360 rgb/1311868194.538360.png 1311868194.538378 depth/1311868194.538378.png +1311868194.568867 rgb/1311868194.568867.png 1311868194.575743 depth/1311868194.575743.png +1311868194.609529 rgb/1311868194.609529.png 1311868194.609573 depth/1311868194.609573.png +1311868194.645036 rgb/1311868194.645036.png 1311868194.644750 depth/1311868194.644750.png +1311868194.669010 rgb/1311868194.669010.png 1311868194.675892 depth/1311868194.675892.png +1311868194.710055 rgb/1311868194.710055.png 1311868194.710102 depth/1311868194.710102.png +1311868194.740970 rgb/1311868194.740970.png 1311868194.740981 depth/1311868194.740981.png +1311868194.768994 rgb/1311868194.768994.png 1311868194.775988 depth/1311868194.775988.png +1311868194.806949 rgb/1311868194.806949.png 1311868194.806957 depth/1311868194.806957.png +1311868194.842311 rgb/1311868194.842311.png 1311868194.842323 depth/1311868194.842323.png +1311868194.868966 rgb/1311868194.868966.png 1311868194.876176 depth/1311868194.876176.png +1311868194.909237 rgb/1311868194.909237.png 1311868194.909258 depth/1311868194.909258.png +1311868194.942724 rgb/1311868194.942724.png 1311868194.942743 depth/1311868194.942743.png +1311868194.968884 rgb/1311868194.968884.png 1311868194.974494 depth/1311868194.974494.png +1311868195.009219 rgb/1311868195.009219.png 1311868195.009261 depth/1311868195.009261.png +1311868195.038705 rgb/1311868195.038705.png 1311868195.038716 depth/1311868195.038716.png +1311868195.068954 rgb/1311868195.068954.png 1311868195.080005 depth/1311868195.080005.png +1311868195.109504 rgb/1311868195.109504.png 1311868195.109514 depth/1311868195.109514.png +1311868195.139745 rgb/1311868195.139745.png 1311868195.139752 depth/1311868195.139752.png +1311868195.168943 rgb/1311868195.168943.png 1311868195.174446 depth/1311868195.174446.png +1311868195.208719 rgb/1311868195.208719.png 1311868195.208730 depth/1311868195.208730.png +1311868195.238370 rgb/1311868195.238370.png 1311868195.238377 depth/1311868195.238377.png +1311868195.269090 rgb/1311868195.269090.png 1311868195.277414 depth/1311868195.277414.png +1311868195.314009 rgb/1311868195.314009.png 1311868195.309563 depth/1311868195.309563.png +1311868195.340715 rgb/1311868195.340715.png 1311868195.340732 depth/1311868195.340732.png +1311868195.368984 rgb/1311868195.368984.png 1311868195.375835 depth/1311868195.375835.png +1311868195.409401 rgb/1311868195.409401.png 1311868195.409446 depth/1311868195.409446.png +1311868195.441781 rgb/1311868195.441781.png 1311868195.441795 depth/1311868195.441795.png +1311868195.469182 rgb/1311868195.469182.png 1311868195.475479 depth/1311868195.475479.png +1311868195.508972 rgb/1311868195.508972.png 1311868195.509060 depth/1311868195.509060.png +1311868195.540776 rgb/1311868195.540776.png 1311868195.540792 depth/1311868195.540792.png +1311868195.569178 rgb/1311868195.569178.png 1311868195.576256 depth/1311868195.576256.png +1311868195.607032 rgb/1311868195.607032.png 1311868195.607072 depth/1311868195.607072.png +1311868195.641375 rgb/1311868195.641375.png 1311868195.641383 depth/1311868195.641383.png +1311868195.669012 rgb/1311868195.669012.png 1311868195.674270 depth/1311868195.674270.png +1311868195.710126 rgb/1311868195.710126.png 1311868195.710169 depth/1311868195.710169.png +1311868195.737290 rgb/1311868195.737290.png 1311868195.742482 depth/1311868195.742482.png +1311868195.769034 rgb/1311868195.769034.png 1311868195.778577 depth/1311868195.778577.png +1311868195.808835 rgb/1311868195.808835.png 1311868195.808879 depth/1311868195.808879.png +1311868195.837123 rgb/1311868195.837123.png 1311868195.842970 depth/1311868195.842970.png +1311868195.869116 rgb/1311868195.869116.png 1311868195.874786 depth/1311868195.874786.png +1311868195.906456 rgb/1311868195.906456.png 1311868195.906472 depth/1311868195.906472.png +1311868195.936986 rgb/1311868195.936986.png 1311868195.948982 depth/1311868195.948982.png +1311868195.969019 rgb/1311868195.969019.png 1311868195.976672 depth/1311868195.976672.png +1311868196.009280 rgb/1311868196.009280.png 1311868196.009295 depth/1311868196.009295.png +1311868196.036924 rgb/1311868196.036924.png 1311868196.049302 depth/1311868196.049302.png +1311868196.068988 rgb/1311868196.068988.png 1311868196.083048 depth/1311868196.083048.png +1311868196.107842 rgb/1311868196.107842.png 1311868196.107854 depth/1311868196.107854.png +1311868196.137076 rgb/1311868196.137076.png 1311868196.147737 depth/1311868196.147737.png +1311868196.168888 rgb/1311868196.168888.png 1311868196.174813 depth/1311868196.174813.png +1311868196.208314 rgb/1311868196.208314.png 1311868196.208324 depth/1311868196.208324.png +1311868196.236975 rgb/1311868196.236975.png 1311868196.244116 depth/1311868196.244116.png +1311868196.269144 rgb/1311868196.269144.png 1311868196.279999 depth/1311868196.279999.png +1311868196.307425 rgb/1311868196.307425.png 1311868196.307458 depth/1311868196.307458.png +1311868196.337126 rgb/1311868196.337126.png 1311868196.344161 depth/1311868196.344161.png +1311868196.369056 rgb/1311868196.369056.png 1311868196.380429 depth/1311868196.380429.png +1311868196.410126 rgb/1311868196.410126.png 1311868196.410168 depth/1311868196.410168.png +1311868196.437163 rgb/1311868196.437163.png 1311868196.446202 depth/1311868196.446202.png +1311868196.468966 rgb/1311868196.468966.png 1311868196.479745 depth/1311868196.479745.png +1311868196.507765 rgb/1311868196.507765.png 1311868196.507227 depth/1311868196.507227.png +1311868196.537088 rgb/1311868196.537088.png 1311868196.542843 depth/1311868196.542843.png +1311868196.569054 rgb/1311868196.569054.png 1311868196.578865 depth/1311868196.578865.png +1311868196.610073 rgb/1311868196.610073.png 1311868196.610088 depth/1311868196.610088.png +1311868196.637007 rgb/1311868196.637007.png 1311868196.648433 depth/1311868196.648433.png +1311868196.668957 rgb/1311868196.668957.png 1311868196.674864 depth/1311868196.674864.png +1311868196.709665 rgb/1311868196.709665.png 1311868196.709712 depth/1311868196.709712.png +1311868196.737079 rgb/1311868196.737079.png 1311868196.743666 depth/1311868196.743666.png +1311868196.769084 rgb/1311868196.769084.png 1311868196.780049 depth/1311868196.780049.png +1311868196.807613 rgb/1311868196.807613.png 1311868196.807621 depth/1311868196.807621.png +1311868196.837005 rgb/1311868196.837005.png 1311868196.844319 depth/1311868196.844319.png +1311868196.869030 rgb/1311868196.869030.png 1311868196.876970 depth/1311868196.876970.png +1311868196.909608 rgb/1311868196.909608.png 1311868196.909614 depth/1311868196.909614.png +1311868196.936988 rgb/1311868196.936988.png 1311868196.947288 depth/1311868196.947288.png +1311868196.969198 rgb/1311868196.969198.png 1311868196.978330 depth/1311868196.978330.png +1311868197.005107 rgb/1311868197.005107.png 1311868197.014534 depth/1311868197.014534.png +1311868197.036991 rgb/1311868197.036991.png 1311868197.046602 depth/1311868197.046602.png +1311868197.069116 rgb/1311868197.069116.png 1311868197.077214 depth/1311868197.077214.png +1311868197.105017 rgb/1311868197.105017.png 1311868197.115217 depth/1311868197.115217.png +1311868197.136991 rgb/1311868197.136991.png 1311868197.148846 depth/1311868197.148846.png +1311868197.169013 rgb/1311868197.169013.png 1311868197.176697 depth/1311868197.176697.png +1311868197.205086 rgb/1311868197.205086.png 1311868197.215804 depth/1311868197.215804.png +1311868197.237163 rgb/1311868197.237163.png 1311868197.244642 depth/1311868197.244642.png +1311868197.269183 rgb/1311868197.269183.png 1311868197.278421 depth/1311868197.278421.png +1311868197.305116 rgb/1311868197.305116.png 1311868197.316544 depth/1311868197.316544.png +1311868197.337258 rgb/1311868197.337258.png 1311868197.350515 depth/1311868197.350515.png +1311868197.369073 rgb/1311868197.369073.png 1311868197.374671 depth/1311868197.374671.png +1311868197.405204 rgb/1311868197.405204.png 1311868197.413967 depth/1311868197.413967.png +1311868197.437047 rgb/1311868197.437047.png 1311868197.443603 depth/1311868197.443603.png +1311868197.469173 rgb/1311868197.469173.png 1311868197.478009 depth/1311868197.478009.png +1311868197.505155 rgb/1311868197.505155.png 1311868197.514831 depth/1311868197.514831.png +1311868197.536977 rgb/1311868197.536977.png 1311868197.545046 depth/1311868197.545046.png +1311868197.569185 rgb/1311868197.569185.png 1311868197.578115 depth/1311868197.578115.png +1311868197.605169 rgb/1311868197.605169.png 1311868197.614158 depth/1311868197.614158.png +1311868197.637079 rgb/1311868197.637079.png 1311868197.648960 depth/1311868197.648960.png +1311868197.669130 rgb/1311868197.669130.png 1311868197.677623 depth/1311868197.677623.png +1311868197.705186 rgb/1311868197.705186.png 1311868197.713383 depth/1311868197.713383.png +1311868197.737277 rgb/1311868197.737277.png 1311868197.749245 depth/1311868197.749245.png +1311868197.769193 rgb/1311868197.769193.png 1311868197.777176 depth/1311868197.777176.png +1311868197.805395 rgb/1311868197.805395.png 1311868197.814720 depth/1311868197.814720.png +1311868197.837217 rgb/1311868197.837217.png 1311868197.846941 depth/1311868197.846941.png +1311868197.869114 rgb/1311868197.869114.png 1311868197.877369 depth/1311868197.877369.png +1311868197.905203 rgb/1311868197.905203.png 1311868197.915506 depth/1311868197.915506.png +1311868197.937196 rgb/1311868197.937196.png 1311868197.947225 depth/1311868197.947225.png +1311868197.969193 rgb/1311868197.969193.png 1311868197.976646 depth/1311868197.976646.png +1311868198.005244 rgb/1311868198.005244.png 1311868198.015692 depth/1311868198.015692.png +1311868198.037139 rgb/1311868198.037139.png 1311868198.047426 depth/1311868198.047426.png +1311868198.069220 rgb/1311868198.069220.png 1311868198.077753 depth/1311868198.077753.png +1311868198.105370 rgb/1311868198.105370.png 1311868198.115270 depth/1311868198.115270.png +1311868198.137212 rgb/1311868198.137212.png 1311868198.149620 depth/1311868198.149620.png +1311868198.169159 rgb/1311868198.169159.png 1311868198.180637 depth/1311868198.180637.png +1311868198.205266 rgb/1311868198.205266.png 1311868198.217618 depth/1311868198.217618.png +1311868198.237167 rgb/1311868198.237167.png 1311868198.248693 depth/1311868198.248693.png +1311868198.269205 rgb/1311868198.269205.png 1311868198.283148 depth/1311868198.283148.png +1311868198.305141 rgb/1311868198.305141.png 1311868198.314134 depth/1311868198.314134.png +1311868198.337248 rgb/1311868198.337248.png 1311868198.345640 depth/1311868198.345640.png +1311868198.369167 rgb/1311868198.369167.png 1311868198.385094 depth/1311868198.385094.png +1311868198.405114 rgb/1311868198.405114.png 1311868198.413332 depth/1311868198.413332.png +1311868198.437155 rgb/1311868198.437155.png 1311868198.444494 depth/1311868198.444494.png +1311868198.469161 rgb/1311868198.469161.png 1311868198.482279 depth/1311868198.482279.png +1311868198.505259 rgb/1311868198.505259.png 1311868198.514834 depth/1311868198.514834.png +1311868198.537261 rgb/1311868198.537261.png 1311868198.545660 depth/1311868198.545660.png +1311868198.569178 rgb/1311868198.569178.png 1311868198.582335 depth/1311868198.582335.png +1311868198.605102 rgb/1311868198.605102.png 1311868198.613448 depth/1311868198.613448.png +1311868198.637155 rgb/1311868198.637155.png 1311868198.643839 depth/1311868198.643839.png +1311868198.669124 rgb/1311868198.669124.png 1311868198.680098 depth/1311868198.680098.png +1311868198.705029 rgb/1311868198.705029.png 1311868198.714601 depth/1311868198.714601.png +1311868198.737178 rgb/1311868198.737178.png 1311868198.744612 depth/1311868198.744612.png +1311868198.769148 rgb/1311868198.769148.png 1311868198.781251 depth/1311868198.781251.png +1311868198.805122 rgb/1311868198.805122.png 1311868198.812579 depth/1311868198.812579.png +1311868198.837189 rgb/1311868198.837189.png 1311868198.846157 depth/1311868198.846157.png +1311868198.869154 rgb/1311868198.869154.png 1311868198.882317 depth/1311868198.882317.png +1311868198.905110 rgb/1311868198.905110.png 1311868198.911755 depth/1311868198.911755.png +1311868198.937129 rgb/1311868198.937129.png 1311868198.944555 depth/1311868198.944555.png +1311868198.969249 rgb/1311868198.969249.png 1311868198.983467 depth/1311868198.983467.png +1311868199.005125 rgb/1311868199.005125.png 1311868199.013481 depth/1311868199.013481.png +1311868199.037153 rgb/1311868199.037153.png 1311868199.043568 depth/1311868199.043568.png +1311868199.069162 rgb/1311868199.069162.png 1311868199.080481 depth/1311868199.080481.png +1311868199.105139 rgb/1311868199.105139.png 1311868199.112174 depth/1311868199.112174.png +1311868199.137202 rgb/1311868199.137202.png 1311868199.143350 depth/1311868199.143350.png +1311868199.169310 rgb/1311868199.169310.png 1311868199.180369 depth/1311868199.180369.png +1311868199.205167 rgb/1311868199.205167.png 1311868199.211722 depth/1311868199.211722.png +1311868199.237228 rgb/1311868199.237228.png 1311868199.245452 depth/1311868199.245452.png +1311868199.269349 rgb/1311868199.269349.png 1311868199.280416 depth/1311868199.280416.png +1311868199.305204 rgb/1311868199.305204.png 1311868199.311451 depth/1311868199.311451.png +1311868199.337251 rgb/1311868199.337251.png 1311868199.343792 depth/1311868199.343792.png +1311868199.369357 rgb/1311868199.369357.png 1311868199.381815 depth/1311868199.381815.png +1311868199.405159 rgb/1311868199.405159.png 1311868199.413160 depth/1311868199.413160.png +1311868199.437214 rgb/1311868199.437214.png 1311868199.449365 depth/1311868199.449365.png +1311868199.469396 rgb/1311868199.469396.png 1311868199.481210 depth/1311868199.481210.png +1311868199.505308 rgb/1311868199.505308.png 1311868199.512945 depth/1311868199.512945.png +1311868199.537263 rgb/1311868199.537263.png 1311868199.548273 depth/1311868199.548273.png +1311868199.569325 rgb/1311868199.569325.png 1311868199.580844 depth/1311868199.580844.png +1311868199.605264 rgb/1311868199.605264.png 1311868199.613118 depth/1311868199.613118.png +1311868199.637203 rgb/1311868199.637203.png 1311868199.647673 depth/1311868199.647673.png +1311868199.669160 rgb/1311868199.669160.png 1311868199.681036 depth/1311868199.681036.png +1311868199.705305 rgb/1311868199.705305.png 1311868199.713851 depth/1311868199.713851.png +1311868199.737153 rgb/1311868199.737153.png 1311868199.748271 depth/1311868199.748271.png +1311868199.769136 rgb/1311868199.769136.png 1311868199.781068 depth/1311868199.781068.png +1311868199.805309 rgb/1311868199.805309.png 1311868199.813002 depth/1311868199.813002.png +1311868199.837168 rgb/1311868199.837168.png 1311868199.849238 depth/1311868199.849238.png +1311868199.869232 rgb/1311868199.869232.png 1311868199.881699 depth/1311868199.881699.png +1311868199.905169 rgb/1311868199.905169.png 1311868199.915637 depth/1311868199.915637.png +1311868199.937209 rgb/1311868199.937209.png 1311868199.949425 depth/1311868199.949425.png +1311868199.969272 rgb/1311868199.969272.png 1311868199.981328 depth/1311868199.981328.png +1311868200.005247 rgb/1311868200.005247.png 1311868200.011907 depth/1311868200.011907.png +1311868200.037557 rgb/1311868200.037557.png 1311868200.048486 depth/1311868200.048486.png +1311868200.069418 rgb/1311868200.069418.png 1311868200.080921 depth/1311868200.080921.png +1311868200.105179 rgb/1311868200.105179.png 1311868200.111308 depth/1311868200.111308.png +1311868200.137281 rgb/1311868200.137281.png 1311868200.149780 depth/1311868200.149780.png +1311868200.169388 rgb/1311868200.169388.png 1311868200.182269 depth/1311868200.182269.png +1311868200.205451 rgb/1311868200.205451.png 1311868200.212926 depth/1311868200.212926.png +1311868200.237169 rgb/1311868200.237169.png 1311868200.247733 depth/1311868200.247733.png +1311868200.273397 rgb/1311868200.273397.png 1311868200.280294 depth/1311868200.280294.png +1311868200.305197 rgb/1311868200.305197.png 1311868200.315750 depth/1311868200.315750.png +1311868200.337233 rgb/1311868200.337233.png 1311868200.348252 depth/1311868200.348252.png +1311868200.373427 rgb/1311868200.373427.png 1311868200.380528 depth/1311868200.380528.png +1311868200.405205 rgb/1311868200.405205.png 1311868200.412060 depth/1311868200.412060.png +1311868200.437327 rgb/1311868200.437327.png 1311868200.449108 depth/1311868200.449108.png +1311868200.473305 rgb/1311868200.473305.png 1311868200.485010 depth/1311868200.485010.png +1311868200.505347 rgb/1311868200.505347.png 1311868200.515841 depth/1311868200.515841.png +1311868200.537240 rgb/1311868200.537240.png 1311868200.548967 depth/1311868200.548967.png +1311868200.573293 rgb/1311868200.573293.png 1311868200.582157 depth/1311868200.582157.png +1311868200.605204 rgb/1311868200.605204.png 1311868200.613020 depth/1311868200.613020.png +1311868200.637423 rgb/1311868200.637423.png 1311868200.648629 depth/1311868200.648629.png +1311868200.673455 rgb/1311868200.673455.png 1311868200.679698 depth/1311868200.679698.png +1311868200.705281 rgb/1311868200.705281.png 1311868200.717862 depth/1311868200.717862.png +1311868200.737553 rgb/1311868200.737553.png 1311868200.748941 depth/1311868200.748941.png +1311868200.773365 rgb/1311868200.773365.png 1311868200.779204 depth/1311868200.779204.png +1311868200.805217 rgb/1311868200.805217.png 1311868200.817259 depth/1311868200.817259.png +1311868200.837445 rgb/1311868200.837445.png 1311868200.848927 depth/1311868200.848927.png +1311868200.873224 rgb/1311868200.873224.png 1311868200.881990 depth/1311868200.881990.png +1311868200.905248 rgb/1311868200.905248.png 1311868200.916807 depth/1311868200.916807.png +1311868200.937356 rgb/1311868200.937356.png 1311868200.948795 depth/1311868200.948795.png +1311868200.973447 rgb/1311868200.973447.png 1311868200.981350 depth/1311868200.981350.png +1311868201.005304 rgb/1311868201.005304.png 1311868201.016041 depth/1311868201.016041.png +1311868201.037420 rgb/1311868201.037420.png 1311868201.048622 depth/1311868201.048622.png +1311868201.073245 rgb/1311868201.073245.png 1311868201.081466 depth/1311868201.081466.png +1311868201.105420 rgb/1311868201.105420.png 1311868201.117905 depth/1311868201.117905.png +1311868201.137460 rgb/1311868201.137460.png 1311868201.147308 depth/1311868201.147308.png +1311868201.173508 rgb/1311868201.173508.png 1311868201.182445 depth/1311868201.182445.png +1311868201.205336 rgb/1311868201.205336.png 1311868201.216734 depth/1311868201.216734.png +1311868201.237377 rgb/1311868201.237377.png 1311868201.247293 depth/1311868201.247293.png +1311868201.273379 rgb/1311868201.273379.png 1311868201.284041 depth/1311868201.284041.png +1311868201.305293 rgb/1311868201.305293.png 1311868201.318421 depth/1311868201.318421.png +1311868201.337491 rgb/1311868201.337491.png 1311868201.349439 depth/1311868201.349439.png +1311868201.373318 rgb/1311868201.373318.png 1311868201.383094 depth/1311868201.383094.png +1311868201.405299 rgb/1311868201.405299.png 1311868201.415370 depth/1311868201.415370.png +1311868201.437414 rgb/1311868201.437414.png 1311868201.447869 depth/1311868201.447869.png +1311868201.473238 rgb/1311868201.473238.png 1311868201.480785 depth/1311868201.480785.png +1311868201.505318 rgb/1311868201.505318.png 1311868201.518411 depth/1311868201.518411.png +1311868201.537450 rgb/1311868201.537450.png 1311868201.548346 depth/1311868201.548346.png +1311868201.573409 rgb/1311868201.573409.png 1311868201.584133 depth/1311868201.584133.png +1311868201.605366 rgb/1311868201.605366.png 1311868201.618693 depth/1311868201.618693.png +1311868201.637398 rgb/1311868201.637398.png 1311868201.648110 depth/1311868201.648110.png +1311868201.673519 rgb/1311868201.673519.png 1311868201.682146 depth/1311868201.682146.png +1311868201.705356 rgb/1311868201.705356.png 1311868201.717094 depth/1311868201.717094.png +1311868201.737412 rgb/1311868201.737412.png 1311868201.750216 depth/1311868201.750216.png +1311868201.773466 rgb/1311868201.773466.png 1311868201.782412 depth/1311868201.782412.png +1311868201.805263 rgb/1311868201.805263.png 1311868201.816684 depth/1311868201.816684.png +1311868201.837447 rgb/1311868201.837447.png 1311868201.849496 depth/1311868201.849496.png +1311868201.873269 rgb/1311868201.873269.png 1311868201.886245 depth/1311868201.886245.png +1311868201.905252 rgb/1311868201.905252.png 1311868201.915736 depth/1311868201.915736.png +1311868201.937456 rgb/1311868201.937456.png 1311868201.948414 depth/1311868201.948414.png +1311868201.973324 rgb/1311868201.973324.png 1311868201.988190 depth/1311868201.988190.png +1311868202.005324 rgb/1311868202.005324.png 1311868202.020311 depth/1311868202.020311.png +1311868202.037477 rgb/1311868202.037477.png 1311868202.050750 depth/1311868202.050750.png +1311868202.073300 rgb/1311868202.073300.png 1311868202.084295 depth/1311868202.084295.png +1311868202.105342 rgb/1311868202.105342.png 1311868202.116660 depth/1311868202.116660.png +1311868202.137626 rgb/1311868202.137626.png 1311868202.148960 depth/1311868202.148960.png +1311868202.173321 rgb/1311868202.173321.png 1311868202.185316 depth/1311868202.185316.png +1311868202.205344 rgb/1311868202.205344.png 1311868202.220704 depth/1311868202.220704.png +1311868202.237472 rgb/1311868202.237472.png 1311868202.248221 depth/1311868202.248221.png +1311868202.273322 rgb/1311868202.273322.png 1311868202.284706 depth/1311868202.284706.png +1311868202.305308 rgb/1311868202.305308.png 1311868202.315907 depth/1311868202.315907.png +1311868202.337417 rgb/1311868202.337417.png 1311868202.350180 depth/1311868202.350180.png +1311868202.373252 rgb/1311868202.373252.png 1311868202.385307 depth/1311868202.385307.png +1311868202.405338 rgb/1311868202.405338.png 1311868202.418776 depth/1311868202.418776.png +1311868202.437436 rgb/1311868202.437436.png 1311868202.449207 depth/1311868202.449207.png +1311868202.473421 rgb/1311868202.473421.png 1311868202.486886 depth/1311868202.486886.png +1311868202.505419 rgb/1311868202.505419.png 1311868202.517269 depth/1311868202.517269.png +1311868202.537451 rgb/1311868202.537451.png 1311868202.550209 depth/1311868202.550209.png +1311868202.573395 rgb/1311868202.573395.png 1311868202.584930 depth/1311868202.584930.png +1311868202.605428 rgb/1311868202.605428.png 1311868202.617698 depth/1311868202.617698.png +1311868202.637392 rgb/1311868202.637392.png 1311868202.651291 depth/1311868202.651291.png +1311868202.673740 rgb/1311868202.673740.png 1311868202.684815 depth/1311868202.684815.png +1311868202.705520 rgb/1311868202.705520.png 1311868202.721423 depth/1311868202.721423.png +1311868202.737342 rgb/1311868202.737342.png 1311868202.750587 depth/1311868202.750587.png +1311868202.773447 rgb/1311868202.773447.png 1311868202.789078 depth/1311868202.789078.png +1311868202.805444 rgb/1311868202.805444.png 1311868202.817783 depth/1311868202.817783.png +1311868202.837625 rgb/1311868202.837625.png 1311868202.847821 depth/1311868202.847821.png +1311868202.873426 rgb/1311868202.873426.png 1311868202.887573 depth/1311868202.887573.png +1311868202.905418 rgb/1311868202.905418.png 1311868202.916713 depth/1311868202.916713.png +1311868202.937647 rgb/1311868202.937647.png 1311868202.950442 depth/1311868202.950442.png +1311868202.973443 rgb/1311868202.973443.png 1311868202.986195 depth/1311868202.986195.png +1311868203.005588 rgb/1311868203.005588.png 1311868203.018688 depth/1311868203.018688.png +1311868203.037557 rgb/1311868203.037557.png 1311868203.051092 depth/1311868203.051092.png +1311868203.073357 rgb/1311868203.073357.png 1311868203.088633 depth/1311868203.088633.png +1311868203.105553 rgb/1311868203.105553.png 1311868203.118553 depth/1311868203.118553.png +1311868203.137538 rgb/1311868203.137538.png 1311868203.151428 depth/1311868203.151428.png +1311868203.173538 rgb/1311868203.173538.png 1311868203.186728 depth/1311868203.186728.png +1311868203.205413 rgb/1311868203.205413.png 1311868203.221978 depth/1311868203.221978.png +1311868203.237522 rgb/1311868203.237522.png 1311868203.251418 depth/1311868203.251418.png +1311868203.273471 rgb/1311868203.273471.png 1311868203.290312 depth/1311868203.290312.png +1311868203.305495 rgb/1311868203.305495.png 1311868203.319511 depth/1311868203.319511.png +1311868203.337532 rgb/1311868203.337532.png 1311868203.355366 depth/1311868203.355366.png +1311868203.373566 rgb/1311868203.373566.png 1311868203.388076 depth/1311868203.388076.png +1311868203.405460 rgb/1311868203.405460.png 1311868203.420300 depth/1311868203.420300.png +1311868203.437674 rgb/1311868203.437674.png 1311868203.452684 depth/1311868203.452684.png +1311868203.505522 rgb/1311868203.505522.png 1311868203.489908 depth/1311868203.489908.png +1311868203.537432 rgb/1311868203.537432.png 1311868203.551488 depth/1311868203.551488.png +1311868203.573541 rgb/1311868203.573541.png 1311868203.590000 depth/1311868203.590000.png +1311868203.605369 rgb/1311868203.605369.png 1311868203.620263 depth/1311868203.620263.png +1311868203.673562 rgb/1311868203.673562.png 1311868203.655631 depth/1311868203.655631.png +1311868203.705515 rgb/1311868203.705515.png 1311868203.693736 depth/1311868203.693736.png +1311868203.737597 rgb/1311868203.737597.png 1311868203.753498 depth/1311868203.753498.png +1311868203.773697 rgb/1311868203.773697.png 1311868203.788292 depth/1311868203.788292.png +1311868203.805515 rgb/1311868203.805515.png 1311868203.819823 depth/1311868203.819823.png +1311868203.837454 rgb/1311868203.837454.png 1311868203.854378 depth/1311868203.854378.png +1311868203.905612 rgb/1311868203.905612.png 1311868203.889896 depth/1311868203.889896.png +1311868203.937698 rgb/1311868203.937698.png 1311868203.922682 depth/1311868203.922682.png +1311868203.973618 rgb/1311868203.973618.png 1311868203.989463 depth/1311868203.989463.png +1311868204.005472 rgb/1311868204.005472.png 1311868204.020950 depth/1311868204.020950.png +1311868204.037612 rgb/1311868204.037612.png 1311868204.053488 depth/1311868204.053488.png +1311868204.073619 rgb/1311868204.073619.png 1311868204.089724 depth/1311868204.089724.png +1311868204.105511 rgb/1311868204.105511.png 1311868204.120304 depth/1311868204.120304.png +1311868204.137666 rgb/1311868204.137666.png 1311868204.153783 depth/1311868204.153783.png +1311868204.173662 rgb/1311868204.173662.png 1311868204.189089 depth/1311868204.189089.png +1311868204.205500 rgb/1311868204.205500.png 1311868204.220000 depth/1311868204.220000.png +1311868204.237660 rgb/1311868204.237660.png 1311868204.254490 depth/1311868204.254490.png +1311868204.273553 rgb/1311868204.273553.png 1311868204.289333 depth/1311868204.289333.png +1311868204.305523 rgb/1311868204.305523.png 1311868204.321788 depth/1311868204.321788.png +1311868204.337676 rgb/1311868204.337676.png 1311868204.353107 depth/1311868204.353107.png +1311868204.373570 rgb/1311868204.373570.png 1311868204.390706 depth/1311868204.390706.png +1311868204.405677 rgb/1311868204.405677.png 1311868204.420594 depth/1311868204.420594.png +1311868204.437659 rgb/1311868204.437659.png 1311868204.452861 depth/1311868204.452861.png +1311868204.473547 rgb/1311868204.473547.png 1311868204.488605 depth/1311868204.488605.png +1311868204.537824 rgb/1311868204.537824.png 1311868204.524765 depth/1311868204.524765.png +1311868204.573698 rgb/1311868204.573698.png 1311868204.589865 depth/1311868204.589865.png +1311868204.605660 rgb/1311868204.605660.png 1311868204.620568 depth/1311868204.620568.png +1311868204.637637 rgb/1311868204.637637.png 1311868204.653105 depth/1311868204.653105.png +1311868204.673697 rgb/1311868204.673697.png 1311868204.688212 depth/1311868204.688212.png +1311868204.705514 rgb/1311868204.705514.png 1311868204.720486 depth/1311868204.720486.png +1311868204.737693 rgb/1311868204.737693.png 1311868204.752331 depth/1311868204.752331.png +1311868204.773695 rgb/1311868204.773695.png 1311868204.788985 depth/1311868204.788985.png +1311868204.837551 rgb/1311868204.837551.png 1311868204.824953 depth/1311868204.824953.png +1311868204.873553 rgb/1311868204.873553.png 1311868204.889201 depth/1311868204.889201.png +1311868204.905660 rgb/1311868204.905660.png 1311868204.920352 depth/1311868204.920352.png +1311868204.937718 rgb/1311868204.937718.png 1311868204.953152 depth/1311868204.953152.png +1311868205.006015 rgb/1311868205.006015.png 1311868204.990689 depth/1311868204.990689.png +1311868205.037739 rgb/1311868205.037739.png 1311868205.025845 depth/1311868205.025845.png +1311868205.073567 rgb/1311868205.073567.png 1311868205.086494 depth/1311868205.086494.png +1311868205.137610 rgb/1311868205.137610.png 1311868205.122568 depth/1311868205.122568.png +1311868205.173557 rgb/1311868205.173557.png 1311868205.188535 depth/1311868205.188535.png +1311868205.205555 rgb/1311868205.205555.png 1311868205.219710 depth/1311868205.219710.png +1311868205.237795 rgb/1311868205.237795.png 1311868205.255934 depth/1311868205.255934.png +1311868205.273577 rgb/1311868205.273577.png 1311868205.289185 depth/1311868205.289185.png +1311868205.305573 rgb/1311868205.305573.png 1311868205.319204 depth/1311868205.319204.png +1311868205.337790 rgb/1311868205.337790.png 1311868205.357323 depth/1311868205.357323.png +1311868205.373547 rgb/1311868205.373547.png 1311868205.389230 depth/1311868205.389230.png +1311868205.405669 rgb/1311868205.405669.png 1311868205.422413 depth/1311868205.422413.png +1311868205.437684 rgb/1311868205.437684.png 1311868205.451557 depth/1311868205.451557.png +1311868205.473609 rgb/1311868205.473609.png 1311868205.487562 depth/1311868205.487562.png +1311868205.505684 rgb/1311868205.505684.png 1311868205.519674 depth/1311868205.519674.png +1311868205.537722 rgb/1311868205.537722.png 1311868205.553390 depth/1311868205.553390.png +1311868205.573643 rgb/1311868205.573643.png 1311868205.586644 depth/1311868205.586644.png +1311868205.605542 rgb/1311868205.605542.png 1311868205.619591 depth/1311868205.619591.png +1311868205.637725 rgb/1311868205.637725.png 1311868205.651913 depth/1311868205.651913.png +1311868205.705594 rgb/1311868205.705594.png 1311868205.690498 depth/1311868205.690498.png +1311868205.737847 rgb/1311868205.737847.png 1311868205.723045 depth/1311868205.723045.png +1311868205.773626 rgb/1311868205.773626.png 1311868205.789006 depth/1311868205.789006.png +1311868205.805674 rgb/1311868205.805674.png 1311868205.821518 depth/1311868205.821518.png +1311868205.837631 rgb/1311868205.837631.png 1311868205.852643 depth/1311868205.852643.png +1311868205.905586 rgb/1311868205.905586.png 1311868205.891319 depth/1311868205.891319.png +1311868205.937758 rgb/1311868205.937758.png 1311868205.921292 depth/1311868205.921292.png +1311868205.973702 rgb/1311868205.973702.png 1311868205.990701 depth/1311868205.990701.png +1311868206.005629 rgb/1311868206.005629.png 1311868206.020176 depth/1311868206.020176.png +1311868206.037992 rgb/1311868206.037992.png 1311868206.053115 depth/1311868206.053115.png +1311868206.105664 rgb/1311868206.105664.png 1311868206.091312 depth/1311868206.091312.png +1311868206.137732 rgb/1311868206.137732.png 1311868206.122346 depth/1311868206.122346.png +1311868206.173808 rgb/1311868206.173808.png 1311868206.190035 depth/1311868206.190035.png +1311868206.205696 rgb/1311868206.205696.png 1311868206.221036 depth/1311868206.221036.png +1311868206.237864 rgb/1311868206.237864.png 1311868206.253907 depth/1311868206.253907.png +1311868206.305562 rgb/1311868206.305562.png 1311868206.289938 depth/1311868206.289938.png +1311868206.337745 rgb/1311868206.337745.png 1311868206.352988 depth/1311868206.352988.png +1311868206.405629 rgb/1311868206.405629.png 1311868206.391438 depth/1311868206.391438.png +1311868206.437725 rgb/1311868206.437725.png 1311868206.422380 depth/1311868206.422380.png +1311868206.473742 rgb/1311868206.473742.png 1311868206.490059 depth/1311868206.490059.png +1311868206.505757 rgb/1311868206.505757.png 1311868206.520856 depth/1311868206.520856.png +1311868206.537710 rgb/1311868206.537710.png 1311868206.554417 depth/1311868206.554417.png +1311868206.573663 rgb/1311868206.573663.png 1311868206.589032 depth/1311868206.589032.png +1311868206.637808 rgb/1311868206.637808.png 1311868206.623746 depth/1311868206.623746.png +1311868206.673806 rgb/1311868206.673806.png 1311868206.689806 depth/1311868206.689806.png +1311868206.705664 rgb/1311868206.705664.png 1311868206.720361 depth/1311868206.720361.png +1311868206.737742 rgb/1311868206.737742.png 1311868206.754103 depth/1311868206.754103.png +1311868206.805720 rgb/1311868206.805720.png 1311868206.792145 depth/1311868206.792145.png +1311868206.837709 rgb/1311868206.837709.png 1311868206.823349 depth/1311868206.823349.png +1311868206.873715 rgb/1311868206.873715.png 1311868206.855875 depth/1311868206.855875.png +1311868206.906005 rgb/1311868206.906005.png 1311868206.892627 depth/1311868206.892627.png +1311868206.938074 rgb/1311868206.938074.png 1311868206.924424 depth/1311868206.924424.png +1311868206.973664 rgb/1311868206.973664.png 1311868206.987416 depth/1311868206.987416.png +1311868207.005651 rgb/1311868207.005651.png 1311868207.019787 depth/1311868207.019787.png +1311868207.073774 rgb/1311868207.073774.png 1311868207.057908 depth/1311868207.057908.png +1311868207.105726 rgb/1311868207.105726.png 1311868207.121576 depth/1311868207.121576.png +1311868207.137747 rgb/1311868207.137747.png 1311868207.154851 depth/1311868207.154851.png +1311868207.205787 rgb/1311868207.205787.png 1311868207.191285 depth/1311868207.191285.png +1311868207.237785 rgb/1311868207.237785.png 1311868207.221222 depth/1311868207.221222.png +1311868207.273845 rgb/1311868207.273845.png 1311868207.289968 depth/1311868207.289968.png +1311868207.305734 rgb/1311868207.305734.png 1311868207.320734 depth/1311868207.320734.png +1311868207.337883 rgb/1311868207.337883.png 1311868207.355453 depth/1311868207.355453.png +1311868207.405766 rgb/1311868207.405766.png 1311868207.390393 depth/1311868207.390393.png +1311868207.437999 rgb/1311868207.437999.png 1311868207.424233 depth/1311868207.424233.png +1311868207.473631 rgb/1311868207.473631.png 1311868207.460003 depth/1311868207.460003.png +1311868207.505671 rgb/1311868207.505671.png 1311868207.490256 depth/1311868207.490256.png +1311868207.537787 rgb/1311868207.537787.png 1311868207.522440 depth/1311868207.522440.png +1311868207.573858 rgb/1311868207.573858.png 1311868207.558020 depth/1311868207.558020.png +1311868207.605696 rgb/1311868207.605696.png 1311868207.592021 depth/1311868207.592021.png +1311868207.637684 rgb/1311868207.637684.png 1311868207.620945 depth/1311868207.620945.png +1311868207.673813 rgb/1311868207.673813.png 1311868207.660880 depth/1311868207.660880.png +1311868207.705850 rgb/1311868207.705850.png 1311868207.690675 depth/1311868207.690675.png +1311868207.737830 rgb/1311868207.737830.png 1311868207.723433 depth/1311868207.723433.png +1311868207.773705 rgb/1311868207.773705.png 1311868207.756243 depth/1311868207.756243.png +1311868207.805764 rgb/1311868207.805764.png 1311868207.791829 depth/1311868207.791829.png +1311868207.837900 rgb/1311868207.837900.png 1311868207.819777 depth/1311868207.819777.png +1311868207.873905 rgb/1311868207.873905.png 1311868207.860113 depth/1311868207.860113.png +1311868207.905716 rgb/1311868207.905716.png 1311868207.888571 depth/1311868207.888571.png +1311868207.937792 rgb/1311868207.937792.png 1311868207.924004 depth/1311868207.924004.png +1311868207.973830 rgb/1311868207.973830.png 1311868207.988781 depth/1311868207.988781.png +1311868208.005771 rgb/1311868208.005771.png 1311868208.021627 depth/1311868208.021627.png +1311868208.037660 rgb/1311868208.037660.png 1311868208.056509 depth/1311868208.056509.png +1311868208.073670 rgb/1311868208.073670.png 1311868208.088991 depth/1311868208.088991.png +1311868208.137703 rgb/1311868208.137703.png 1311868208.123515 depth/1311868208.123515.png +1311868208.173832 rgb/1311868208.173832.png 1311868208.187911 depth/1311868208.187911.png +1311868208.237842 rgb/1311868208.237842.png 1311868208.223223 depth/1311868208.223223.png +1311868208.273904 rgb/1311868208.273904.png 1311868208.288012 depth/1311868208.288012.png +1311868208.337811 rgb/1311868208.337811.png 1311868208.324316 depth/1311868208.324316.png +1311868208.373775 rgb/1311868208.373775.png 1311868208.387355 depth/1311868208.387355.png +1311868208.437928 rgb/1311868208.437928.png 1311868208.424557 depth/1311868208.424557.png +1311868208.473867 rgb/1311868208.473867.png 1311868208.489116 depth/1311868208.489116.png +1311868208.537898 rgb/1311868208.537898.png 1311868208.527828 depth/1311868208.527828.png +1311868208.573867 rgb/1311868208.573867.png 1311868208.587870 depth/1311868208.587870.png +1311868208.637812 rgb/1311868208.637812.png 1311868208.623963 depth/1311868208.623963.png +1311868208.673890 rgb/1311868208.673890.png 1311868208.687952 depth/1311868208.687952.png +1311868208.737756 rgb/1311868208.737756.png 1311868208.723366 depth/1311868208.723366.png +1311868208.773982 rgb/1311868208.773982.png 1311868208.788388 depth/1311868208.788388.png +1311868208.837756 rgb/1311868208.837756.png 1311868208.824045 depth/1311868208.824045.png +1311868208.873831 rgb/1311868208.873831.png 1311868208.887440 depth/1311868208.887440.png +1311868208.937746 rgb/1311868208.937746.png 1311868208.923353 depth/1311868208.923353.png +1311868208.973765 rgb/1311868208.973765.png 1311868208.987749 depth/1311868208.987749.png +1311868209.037800 rgb/1311868209.037800.png 1311868209.023376 depth/1311868209.023376.png +1311868209.073793 rgb/1311868209.073793.png 1311868209.087996 depth/1311868209.087996.png +1311868209.137783 rgb/1311868209.137783.png 1311868209.124727 depth/1311868209.124727.png +1311868209.173775 rgb/1311868209.173775.png 1311868209.188268 depth/1311868209.188268.png +1311868209.237811 rgb/1311868209.237811.png 1311868209.223737 depth/1311868209.223737.png +1311868209.273776 rgb/1311868209.273776.png 1311868209.288996 depth/1311868209.288996.png +1311868209.305793 rgb/1311868209.305793.png 1311868209.324461 depth/1311868209.324461.png +1311868209.341866 rgb/1311868209.341866.png 1311868209.356288 depth/1311868209.356288.png +1311868209.405777 rgb/1311868209.405777.png 1311868209.397063 depth/1311868209.397063.png +1311868209.441953 rgb/1311868209.441953.png 1311868209.456861 depth/1311868209.456861.png +1311868209.505812 rgb/1311868209.505812.png 1311868209.492372 depth/1311868209.492372.png +1311868209.541800 rgb/1311868209.541800.png 1311868209.555981 depth/1311868209.555981.png +1311868209.606012 rgb/1311868209.606012.png 1311868209.592655 depth/1311868209.592655.png +1311868209.642092 rgb/1311868209.642092.png 1311868209.657089 depth/1311868209.657089.png +1311868209.705861 rgb/1311868209.705861.png 1311868209.693474 depth/1311868209.693474.png +1311868209.741975 rgb/1311868209.741975.png 1311868209.757140 depth/1311868209.757140.png +1311868209.805796 rgb/1311868209.805796.png 1311868209.793723 depth/1311868209.793723.png +1311868209.841897 rgb/1311868209.841897.png 1311868209.857383 depth/1311868209.857383.png +1311868209.905787 rgb/1311868209.905787.png 1311868209.891792 depth/1311868209.891792.png +1311868209.942127 rgb/1311868209.942127.png 1311868209.956558 depth/1311868209.956558.png +1311868210.005883 rgb/1311868210.005883.png 1311868209.991817 depth/1311868209.991817.png +1311868210.042009 rgb/1311868210.042009.png 1311868210.024765 depth/1311868210.024765.png +1311868210.073822 rgb/1311868210.073822.png 1311868210.058500 depth/1311868210.058500.png +1311868210.105867 rgb/1311868210.105867.png 1311868210.091532 depth/1311868210.091532.png +1311868210.141864 rgb/1311868210.141864.png 1311868210.123691 depth/1311868210.123691.png +1311868210.173922 rgb/1311868210.173922.png 1311868210.158032 depth/1311868210.158032.png +1311868210.205786 rgb/1311868210.205786.png 1311868210.193737 depth/1311868210.193737.png +1311868210.241903 rgb/1311868210.241903.png 1311868210.255458 depth/1311868210.255458.png +1311868210.305977 rgb/1311868210.305977.png 1311868210.292809 depth/1311868210.292809.png +1311868210.341851 rgb/1311868210.341851.png 1311868210.357061 depth/1311868210.357061.png +1311868210.405885 rgb/1311868210.405885.png 1311868210.391582 depth/1311868210.391582.png +1311868210.441961 rgb/1311868210.441961.png 1311868210.423315 depth/1311868210.423315.png +1311868210.473857 rgb/1311868210.473857.png 1311868210.459162 depth/1311868210.459162.png +1311868210.505879 rgb/1311868210.505879.png 1311868210.491729 depth/1311868210.491729.png +1311868210.541924 rgb/1311868210.541924.png 1311868210.524078 depth/1311868210.524078.png +1311868210.573923 rgb/1311868210.573923.png 1311868210.560350 depth/1311868210.560350.png +1311868210.605964 rgb/1311868210.605964.png 1311868210.593981 depth/1311868210.593981.png +1311868210.642018 rgb/1311868210.642018.png 1311868210.624137 depth/1311868210.624137.png +1311868210.673897 rgb/1311868210.673897.png 1311868210.660941 depth/1311868210.660941.png +1311868210.705897 rgb/1311868210.705897.png 1311868210.694072 depth/1311868210.694072.png +1311868210.742133 rgb/1311868210.742133.png 1311868210.725646 depth/1311868210.725646.png +1311868210.774018 rgb/1311868210.774018.png 1311868210.761375 depth/1311868210.761375.png +1311868210.805942 rgb/1311868210.805942.png 1311868210.792255 depth/1311868210.792255.png +1311868210.841882 rgb/1311868210.841882.png 1311868210.824869 depth/1311868210.824869.png +1311868210.873988 rgb/1311868210.873988.png 1311868210.862050 depth/1311868210.862050.png +1311868210.905826 rgb/1311868210.905826.png 1311868210.892741 depth/1311868210.892741.png +1311868210.942021 rgb/1311868210.942021.png 1311868210.925029 depth/1311868210.925029.png +1311868210.974235 rgb/1311868210.974235.png 1311868210.960048 depth/1311868210.960048.png +1311868211.005839 rgb/1311868211.005839.png 1311868210.993438 depth/1311868210.993438.png +1311868211.041878 rgb/1311868211.041878.png 1311868211.025176 depth/1311868211.025176.png +1311868211.074009 rgb/1311868211.074009.png 1311868211.059498 depth/1311868211.059498.png +1311868211.106006 rgb/1311868211.106006.png 1311868211.091740 depth/1311868211.091740.png +1311868211.142002 rgb/1311868211.142002.png 1311868211.125207 depth/1311868211.125207.png +1311868211.174051 rgb/1311868211.174051.png 1311868211.160225 depth/1311868211.160225.png +1311868211.205845 rgb/1311868211.205845.png 1311868211.192632 depth/1311868211.192632.png +1311868211.241987 rgb/1311868211.241987.png 1311868211.224527 depth/1311868211.224527.png +1311868211.274088 rgb/1311868211.274088.png 1311868211.259284 depth/1311868211.259284.png +1311868211.306090 rgb/1311868211.306090.png 1311868211.293066 depth/1311868211.293066.png +1311868211.342241 rgb/1311868211.342241.png 1311868211.324322 depth/1311868211.324322.png +1311868211.374052 rgb/1311868211.374052.png 1311868211.361163 depth/1311868211.361163.png +1311868211.406119 rgb/1311868211.406119.png 1311868211.393543 depth/1311868211.393543.png +1311868211.442216 rgb/1311868211.442216.png 1311868211.424189 depth/1311868211.424189.png +1311868211.473939 rgb/1311868211.473939.png 1311868211.460678 depth/1311868211.460678.png +1311868211.505937 rgb/1311868211.505937.png 1311868211.493996 depth/1311868211.493996.png +1311868211.541927 rgb/1311868211.541927.png 1311868211.524612 depth/1311868211.524612.png +1311868211.573950 rgb/1311868211.573950.png 1311868211.560741 depth/1311868211.560741.png +1311868211.606012 rgb/1311868211.606012.png 1311868211.592842 depth/1311868211.592842.png +1311868211.642009 rgb/1311868211.642009.png 1311868211.624034 depth/1311868211.624034.png +1311868211.674030 rgb/1311868211.674030.png 1311868211.659881 depth/1311868211.659881.png +1311868211.706002 rgb/1311868211.706002.png 1311868211.694654 depth/1311868211.694654.png +1311868211.742056 rgb/1311868211.742056.png 1311868211.724257 depth/1311868211.724257.png +1311868211.773982 rgb/1311868211.773982.png 1311868211.760756 depth/1311868211.760756.png +1311868211.806164 rgb/1311868211.806164.png 1311868211.796126 depth/1311868211.796126.png +1311868211.842132 rgb/1311868211.842132.png 1311868211.828952 depth/1311868211.828952.png +1311868211.873907 rgb/1311868211.873907.png 1311868211.861079 depth/1311868211.861079.png +1311868211.906024 rgb/1311868211.906024.png 1311868211.893028 depth/1311868211.893028.png +1311868211.942293 rgb/1311868211.942293.png 1311868211.928354 depth/1311868211.928354.png +1311868211.974041 rgb/1311868211.974041.png 1311868211.960968 depth/1311868211.960968.png +1311868212.005902 rgb/1311868212.005902.png 1311868211.994401 depth/1311868211.994401.png +1311868212.042182 rgb/1311868212.042182.png 1311868212.028849 depth/1311868212.028849.png +1311868212.074044 rgb/1311868212.074044.png 1311868212.062146 depth/1311868212.062146.png +1311868212.105906 rgb/1311868212.105906.png 1311868212.093919 depth/1311868212.093919.png +1311868212.142105 rgb/1311868212.142105.png 1311868212.127527 depth/1311868212.127527.png +1311868212.174023 rgb/1311868212.174023.png 1311868212.161612 depth/1311868212.161612.png +1311868212.206126 rgb/1311868212.206126.png 1311868212.194687 depth/1311868212.194687.png +1311868212.242313 rgb/1311868212.242313.png 1311868212.231541 depth/1311868212.231541.png +1311868212.274255 rgb/1311868212.274255.png 1311868212.262754 depth/1311868212.262754.png +1311868212.306028 rgb/1311868212.306028.png 1311868212.293996 depth/1311868212.293996.png +1311868212.342124 rgb/1311868212.342124.png 1311868212.327446 depth/1311868212.327446.png +1311868212.374157 rgb/1311868212.374157.png 1311868212.365707 depth/1311868212.365707.png +1311868212.406130 rgb/1311868212.406130.png 1311868212.391604 depth/1311868212.391604.png +1311868212.442138 rgb/1311868212.442138.png 1311868212.430051 depth/1311868212.430051.png +1311868212.474044 rgb/1311868212.474044.png 1311868212.465503 depth/1311868212.465503.png +1311868212.506032 rgb/1311868212.506032.png 1311868212.491652 depth/1311868212.491652.png +1311868212.542167 rgb/1311868212.542167.png 1311868212.527607 depth/1311868212.527607.png +1311868212.574023 rgb/1311868212.574023.png 1311868212.561717 depth/1311868212.561717.png +1311868212.606112 rgb/1311868212.606112.png 1311868212.596018 depth/1311868212.596018.png +1311868212.642096 rgb/1311868212.642096.png 1311868212.631003 depth/1311868212.631003.png +1311868212.674200 rgb/1311868212.674200.png 1311868212.662593 depth/1311868212.662593.png +1311868212.706878 rgb/1311868212.706878.png 1311868212.695112 depth/1311868212.695112.png +1311868212.742196 rgb/1311868212.742196.png 1311868212.731388 depth/1311868212.731388.png +1311868212.773943 rgb/1311868212.773943.png 1311868212.762764 depth/1311868212.762764.png +1311868212.806006 rgb/1311868212.806006.png 1311868212.793628 depth/1311868212.793628.png +1311868212.842064 rgb/1311868212.842064.png 1311868212.830201 depth/1311868212.830201.png +1311868212.874075 rgb/1311868212.874075.png 1311868212.861627 depth/1311868212.861627.png +1311868212.906161 rgb/1311868212.906161.png 1311868212.895707 depth/1311868212.895707.png +1311868212.942123 rgb/1311868212.942123.png 1311868212.930614 depth/1311868212.930614.png +1311868212.974154 rgb/1311868212.974154.png 1311868212.961582 depth/1311868212.961582.png +1311868213.006193 rgb/1311868213.006193.png 1311868212.995055 depth/1311868212.995055.png +1311868213.042223 rgb/1311868213.042223.png 1311868213.030994 depth/1311868213.030994.png +1311868213.073951 rgb/1311868213.073951.png 1311868213.062127 depth/1311868213.062127.png +1311868213.106053 rgb/1311868213.106053.png 1311868213.096720 depth/1311868213.096720.png +1311868213.142119 rgb/1311868213.142119.png 1311868213.130213 depth/1311868213.130213.png +1311868213.174219 rgb/1311868213.174219.png 1311868213.161672 depth/1311868213.161672.png +1311868213.206347 rgb/1311868213.206347.png 1311868213.199357 depth/1311868213.199357.png +1311868213.242209 rgb/1311868213.242209.png 1311868213.231589 depth/1311868213.231589.png +1311868213.274014 rgb/1311868213.274014.png 1311868213.262100 depth/1311868213.262100.png +1311868213.306151 rgb/1311868213.306151.png 1311868213.296404 depth/1311868213.296404.png +1311868213.342368 rgb/1311868213.342368.png 1311868213.331731 depth/1311868213.331731.png +1311868213.374390 rgb/1311868213.374390.png 1311868213.363191 depth/1311868213.363191.png +1311868213.406010 rgb/1311868213.406010.png 1311868213.395848 depth/1311868213.395848.png +1311868213.442300 rgb/1311868213.442300.png 1311868213.430986 depth/1311868213.430986.png +1311868213.474546 rgb/1311868213.474546.png 1311868213.463117 depth/1311868213.463117.png +1311868213.506347 rgb/1311868213.506347.png 1311868213.499324 depth/1311868213.499324.png +1311868213.542189 rgb/1311868213.542189.png 1311868213.531201 depth/1311868213.531201.png +1311868213.574297 rgb/1311868213.574297.png 1311868213.563046 depth/1311868213.563046.png +1311868213.608357 rgb/1311868213.608357.png 1311868213.599589 depth/1311868213.599589.png +1311868213.642086 rgb/1311868213.642086.png 1311868213.631001 depth/1311868213.631001.png +1311868213.674238 rgb/1311868213.674238.png 1311868213.661925 depth/1311868213.661925.png +1311868213.706267 rgb/1311868213.706267.png 1311868213.699582 depth/1311868213.699582.png +1311868213.742210 rgb/1311868213.742210.png 1311868213.729688 depth/1311868213.729688.png +1311868213.774084 rgb/1311868213.774084.png 1311868213.762865 depth/1311868213.762865.png +1311868213.806247 rgb/1311868213.806247.png 1311868213.798710 depth/1311868213.798710.png +1311868213.842211 rgb/1311868213.842211.png 1311868213.828307 depth/1311868213.828307.png +1311868213.874145 rgb/1311868213.874145.png 1311868213.862133 depth/1311868213.862133.png +1311868213.906335 rgb/1311868213.906335.png 1311868213.898969 depth/1311868213.898969.png +1311868213.942213 rgb/1311868213.942213.png 1311868213.932051 depth/1311868213.932051.png +1311868213.974085 rgb/1311868213.974085.png 1311868213.962376 depth/1311868213.962376.png +1311868214.006317 rgb/1311868214.006317.png 1311868214.000127 depth/1311868214.000127.png +1311868214.042178 rgb/1311868214.042178.png 1311868214.028718 depth/1311868214.028718.png +1311868214.074100 rgb/1311868214.074100.png 1311868214.062257 depth/1311868214.062257.png +1311868214.106187 rgb/1311868214.106187.png 1311868214.096212 depth/1311868214.096212.png +1311868214.142287 rgb/1311868214.142287.png 1311868214.130191 depth/1311868214.130191.png +1311868214.174039 rgb/1311868214.174039.png 1311868214.160358 depth/1311868214.160358.png +1311868214.206335 rgb/1311868214.206335.png 1311868214.196958 depth/1311868214.196958.png +1311868214.242159 rgb/1311868214.242159.png 1311868214.231385 depth/1311868214.231385.png +1311868214.274221 rgb/1311868214.274221.png 1311868214.269163 depth/1311868214.269163.png +1311868214.306406 rgb/1311868214.306406.png 1311868214.298875 depth/1311868214.298875.png +1311868214.342288 rgb/1311868214.342288.png 1311868214.331239 depth/1311868214.331239.png +1311868214.374244 rgb/1311868214.374244.png 1311868214.364089 depth/1311868214.364089.png +1311868214.406227 rgb/1311868214.406227.png 1311868214.400932 depth/1311868214.400932.png +1311868214.442184 rgb/1311868214.442184.png 1311868214.428342 depth/1311868214.428342.png +1311868214.474262 rgb/1311868214.474262.png 1311868214.466683 depth/1311868214.466683.png +1311868214.506579 rgb/1311868214.506579.png 1311868214.499607 depth/1311868214.499607.png +1311868214.542302 rgb/1311868214.542302.png 1311868214.531421 depth/1311868214.531421.png +1311868214.574356 rgb/1311868214.574356.png 1311868214.566788 depth/1311868214.566788.png +1311868214.606407 rgb/1311868214.606407.png 1311868214.596131 depth/1311868214.596131.png +1311868214.642280 rgb/1311868214.642280.png 1311868214.627964 depth/1311868214.627964.png +1311868214.674410 rgb/1311868214.674410.png 1311868214.667136 depth/1311868214.667136.png +1311868214.706198 rgb/1311868214.706198.png 1311868214.697712 depth/1311868214.697712.png +1311868214.742333 rgb/1311868214.742333.png 1311868214.727991 depth/1311868214.727991.png +1311868214.774481 rgb/1311868214.774481.png 1311868214.767288 depth/1311868214.767288.png +1311868214.806468 rgb/1311868214.806468.png 1311868214.798886 depth/1311868214.798886.png +1311868214.842297 rgb/1311868214.842297.png 1311868214.828913 depth/1311868214.828913.png +1311868214.874290 rgb/1311868214.874290.png 1311868214.868793 depth/1311868214.868793.png +1311868214.906326 rgb/1311868214.906326.png 1311868214.900436 depth/1311868214.900436.png +1311868214.942194 rgb/1311868214.942194.png 1311868214.927817 depth/1311868214.927817.png +1311868214.974404 rgb/1311868214.974404.png 1311868214.966937 depth/1311868214.966937.png +1311868215.006391 rgb/1311868215.006391.png 1311868214.999633 depth/1311868214.999633.png +1311868215.042220 rgb/1311868215.042220.png 1311868215.030933 depth/1311868215.030933.png +1311868215.074234 rgb/1311868215.074234.png 1311868215.064106 depth/1311868215.064106.png +1311868215.106202 rgb/1311868215.106202.png 1311868215.098227 depth/1311868215.098227.png +1311868215.142266 rgb/1311868215.142266.png 1311868215.129751 depth/1311868215.129751.png +1311868215.174343 rgb/1311868215.174343.png 1311868215.165719 depth/1311868215.165719.png +1311868215.206366 rgb/1311868215.206366.png 1311868215.199781 depth/1311868215.199781.png +1311868215.242259 rgb/1311868215.242259.png 1311868215.229628 depth/1311868215.229628.png +1311868215.274353 rgb/1311868215.274353.png 1311868215.265968 depth/1311868215.265968.png +1311868215.306401 rgb/1311868215.306401.png 1311868215.297820 depth/1311868215.297820.png +1311868215.342475 rgb/1311868215.342475.png 1311868215.331843 depth/1311868215.331843.png +1311868215.374240 rgb/1311868215.374240.png 1311868215.365828 depth/1311868215.365828.png +1311868215.406376 rgb/1311868215.406376.png 1311868215.398876 depth/1311868215.398876.png +1311868215.442338 rgb/1311868215.442338.png 1311868215.428227 depth/1311868215.428227.png +1311868215.474499 rgb/1311868215.474499.png 1311868215.464523 depth/1311868215.464523.png +1311868215.506308 rgb/1311868215.506308.png 1311868215.499379 depth/1311868215.499379.png +1311868215.542336 rgb/1311868215.542336.png 1311868215.532372 depth/1311868215.532372.png +1311868215.574139 rgb/1311868215.574139.png 1311868215.564697 depth/1311868215.564697.png +1311868215.606249 rgb/1311868215.606249.png 1311868215.595707 depth/1311868215.595707.png +1311868215.642404 rgb/1311868215.642404.png 1311868215.634840 depth/1311868215.634840.png +1311868215.674534 rgb/1311868215.674534.png 1311868215.666718 depth/1311868215.666718.png +1311868215.706473 rgb/1311868215.706473.png 1311868215.699219 depth/1311868215.699219.png +1311868215.742205 rgb/1311868215.742205.png 1311868215.733621 depth/1311868215.733621.png +1311868215.774735 rgb/1311868215.774735.png 1311868215.767615 depth/1311868215.767615.png +1311868215.806559 rgb/1311868215.806559.png 1311868215.801906 depth/1311868215.801906.png +1311868215.842289 rgb/1311868215.842289.png 1311868215.833568 depth/1311868215.833568.png +1311868215.874205 rgb/1311868215.874205.png 1311868215.864820 depth/1311868215.864820.png +1311868215.906403 rgb/1311868215.906403.png 1311868215.898023 depth/1311868215.898023.png +1311868215.942381 rgb/1311868215.942381.png 1311868215.932024 depth/1311868215.932024.png +1311868215.974271 rgb/1311868215.974271.png 1311868215.968317 depth/1311868215.968317.png +1311868216.006524 rgb/1311868216.006524.png 1311868215.996855 depth/1311868215.996855.png +1311868216.042488 rgb/1311868216.042488.png 1311868216.035046 depth/1311868216.035046.png +1311868216.074212 rgb/1311868216.074212.png 1311868216.065637 depth/1311868216.065637.png +1311868216.106321 rgb/1311868216.106321.png 1311868216.096071 depth/1311868216.096071.png +1311868216.142434 rgb/1311868216.142434.png 1311868216.135571 depth/1311868216.135571.png +1311868216.174227 rgb/1311868216.174227.png 1311868216.166199 depth/1311868216.166199.png +1311868216.206326 rgb/1311868216.206326.png 1311868216.197597 depth/1311868216.197597.png +1311868216.242946 rgb/1311868216.242946.png 1311868216.234802 depth/1311868216.234802.png +1311868216.275879 rgb/1311868216.275879.png 1311868216.266603 depth/1311868216.266603.png +1311868216.306682 rgb/1311868216.306682.png 1311868216.300423 depth/1311868216.300423.png +1311868216.342596 rgb/1311868216.342596.png 1311868216.334966 depth/1311868216.334966.png +1311868216.374273 rgb/1311868216.374273.png 1311868216.365042 depth/1311868216.365042.png +1311868216.406671 rgb/1311868216.406671.png 1311868216.396324 depth/1311868216.396324.png +1311868216.442339 rgb/1311868216.442339.png 1311868216.437861 depth/1311868216.437861.png +1311868216.474357 rgb/1311868216.474357.png 1311868216.464425 depth/1311868216.464425.png +1311868216.506418 rgb/1311868216.506418.png 1311868216.496861 depth/1311868216.496861.png +1311868216.542390 rgb/1311868216.542390.png 1311868216.531729 depth/1311868216.531729.png +1311868216.574328 rgb/1311868216.574328.png 1311868216.565989 depth/1311868216.565989.png +1311868216.606527 rgb/1311868216.606527.png 1311868216.597315 depth/1311868216.597315.png +1311868216.642461 rgb/1311868216.642461.png 1311868216.633797 depth/1311868216.633797.png +1311868216.674349 rgb/1311868216.674349.png 1311868216.665318 depth/1311868216.665318.png +1311868216.706576 rgb/1311868216.706576.png 1311868216.699687 depth/1311868216.699687.png +1311868216.742454 rgb/1311868216.742454.png 1311868216.732294 depth/1311868216.732294.png +1311868216.774257 rgb/1311868216.774257.png 1311868216.764468 depth/1311868216.764468.png +1311868216.806393 rgb/1311868216.806393.png 1311868216.800259 depth/1311868216.800259.png +1311868216.842459 rgb/1311868216.842459.png 1311868216.832619 depth/1311868216.832619.png +1311868216.874405 rgb/1311868216.874405.png 1311868216.866560 depth/1311868216.866560.png +1311868216.906366 rgb/1311868216.906366.png 1311868216.903003 depth/1311868216.903003.png +1311868216.942380 rgb/1311868216.942380.png 1311868216.932272 depth/1311868216.932272.png +1311868216.974559 rgb/1311868216.974559.png 1311868216.965458 depth/1311868216.965458.png +1311868217.006426 rgb/1311868217.006426.png 1311868217.002689 depth/1311868217.002689.png +1311868217.042435 rgb/1311868217.042435.png 1311868217.032318 depth/1311868217.032318.png +1311868217.074615 rgb/1311868217.074615.png 1311868217.065317 depth/1311868217.065317.png +1311868217.106679 rgb/1311868217.106679.png 1311868217.103305 depth/1311868217.103305.png +1311868217.143747 rgb/1311868217.143747.png 1311868217.136263 depth/1311868217.136263.png +1311868217.174613 rgb/1311868217.174613.png 1311868217.166840 depth/1311868217.166840.png +1311868217.206576 rgb/1311868217.206576.png 1311868217.201967 depth/1311868217.201967.png +1311868217.242361 rgb/1311868217.242361.png 1311868217.232198 depth/1311868217.232198.png +1311868217.274712 rgb/1311868217.274712.png 1311868217.266852 depth/1311868217.266852.png +1311868217.307288 rgb/1311868217.307288.png 1311868217.301319 depth/1311868217.301319.png +1311868217.342453 rgb/1311868217.342453.png 1311868217.332206 depth/1311868217.332206.png +1311868217.374311 rgb/1311868217.374311.png 1311868217.363769 depth/1311868217.363769.png +1311868217.406701 rgb/1311868217.406701.png 1311868217.399390 depth/1311868217.399390.png +1311868217.442485 rgb/1311868217.442485.png 1311868217.434691 depth/1311868217.434691.png +1311868217.475102 rgb/1311868217.475102.png 1311868217.466778 depth/1311868217.466778.png +1311868217.506647 rgb/1311868217.506647.png 1311868217.502605 depth/1311868217.502605.png +1311868217.542334 rgb/1311868217.542334.png 1311868217.531760 depth/1311868217.531760.png +1311868217.574294 rgb/1311868217.574294.png 1311868217.563694 depth/1311868217.563694.png +1311868217.606343 rgb/1311868217.606343.png 1311868217.599985 depth/1311868217.599985.png +1311868217.642399 rgb/1311868217.642399.png 1311868217.632879 depth/1311868217.632879.png +1311868217.674402 rgb/1311868217.674402.png 1311868217.664702 depth/1311868217.664702.png +1311868217.706372 rgb/1311868217.706372.png 1311868217.700189 depth/1311868217.700189.png +1311868217.742436 rgb/1311868217.742436.png 1311868217.735278 depth/1311868217.735278.png +1311868217.775482 rgb/1311868217.775482.png 1311868217.768408 depth/1311868217.768408.png +1311868217.806772 rgb/1311868217.806772.png 1311868217.801730 depth/1311868217.801730.png +1311868217.842462 rgb/1311868217.842462.png 1311868217.831781 depth/1311868217.831781.png +1311868217.874273 rgb/1311868217.874273.png 1311868217.866254 depth/1311868217.866254.png +1311868217.906458 rgb/1311868217.906458.png 1311868217.900688 depth/1311868217.900688.png +1311868217.942466 rgb/1311868217.942466.png 1311868217.935531 depth/1311868217.935531.png +1311868217.975110 rgb/1311868217.975110.png 1311868217.970178 depth/1311868217.970178.png +1311868218.006398 rgb/1311868218.006398.png 1311868217.999378 depth/1311868217.999378.png +1311868218.042374 rgb/1311868218.042374.png 1311868218.031505 depth/1311868218.031505.png +1311868218.074687 rgb/1311868218.074687.png 1311868218.067405 depth/1311868218.067405.png +1311868218.106528 rgb/1311868218.106528.png 1311868218.099367 depth/1311868218.099367.png +1311868218.142452 rgb/1311868218.142452.png 1311868218.131479 depth/1311868218.131479.png +1311868218.174634 rgb/1311868218.174634.png 1311868218.168288 depth/1311868218.168288.png +1311868218.206493 rgb/1311868218.206493.png 1311868218.199946 depth/1311868218.199946.png +1311868218.242489 rgb/1311868218.242489.png 1311868218.233668 depth/1311868218.233668.png +1311868218.274613 rgb/1311868218.274613.png 1311868218.270554 depth/1311868218.270554.png +1311868218.306510 rgb/1311868218.306510.png 1311868218.302471 depth/1311868218.302471.png +1311868218.342575 rgb/1311868218.342575.png 1311868218.333373 depth/1311868218.333373.png +1311868218.374760 rgb/1311868218.374760.png 1311868218.371327 depth/1311868218.371327.png +1311868218.410500 rgb/1311868218.410500.png 1311868218.405229 depth/1311868218.405229.png +1311868218.442486 rgb/1311868218.442486.png 1311868218.433451 depth/1311868218.433451.png +1311868218.474491 rgb/1311868218.474491.png 1311868218.472236 depth/1311868218.472236.png +1311868218.510448 rgb/1311868218.510448.png 1311868218.501503 depth/1311868218.501503.png +1311868218.542375 rgb/1311868218.542375.png 1311868218.532944 depth/1311868218.532944.png +1311868218.574422 rgb/1311868218.574422.png 1311868218.567444 depth/1311868218.567444.png +1311868218.610383 rgb/1311868218.610383.png 1311868218.602207 depth/1311868218.602207.png +1311868218.642508 rgb/1311868218.642508.png 1311868218.633787 depth/1311868218.633787.png +1311868218.674491 rgb/1311868218.674491.png 1311868218.667366 depth/1311868218.667366.png +1311868218.710423 rgb/1311868218.710423.png 1311868218.701368 depth/1311868218.701368.png +1311868218.742485 rgb/1311868218.742485.png 1311868218.732400 depth/1311868218.732400.png +1311868218.774455 rgb/1311868218.774455.png 1311868218.769072 depth/1311868218.769072.png +1311868218.810331 rgb/1311868218.810331.png 1311868218.800107 depth/1311868218.800107.png +1311868218.842407 rgb/1311868218.842407.png 1311868218.831723 depth/1311868218.831723.png +1311868218.874697 rgb/1311868218.874697.png 1311868218.869983 depth/1311868218.869983.png +1311868218.910344 rgb/1311868218.910344.png 1311868218.899595 depth/1311868218.899595.png +1311868218.942390 rgb/1311868218.942390.png 1311868218.931950 depth/1311868218.931950.png +1311868218.974531 rgb/1311868218.974531.png 1311868218.969948 depth/1311868218.969948.png +1311868219.010718 rgb/1311868219.010718.png 1311868219.001382 depth/1311868219.001382.png +1311868219.042799 rgb/1311868219.042799.png 1311868219.036519 depth/1311868219.036519.png +1311868219.074699 rgb/1311868219.074699.png 1311868219.067363 depth/1311868219.067363.png +1311868219.110710 rgb/1311868219.110710.png 1311868219.100346 depth/1311868219.100346.png +1311868219.142449 rgb/1311868219.142449.png 1311868219.132682 depth/1311868219.132682.png +1311868219.174460 rgb/1311868219.174460.png 1311868219.167726 depth/1311868219.167726.png +1311868219.210391 rgb/1311868219.210391.png 1311868219.199463 depth/1311868219.199463.png +1311868219.242632 rgb/1311868219.242632.png 1311868219.235734 depth/1311868219.235734.png +1311868219.274458 rgb/1311868219.274458.png 1311868219.267876 depth/1311868219.267876.png +1311868219.310567 rgb/1311868219.310567.png 1311868219.301405 depth/1311868219.301405.png +1311868219.342858 rgb/1311868219.342858.png 1311868219.336414 depth/1311868219.336414.png +1311868219.374565 rgb/1311868219.374565.png 1311868219.368069 depth/1311868219.368069.png +1311868219.410427 rgb/1311868219.410427.png 1311868219.400180 depth/1311868219.400180.png +1311868219.442491 rgb/1311868219.442491.png 1311868219.435990 depth/1311868219.435990.png +1311868219.474442 rgb/1311868219.474442.png 1311868219.467615 depth/1311868219.467615.png +1311868219.510471 rgb/1311868219.510471.png 1311868219.500250 depth/1311868219.500250.png +1311868219.543330 rgb/1311868219.543330.png 1311868219.540778 depth/1311868219.540778.png +1311868219.574798 rgb/1311868219.574798.png 1311868219.567933 depth/1311868219.567933.png +1311868219.610673 rgb/1311868219.610673.png 1311868219.602290 depth/1311868219.602290.png +1311868219.642931 rgb/1311868219.642931.png 1311868219.636093 depth/1311868219.636093.png +1311868219.674450 rgb/1311868219.674450.png 1311868219.667827 depth/1311868219.667827.png +1311868219.710785 rgb/1311868219.710785.png 1311868219.700080 depth/1311868219.700080.png +1311868219.742593 rgb/1311868219.742593.png 1311868219.735627 depth/1311868219.735627.png +1311868219.774534 rgb/1311868219.774534.png 1311868219.768145 depth/1311868219.768145.png +1311868219.810409 rgb/1311868219.810409.png 1311868219.801247 depth/1311868219.801247.png +1311868219.842777 rgb/1311868219.842777.png 1311868219.835981 depth/1311868219.835981.png +1311868219.874478 rgb/1311868219.874478.png 1311868219.867815 depth/1311868219.867815.png +1311868219.910641 rgb/1311868219.910641.png 1311868219.900014 depth/1311868219.900014.png +1311868219.942611 rgb/1311868219.942611.png 1311868219.936057 depth/1311868219.936057.png +1311868219.974873 rgb/1311868219.974873.png 1311868219.967731 depth/1311868219.967731.png +1311868220.010555 rgb/1311868220.010555.png 1311868220.000484 depth/1311868220.000484.png +1311868220.042788 rgb/1311868220.042788.png 1311868220.035991 depth/1311868220.035991.png +1311868220.074683 rgb/1311868220.074683.png 1311868220.068021 depth/1311868220.068021.png +1311868220.110558 rgb/1311868220.110558.png 1311868220.101658 depth/1311868220.101658.png +1311868220.142630 rgb/1311868220.142630.png 1311868220.136124 depth/1311868220.136124.png +1311868220.174706 rgb/1311868220.174706.png 1311868220.168106 depth/1311868220.168106.png +1311868220.210459 rgb/1311868220.210459.png 1311868220.200388 depth/1311868220.200388.png +1311868220.242513 rgb/1311868220.242513.png 1311868220.236348 depth/1311868220.236348.png +1311868220.274890 rgb/1311868220.274890.png 1311868220.268408 depth/1311868220.268408.png +1311868220.310675 rgb/1311868220.310675.png 1311868220.303243 depth/1311868220.303243.png +1311868220.342794 rgb/1311868220.342794.png 1311868220.336368 depth/1311868220.336368.png +1311868220.374967 rgb/1311868220.374967.png 1311868220.368106 depth/1311868220.368106.png +1311868220.410461 rgb/1311868220.410461.png 1311868220.400760 depth/1311868220.400760.png +1311868220.442609 rgb/1311868220.442609.png 1311868220.436414 depth/1311868220.436414.png +1311868220.474751 rgb/1311868220.474751.png 1311868220.468009 depth/1311868220.468009.png +1311868220.510865 rgb/1311868220.510865.png 1311868220.505404 depth/1311868220.505404.png +1311868220.542610 rgb/1311868220.542610.png 1311868220.535923 depth/1311868220.535923.png +1311868220.574495 rgb/1311868220.574495.png 1311868220.568743 depth/1311868220.568743.png +1311868220.611343 rgb/1311868220.611343.png 1311868220.607919 depth/1311868220.607919.png +1311868220.642648 rgb/1311868220.642648.png 1311868220.638122 depth/1311868220.638122.png +1311868220.674598 rgb/1311868220.674598.png 1311868220.669290 depth/1311868220.669290.png +1311868220.710604 rgb/1311868220.710604.png 1311868220.705802 depth/1311868220.705802.png +1311868220.742672 rgb/1311868220.742672.png 1311868220.740041 depth/1311868220.740041.png +1311868220.774530 rgb/1311868220.774530.png 1311868220.768076 depth/1311868220.768076.png +1311868220.810775 rgb/1311868220.810775.png 1311868220.807362 depth/1311868220.807362.png +1311868220.842747 rgb/1311868220.842747.png 1311868220.840215 depth/1311868220.840215.png +1311868220.874779 rgb/1311868220.874779.png 1311868220.868076 depth/1311868220.868076.png +1311868220.910650 rgb/1311868220.910650.png 1311868220.907645 depth/1311868220.907645.png +1311868220.942980 rgb/1311868220.942980.png 1311868220.936974 depth/1311868220.936974.png +1311868220.974895 rgb/1311868220.974895.png 1311868220.971264 depth/1311868220.971264.png +1311868221.010492 rgb/1311868221.010492.png 1311868221.004830 depth/1311868221.004830.png +1311868221.042575 rgb/1311868221.042575.png 1311868221.038022 depth/1311868221.038022.png +1311868221.074778 rgb/1311868221.074778.png 1311868221.068433 depth/1311868221.068433.png +1311868221.110563 rgb/1311868221.110563.png 1311868221.104071 depth/1311868221.104071.png +1311868221.142677 rgb/1311868221.142677.png 1311868221.136394 depth/1311868221.136394.png +1311868221.174633 rgb/1311868221.174633.png 1311868221.168289 depth/1311868221.168289.png +1311868221.210618 rgb/1311868221.210618.png 1311868221.208083 depth/1311868221.208083.png +1311868221.242676 rgb/1311868221.242676.png 1311868221.237782 depth/1311868221.237782.png +1311868221.274959 rgb/1311868221.274959.png 1311868221.270077 depth/1311868221.270077.png +1311868221.311415 rgb/1311868221.311415.png 1311868221.306408 depth/1311868221.306408.png +1311868221.342835 rgb/1311868221.342835.png 1311868221.336428 depth/1311868221.336428.png +1311868221.374902 rgb/1311868221.374902.png 1311868221.370085 depth/1311868221.370085.png +1311868221.410723 rgb/1311868221.410723.png 1311868221.407576 depth/1311868221.407576.png +1311868221.442831 rgb/1311868221.442831.png 1311868221.440279 depth/1311868221.440279.png +1311868221.474658 rgb/1311868221.474658.png 1311868221.470216 depth/1311868221.470216.png +1311868221.510999 rgb/1311868221.510999.png 1311868221.506155 depth/1311868221.506155.png +1311868221.543040 rgb/1311868221.543040.png 1311868221.539623 depth/1311868221.539623.png +1311868221.574743 rgb/1311868221.574743.png 1311868221.571188 depth/1311868221.571188.png +1311868221.610738 rgb/1311868221.610738.png 1311868221.606503 depth/1311868221.606503.png +1311868221.642622 rgb/1311868221.642622.png 1311868221.636216 depth/1311868221.636216.png +1311868221.674631 rgb/1311868221.674631.png 1311868221.673439 depth/1311868221.673439.png +1311868221.711507 rgb/1311868221.711507.png 1311868221.707091 depth/1311868221.707091.png +1311868221.742786 rgb/1311868221.742786.png 1311868221.738380 depth/1311868221.738380.png +1311868221.775854 rgb/1311868221.775854.png 1311868221.775869 depth/1311868221.775869.png +1311868221.810774 rgb/1311868221.810774.png 1311868221.805954 depth/1311868221.805954.png +1311868221.842668 rgb/1311868221.842668.png 1311868221.836585 depth/1311868221.836585.png +1311868221.874613 rgb/1311868221.874613.png 1311868221.873274 depth/1311868221.873274.png +1311868221.910793 rgb/1311868221.910793.png 1311868221.905122 depth/1311868221.905122.png +1311868221.942672 rgb/1311868221.942672.png 1311868221.936660 depth/1311868221.936660.png +1311868221.975288 rgb/1311868221.975288.png 1311868221.975301 depth/1311868221.975301.png +1311868222.010658 rgb/1311868222.010658.png 1311868222.006126 depth/1311868222.006126.png +1311868222.042799 rgb/1311868222.042799.png 1311868222.037887 depth/1311868222.037887.png +1311868222.077068 rgb/1311868222.077068.png 1311868222.077077 depth/1311868222.077077.png +1311868222.110687 rgb/1311868222.110687.png 1311868222.106238 depth/1311868222.106238.png +1311868222.142853 rgb/1311868222.142853.png 1311868222.136039 depth/1311868222.136039.png +1311868222.174994 rgb/1311868222.174994.png 1311868222.175004 depth/1311868222.175004.png +1311868222.210798 rgb/1311868222.210798.png 1311868222.204322 depth/1311868222.204322.png +1311868222.242692 rgb/1311868222.242692.png 1311868222.239963 depth/1311868222.239963.png +1311868222.275699 rgb/1311868222.275699.png 1311868222.275741 depth/1311868222.275741.png +1311868222.310861 rgb/1311868222.310861.png 1311868222.307107 depth/1311868222.307107.png +1311868222.343002 rgb/1311868222.343002.png 1311868222.337833 depth/1311868222.337833.png +1311868222.375332 rgb/1311868222.375332.png 1311868222.375382 depth/1311868222.375382.png +1311868222.410818 rgb/1311868222.410818.png 1311868222.407168 depth/1311868222.407168.png +1311868222.442701 rgb/1311868222.442701.png 1311868222.437456 depth/1311868222.437456.png +1311868222.474746 rgb/1311868222.474746.png 1311868222.474272 depth/1311868222.474272.png +1311868222.510786 rgb/1311868222.510786.png 1311868222.504091 depth/1311868222.504091.png +1311868222.542796 rgb/1311868222.542796.png 1311868222.536822 depth/1311868222.536822.png +1311868222.574664 rgb/1311868222.574664.png 1311868222.573445 depth/1311868222.573445.png +1311868222.610667 rgb/1311868222.610667.png 1311868222.606367 depth/1311868222.606367.png +1311868222.643013 rgb/1311868222.643013.png 1311868222.635993 depth/1311868222.635993.png +1311868222.674911 rgb/1311868222.674911.png 1311868222.674930 depth/1311868222.674930.png +1311868222.710764 rgb/1311868222.710764.png 1311868222.704440 depth/1311868222.704440.png +1311868222.742784 rgb/1311868222.742784.png 1311868222.737516 depth/1311868222.737516.png +1311868222.774863 rgb/1311868222.774863.png 1311868222.774872 depth/1311868222.774872.png +1311868222.810880 rgb/1311868222.810880.png 1311868222.804839 depth/1311868222.804839.png +1311868222.842888 rgb/1311868222.842888.png 1311868222.839765 depth/1311868222.839765.png +1311868222.875581 rgb/1311868222.875581.png 1311868222.875596 depth/1311868222.875596.png +1311868222.910730 rgb/1311868222.910730.png 1311868222.904031 depth/1311868222.904031.png +1311868222.943172 rgb/1311868222.943172.png 1311868222.943183 depth/1311868222.943183.png +1311868222.974842 rgb/1311868222.974842.png 1311868222.971964 depth/1311868222.971964.png +1311868223.012381 rgb/1311868223.012381.png 1311868223.007263 depth/1311868223.007263.png +1311868223.043777 rgb/1311868223.043777.png 1311868223.043787 depth/1311868223.043787.png +1311868223.076517 rgb/1311868223.076517.png 1311868223.076528 depth/1311868223.076528.png +1311868223.110921 rgb/1311868223.110921.png 1311868223.105782 depth/1311868223.105782.png +1311868223.143721 rgb/1311868223.143721.png 1311868223.143738 depth/1311868223.143738.png +1311868223.174769 rgb/1311868223.174769.png 1311868223.172518 depth/1311868223.172518.png +1311868223.210868 rgb/1311868223.210868.png 1311868223.207414 depth/1311868223.207414.png +1311868223.242696 rgb/1311868223.242696.png 1311868223.240462 depth/1311868223.240462.png +1311868223.275316 rgb/1311868223.275316.png 1311868223.275333 depth/1311868223.275333.png +1311868223.310697 rgb/1311868223.310697.png 1311868223.304131 depth/1311868223.304131.png +1311868223.343366 rgb/1311868223.343366.png 1311868223.343387 depth/1311868223.343387.png +1311868223.375535 rgb/1311868223.375535.png 1311868223.375547 depth/1311868223.375547.png +1311868223.410819 rgb/1311868223.410819.png 1311868223.404381 depth/1311868223.404381.png +1311868223.444149 rgb/1311868223.444149.png 1311868223.444168 depth/1311868223.444168.png +1311868223.479074 rgb/1311868223.479074.png 1311868223.479084 depth/1311868223.479084.png +1311868223.511227 rgb/1311868223.511227.png 1311868223.507287 depth/1311868223.507287.png +1311868223.542757 rgb/1311868223.542757.png 1311868223.541966 depth/1311868223.541966.png +1311868223.576261 rgb/1311868223.576261.png 1311868223.575255 depth/1311868223.575255.png +1311868223.610846 rgb/1311868223.610846.png 1311868223.607260 depth/1311868223.607260.png +1311868223.642738 rgb/1311868223.642738.png 1311868223.640714 depth/1311868223.640714.png +1311868223.674789 rgb/1311868223.674789.png 1311868223.672328 depth/1311868223.672328.png +1311868223.710948 rgb/1311868223.710948.png 1311868223.706442 depth/1311868223.706442.png +1311868223.742872 rgb/1311868223.742872.png 1311868223.740662 depth/1311868223.740662.png +1311868223.774925 rgb/1311868223.774925.png 1311868223.773620 depth/1311868223.773620.png +1311868223.810993 rgb/1311868223.810993.png 1311868223.804209 depth/1311868223.804209.png +1311868223.842828 rgb/1311868223.842828.png 1311868223.840316 depth/1311868223.840316.png +1311868223.874841 rgb/1311868223.874841.png 1311868223.872281 depth/1311868223.872281.png +1311868223.910906 rgb/1311868223.910906.png 1311868223.904377 depth/1311868223.904377.png +1311868223.943036 rgb/1311868223.943036.png 1311868223.943290 depth/1311868223.943290.png +1311868223.975101 rgb/1311868223.975101.png 1311868223.975108 depth/1311868223.975108.png +1311868224.010808 rgb/1311868224.010808.png 1311868224.007653 depth/1311868224.007653.png +1311868224.043743 rgb/1311868224.043743.png 1311868224.040432 depth/1311868224.040432.png +1311868224.075595 rgb/1311868224.075595.png 1311868224.075604 depth/1311868224.075604.png +1311868224.110830 rgb/1311868224.110830.png 1311868224.107394 depth/1311868224.107394.png +1311868224.145344 rgb/1311868224.145344.png 1311868224.145360 depth/1311868224.145360.png +1311868224.174788 rgb/1311868224.174788.png 1311868224.172734 depth/1311868224.172734.png +1311868224.211401 rgb/1311868224.211401.png 1311868224.211885 depth/1311868224.211885.png +1311868224.242911 rgb/1311868224.242911.png 1311868224.240252 depth/1311868224.240252.png +1311868224.277363 rgb/1311868224.277363.png 1311868224.273978 depth/1311868224.273978.png +1311868224.311516 rgb/1311868224.311516.png 1311868224.311536 depth/1311868224.311536.png +1311868224.342895 rgb/1311868224.342895.png 1311868224.340357 depth/1311868224.340357.png +1311868224.374897 rgb/1311868224.374897.png 1311868224.373499 depth/1311868224.373499.png +1311868224.410879 rgb/1311868224.410879.png 1311868224.408817 depth/1311868224.408817.png +1311868224.442907 rgb/1311868224.442907.png 1311868224.442917 depth/1311868224.442917.png +1311868224.474953 rgb/1311868224.474953.png 1311868224.472124 depth/1311868224.472124.png +1311868224.511812 rgb/1311868224.511812.png 1311868224.511856 depth/1311868224.511856.png +1311868224.545292 rgb/1311868224.545292.png 1311868224.545162 depth/1311868224.545162.png +1311868224.574703 rgb/1311868224.574703.png 1311868224.573673 depth/1311868224.573673.png +1311868224.611208 rgb/1311868224.611208.png 1311868224.611247 depth/1311868224.611247.png +1311868224.643090 rgb/1311868224.643090.png 1311868224.643159 depth/1311868224.643159.png +1311868224.674856 rgb/1311868224.674856.png 1311868224.672374 depth/1311868224.672374.png +1311868224.710776 rgb/1311868224.710776.png 1311868224.710056 depth/1311868224.710056.png +1311868224.742798 rgb/1311868224.742798.png 1311868224.740644 depth/1311868224.740644.png +1311868224.775598 rgb/1311868224.775598.png 1311868224.775615 depth/1311868224.775615.png +1311868224.812285 rgb/1311868224.812285.png 1311868224.812297 depth/1311868224.812297.png +1311868224.842708 rgb/1311868224.842708.png 1311868224.841945 depth/1311868224.841945.png +1311868224.874851 rgb/1311868224.874851.png 1311868224.874405 depth/1311868224.874405.png +1311868224.912106 rgb/1311868224.912106.png 1311868224.912116 depth/1311868224.912116.png +1311868224.943076 rgb/1311868224.943076.png 1311868224.940425 depth/1311868224.940425.png +1311868224.978324 rgb/1311868224.978324.png 1311868224.975279 depth/1311868224.975279.png +1311868225.012002 rgb/1311868225.012002.png 1311868225.012017 depth/1311868225.012017.png +1311868225.045354 rgb/1311868225.045354.png 1311868225.042544 depth/1311868225.042544.png +1311868225.076066 rgb/1311868225.076066.png 1311868225.076080 depth/1311868225.076080.png +1311868225.111236 rgb/1311868225.111236.png 1311868225.111317 depth/1311868225.111317.png +1311868225.143930 rgb/1311868225.143930.png 1311868225.143950 depth/1311868225.143950.png +1311868225.176049 rgb/1311868225.176049.png 1311868225.176066 depth/1311868225.176066.png +1311868225.211565 rgb/1311868225.211565.png 1311868225.209393 depth/1311868225.209393.png +1311868225.242896 rgb/1311868225.242896.png 1311868225.240636 depth/1311868225.240636.png +1311868225.275007 rgb/1311868225.275007.png 1311868225.275019 depth/1311868225.275019.png +1311868225.310787 rgb/1311868225.310787.png 1311868225.310797 depth/1311868225.310797.png +1311868225.342940 rgb/1311868225.342940.png 1311868225.340158 depth/1311868225.340158.png +1311868225.379392 rgb/1311868225.379392.png 1311868225.379405 depth/1311868225.379405.png +1311868225.410917 rgb/1311868225.410917.png 1311868225.410937 depth/1311868225.410937.png +1311868225.443381 rgb/1311868225.443381.png 1311868225.443405 depth/1311868225.443405.png +1311868225.479273 rgb/1311868225.479273.png 1311868225.479285 depth/1311868225.479285.png +1311868225.510884 rgb/1311868225.510884.png 1311868225.508380 depth/1311868225.508380.png +1311868225.542923 rgb/1311868225.542923.png 1311868225.541319 depth/1311868225.541319.png +1311868225.576439 rgb/1311868225.576439.png 1311868225.576451 depth/1311868225.576451.png +1311868225.612078 rgb/1311868225.612078.png 1311868225.612089 depth/1311868225.612089.png +1311868225.644151 rgb/1311868225.644151.png 1311868225.644160 depth/1311868225.644160.png +1311868225.678868 rgb/1311868225.678868.png 1311868225.678877 depth/1311868225.678877.png +1311868225.711259 rgb/1311868225.711259.png 1311868225.711272 depth/1311868225.711272.png +1311868225.746296 rgb/1311868225.746296.png 1311868225.746313 depth/1311868225.746313.png +1311868225.776898 rgb/1311868225.776898.png 1311868225.776903 depth/1311868225.776903.png +1311868225.810874 rgb/1311868225.810874.png 1311868225.810134 depth/1311868225.810134.png +1311868225.842939 rgb/1311868225.842939.png 1311868225.841916 depth/1311868225.841916.png +1311868225.880247 rgb/1311868225.880247.png 1311868225.880278 depth/1311868225.880278.png +1311868225.910765 rgb/1311868225.910765.png 1311868225.909912 depth/1311868225.909912.png +1311868225.943096 rgb/1311868225.943096.png 1311868225.943109 depth/1311868225.943109.png +1311868225.977018 rgb/1311868225.977018.png 1311868225.977027 depth/1311868225.977027.png +1311868226.010899 rgb/1311868226.010899.png 1311868226.008677 depth/1311868226.008677.png +1311868226.043782 rgb/1311868226.043782.png 1311868226.043800 depth/1311868226.043800.png +1311868226.079850 rgb/1311868226.079850.png 1311868226.079861 depth/1311868226.079861.png +1311868226.115058 rgb/1311868226.115058.png 1311868226.115075 depth/1311868226.115075.png +1311868226.144537 rgb/1311868226.144537.png 1311868226.144546 depth/1311868226.144546.png +1311868226.178896 rgb/1311868226.178896.png 1311868226.178910 depth/1311868226.178910.png +1311868226.210939 rgb/1311868226.210939.png 1311868226.210944 depth/1311868226.210944.png +1311868226.247306 rgb/1311868226.247306.png 1311868226.246456 depth/1311868226.246456.png +1311868226.277609 rgb/1311868226.277609.png 1311868226.277625 depth/1311868226.277625.png +1311868226.310950 rgb/1311868226.310950.png 1311868226.308469 depth/1311868226.308469.png +1311868226.345151 rgb/1311868226.345151.png 1311868226.345166 depth/1311868226.345166.png +1311868226.381607 rgb/1311868226.381607.png 1311868226.381651 depth/1311868226.381651.png +1311868226.411020 rgb/1311868226.411020.png 1311868226.408655 depth/1311868226.408655.png +1311868226.444052 rgb/1311868226.444052.png 1311868226.444073 depth/1311868226.444073.png +1311868226.481112 rgb/1311868226.481112.png 1311868226.481122 depth/1311868226.481122.png +1311868226.511027 rgb/1311868226.511027.png 1311868226.508358 depth/1311868226.508358.png +1311868226.543455 rgb/1311868226.543455.png 1311868226.546524 depth/1311868226.546524.png +1311868226.576612 rgb/1311868226.576612.png 1311868226.576639 depth/1311868226.576639.png +1311868226.610909 rgb/1311868226.610909.png 1311868226.610319 depth/1311868226.610319.png +1311868226.644260 rgb/1311868226.644260.png 1311868226.644264 depth/1311868226.644264.png +1311868226.676348 rgb/1311868226.676348.png 1311868226.676359 depth/1311868226.676359.png +1311868226.711126 rgb/1311868226.711126.png 1311868226.708363 depth/1311868226.708363.png +1311868226.745829 rgb/1311868226.745829.png 1311868226.745837 depth/1311868226.745837.png +1311868226.778492 rgb/1311868226.778492.png 1311868226.778507 depth/1311868226.778507.png +1311868226.810784 rgb/1311868226.810784.png 1311868226.809730 depth/1311868226.809730.png +1311868226.844284 rgb/1311868226.844284.png 1311868226.844289 depth/1311868226.844289.png +1311868226.879222 rgb/1311868226.879222.png 1311868226.879251 depth/1311868226.879251.png +1311868226.910863 rgb/1311868226.910863.png 1311868226.908253 depth/1311868226.908253.png +1311868226.944204 rgb/1311868226.944204.png 1311868226.944215 depth/1311868226.944215.png +1311868226.976309 rgb/1311868226.976309.png 1311868226.976315 depth/1311868226.976315.png +1311868227.010946 rgb/1311868227.010946.png 1311868227.010792 depth/1311868227.010792.png +1311868227.047092 rgb/1311868227.047092.png 1311868227.047113 depth/1311868227.047113.png +1311868227.077103 rgb/1311868227.077103.png 1311868227.077119 depth/1311868227.077119.png +1311868227.110902 rgb/1311868227.110902.png 1311868227.109667 depth/1311868227.109667.png +1311868227.144535 rgb/1311868227.144535.png 1311868227.144548 depth/1311868227.144548.png +1311868227.179137 rgb/1311868227.179137.png 1311868227.179146 depth/1311868227.179146.png +1311868227.210865 rgb/1311868227.210865.png 1311868227.209760 depth/1311868227.209760.png +1311868227.247413 rgb/1311868227.247413.png 1311868227.247444 depth/1311868227.247444.png +1311868227.276556 rgb/1311868227.276556.png 1311868227.276576 depth/1311868227.276576.png +1311868227.311677 rgb/1311868227.311677.png 1311868227.311685 depth/1311868227.311685.png +1311868227.347893 rgb/1311868227.347893.png 1311868227.347925 depth/1311868227.347925.png +1311868227.377762 rgb/1311868227.377762.png 1311868227.377769 depth/1311868227.377769.png +1311868227.411422 rgb/1311868227.411422.png 1311868227.411441 depth/1311868227.411441.png +1311868227.446682 rgb/1311868227.446682.png 1311868227.446700 depth/1311868227.446700.png +1311868227.479018 rgb/1311868227.479018.png 1311868227.476734 depth/1311868227.476734.png +1311868227.510861 rgb/1311868227.510861.png 1311868227.509621 depth/1311868227.509621.png +1311868227.547438 rgb/1311868227.547438.png 1311868227.547447 depth/1311868227.547447.png +1311868227.579073 rgb/1311868227.579073.png 1311868227.576509 depth/1311868227.576509.png +1311868227.610890 rgb/1311868227.610890.png 1311868227.610169 depth/1311868227.610169.png +1311868227.644341 rgb/1311868227.644341.png 1311868227.644352 depth/1311868227.644352.png +1311868227.679026 rgb/1311868227.679026.png 1311868227.676558 depth/1311868227.676558.png +1311868227.711001 rgb/1311868227.711001.png 1311868227.708818 depth/1311868227.708818.png +1311868227.744281 rgb/1311868227.744281.png 1311868227.744295 depth/1311868227.744295.png +1311868227.779154 rgb/1311868227.779154.png 1311868227.776629 depth/1311868227.776629.png +1311868227.813722 rgb/1311868227.813722.png 1311868227.813739 depth/1311868227.813739.png +1311868227.844330 rgb/1311868227.844330.png 1311868227.844235 depth/1311868227.844235.png +1311868227.879151 rgb/1311868227.879151.png 1311868227.876400 depth/1311868227.876400.png +1311868227.912471 rgb/1311868227.912471.png 1311868227.912496 depth/1311868227.912496.png +1311868227.946163 rgb/1311868227.946163.png 1311868227.946174 depth/1311868227.946174.png +1311868227.979289 rgb/1311868227.979289.png 1311868227.979307 depth/1311868227.979307.png +1311868228.014729 rgb/1311868228.014729.png 1311868228.014743 depth/1311868228.014743.png +1311868228.044938 rgb/1311868228.044938.png 1311868228.044945 depth/1311868228.044945.png +1311868228.079022 rgb/1311868228.079022.png 1311868228.079040 depth/1311868228.079040.png +1311868228.112684 rgb/1311868228.112684.png 1311868228.112696 depth/1311868228.112696.png +1311868228.146187 rgb/1311868228.146187.png 1311868228.146245 depth/1311868228.146245.png +1311868228.178968 rgb/1311868228.178968.png 1311868228.177569 depth/1311868228.177569.png +1311868228.214746 rgb/1311868228.214746.png 1311868228.214818 depth/1311868228.214818.png +1311868228.246147 rgb/1311868228.246147.png 1311868228.246155 depth/1311868228.246155.png +1311868228.279971 rgb/1311868228.279971.png 1311868228.277518 depth/1311868228.277518.png +1311868228.312417 rgb/1311868228.312417.png 1311868228.312426 depth/1311868228.312426.png +1311868228.344381 rgb/1311868228.344381.png 1311868228.344411 depth/1311868228.344411.png +1311868228.378967 rgb/1311868228.378967.png 1311868228.378082 depth/1311868228.378082.png +1311868228.412437 rgb/1311868228.412437.png 1311868228.412447 depth/1311868228.412447.png +1311868228.444527 rgb/1311868228.444527.png 1311868228.444535 depth/1311868228.444535.png +1311868228.479553 rgb/1311868228.479553.png 1311868228.477488 depth/1311868228.477488.png +1311868228.515154 rgb/1311868228.515154.png 1311868228.515164 depth/1311868228.515164.png +1311868228.545801 rgb/1311868228.545801.png 1311868228.545809 depth/1311868228.545809.png +1311868228.579592 rgb/1311868228.579592.png 1311868228.576548 depth/1311868228.576548.png +1311868228.612450 rgb/1311868228.612450.png 1311868228.613103 depth/1311868228.613103.png +1311868228.645315 rgb/1311868228.645315.png 1311868228.645326 depth/1311868228.645326.png +1311868228.679035 rgb/1311868228.679035.png 1311868228.678198 depth/1311868228.678198.png +1311868228.714922 rgb/1311868228.714922.png 1311868228.714943 depth/1311868228.714943.png +1311868228.746541 rgb/1311868228.746541.png 1311868228.746562 depth/1311868228.746562.png +1311868228.779112 rgb/1311868228.779112.png 1311868228.776419 depth/1311868228.776419.png +1311868228.815012 rgb/1311868228.815012.png 1311868228.815023 depth/1311868228.815023.png +1311868228.844666 rgb/1311868228.844666.png 1311868228.844682 depth/1311868228.844682.png +1311868228.879273 rgb/1311868228.879273.png 1311868228.876855 depth/1311868228.876855.png +1311868228.912667 rgb/1311868228.912667.png 1311868228.912678 depth/1311868228.912678.png +1311868228.944678 rgb/1311868228.944678.png 1311868228.944686 depth/1311868228.944686.png +1311868228.979108 rgb/1311868228.979108.png 1311868228.976767 depth/1311868228.976767.png +1311868229.012685 rgb/1311868229.012685.png 1311868229.012705 depth/1311868229.012705.png +1311868229.044504 rgb/1311868229.044504.png 1311868229.044519 depth/1311868229.044519.png +1311868229.080635 rgb/1311868229.080635.png 1311868229.080644 depth/1311868229.080644.png +1311868229.115479 rgb/1311868229.115479.png 1311868229.115079 depth/1311868229.115079.png +1311868229.148295 rgb/1311868229.148295.png 1311868229.148304 depth/1311868229.148304.png +1311868229.184081 rgb/1311868229.184081.png 1311868229.184100 depth/1311868229.184100.png +1311868229.216477 rgb/1311868229.216477.png 1311868229.216508 depth/1311868229.216508.png +1311868229.249047 rgb/1311868229.249047.png 1311868229.249184 depth/1311868229.249184.png +1311868229.281198 rgb/1311868229.281198.png 1311868229.281306 depth/1311868229.281306.png +1311868229.315238 rgb/1311868229.315238.png 1311868229.315247 depth/1311868229.315247.png +1311868229.350313 rgb/1311868229.350313.png 1311868229.345007 depth/1311868229.345007.png +1311868229.381047 rgb/1311868229.381047.png 1311868229.381055 depth/1311868229.381055.png +1311868229.413148 rgb/1311868229.413148.png 1311868229.413156 depth/1311868229.413156.png +1311868229.444833 rgb/1311868229.444833.png 1311868229.444845 depth/1311868229.444845.png +1311868229.482439 rgb/1311868229.482439.png 1311868229.482317 depth/1311868229.482317.png +1311868229.512638 rgb/1311868229.512638.png 1311868229.512643 depth/1311868229.512643.png +1311868229.547820 rgb/1311868229.547820.png 1311868229.547829 depth/1311868229.547829.png +1311868229.580641 rgb/1311868229.580641.png 1311868229.580649 depth/1311868229.580649.png +1311868229.613429 rgb/1311868229.613429.png 1311868229.613438 depth/1311868229.613438.png +1311868229.647479 rgb/1311868229.647479.png 1311868229.647491 depth/1311868229.647491.png +1311868229.681523 rgb/1311868229.681523.png 1311868229.681542 depth/1311868229.681542.png +1311868229.712459 rgb/1311868229.712459.png 1311868229.712514 depth/1311868229.712514.png +1311868229.748721 rgb/1311868229.748721.png 1311868229.748851 depth/1311868229.748851.png +1311868229.782489 rgb/1311868229.782489.png 1311868229.782512 depth/1311868229.782512.png +1311868229.812669 rgb/1311868229.812669.png 1311868229.812710 depth/1311868229.812710.png +1311868229.844489 rgb/1311868229.844489.png 1311868229.844496 depth/1311868229.844496.png +1311868229.883361 rgb/1311868229.883361.png 1311868229.883367 depth/1311868229.883367.png +1311868229.914462 rgb/1311868229.914462.png 1311868229.914473 depth/1311868229.914473.png +1311868229.944417 rgb/1311868229.944417.png 1311868229.944425 depth/1311868229.944425.png +1311868229.982424 rgb/1311868229.982424.png 1311868229.982447 depth/1311868229.982447.png +1311868230.012490 rgb/1311868230.012490.png 1311868230.012502 depth/1311868230.012502.png +1311868230.047030 rgb/1311868230.047030.png 1311868230.047041 depth/1311868230.047041.png +1311868230.083190 rgb/1311868230.083190.png 1311868230.083195 depth/1311868230.083195.png +1311868230.113585 rgb/1311868230.113585.png 1311868230.113593 depth/1311868230.113593.png +1311868230.147393 rgb/1311868230.147393.png 1311868230.147405 depth/1311868230.147405.png +1311868230.180570 rgb/1311868230.180570.png 1311868230.180580 depth/1311868230.180580.png +1311868230.214879 rgb/1311868230.214879.png 1311868230.214916 depth/1311868230.214916.png +1311868230.245363 rgb/1311868230.245363.png 1311868230.245372 depth/1311868230.245372.png +1311868230.283031 rgb/1311868230.283031.png 1311868230.283053 depth/1311868230.283053.png +1311868230.312518 rgb/1311868230.312518.png 1311868230.312531 depth/1311868230.312531.png +1311868230.343265 rgb/1311868230.343265.png 1311868230.353156 depth/1311868230.353156.png +1311868230.382061 rgb/1311868230.382061.png 1311868230.382076 depth/1311868230.382076.png +1311868230.414198 rgb/1311868230.414198.png 1311868230.414216 depth/1311868230.414216.png +1311868230.443234 rgb/1311868230.443234.png 1311868230.450510 depth/1311868230.450510.png +1311868230.484314 rgb/1311868230.484314.png 1311868230.484325 depth/1311868230.484325.png +1311868230.512705 rgb/1311868230.512705.png 1311868230.512945 depth/1311868230.512945.png +1311868230.543330 rgb/1311868230.543330.png 1311868230.549719 depth/1311868230.549719.png +1311868230.582035 rgb/1311868230.582035.png 1311868230.582042 depth/1311868230.582042.png +1311868230.613609 rgb/1311868230.613609.png 1311868230.613625 depth/1311868230.613625.png +1311868230.643420 rgb/1311868230.643420.png 1311868230.649952 depth/1311868230.649952.png +1311868230.682847 rgb/1311868230.682847.png 1311868230.682859 depth/1311868230.682859.png +1311868230.713079 rgb/1311868230.713079.png 1311868230.713087 depth/1311868230.713087.png +1311868230.743239 rgb/1311868230.743239.png 1311868230.752279 depth/1311868230.752279.png +1311868230.783163 rgb/1311868230.783163.png 1311868230.783179 depth/1311868230.783179.png +1311868230.812536 rgb/1311868230.812536.png 1311868230.812551 depth/1311868230.812551.png +1311868230.843194 rgb/1311868230.843194.png 1311868230.849972 depth/1311868230.849972.png +1311868230.884514 rgb/1311868230.884514.png 1311868230.884557 depth/1311868230.884557.png +1311868230.912835 rgb/1311868230.912835.png 1311868230.912844 depth/1311868230.912844.png +1311868230.943429 rgb/1311868230.943429.png 1311868230.950464 depth/1311868230.950464.png +1311868230.983928 rgb/1311868230.983928.png 1311868230.983939 depth/1311868230.983939.png +1311868231.012678 rgb/1311868231.012678.png 1311868231.012688 depth/1311868231.012688.png +1311868231.043362 rgb/1311868231.043362.png 1311868231.053257 depth/1311868231.053257.png +1311868231.083967 rgb/1311868231.083967.png 1311868231.083982 depth/1311868231.083982.png +1311868231.115505 rgb/1311868231.115505.png 1311868231.115521 depth/1311868231.115521.png +1311868231.143191 rgb/1311868231.143191.png 1311868231.150642 depth/1311868231.150642.png +1311868231.180564 rgb/1311868231.180564.png 1311868231.180574 depth/1311868231.180574.png +1311868231.215427 rgb/1311868231.215427.png 1311868231.215437 depth/1311868231.215437.png +1311868231.243144 rgb/1311868231.243144.png 1311868231.251532 depth/1311868231.251532.png +1311868231.284432 rgb/1311868231.284432.png 1311868231.284151 depth/1311868231.284151.png +1311868231.313322 rgb/1311868231.313322.png 1311868231.313332 depth/1311868231.313332.png +1311868231.343237 rgb/1311868231.343237.png 1311868231.350818 depth/1311868231.350818.png +1311868231.380706 rgb/1311868231.380706.png 1311868231.385816 depth/1311868231.385816.png +1311868231.412886 rgb/1311868231.412886.png 1311868231.412906 depth/1311868231.412906.png +1311868231.443247 rgb/1311868231.443247.png 1311868231.451469 depth/1311868231.451469.png +1311868231.481615 rgb/1311868231.481615.png 1311868231.481626 depth/1311868231.481626.png +1311868231.514222 rgb/1311868231.514222.png 1311868231.514232 depth/1311868231.514232.png +1311868231.543183 rgb/1311868231.543183.png 1311868231.551045 depth/1311868231.551045.png +1311868231.582970 rgb/1311868231.582970.png 1311868231.582981 depth/1311868231.582981.png +1311868231.611182 rgb/1311868231.611182.png 1311868231.616852 depth/1311868231.616852.png +1311868231.643249 rgb/1311868231.643249.png 1311868231.650892 depth/1311868231.650892.png +1311868231.683851 rgb/1311868231.683851.png 1311868231.683868 depth/1311868231.683868.png +1311868231.711268 rgb/1311868231.711268.png 1311868231.718914 depth/1311868231.718914.png +1311868231.743341 rgb/1311868231.743341.png 1311868231.749256 depth/1311868231.749256.png +1311868231.782700 rgb/1311868231.782700.png 1311868231.782718 depth/1311868231.782718.png +1311868231.811225 rgb/1311868231.811225.png 1311868231.817512 depth/1311868231.817512.png +1311868231.843239 rgb/1311868231.843239.png 1311868231.848763 depth/1311868231.848763.png +1311868231.883453 rgb/1311868231.883453.png 1311868231.883462 depth/1311868231.883462.png +1311868231.911236 rgb/1311868231.911236.png 1311868231.917510 depth/1311868231.917510.png +1311868231.943245 rgb/1311868231.943245.png 1311868231.949859 depth/1311868231.949859.png +1311868231.981369 rgb/1311868231.981369.png 1311868231.981380 depth/1311868231.981380.png +1311868232.011255 rgb/1311868232.011255.png 1311868232.019822 depth/1311868232.019822.png +1311868232.043334 rgb/1311868232.043334.png 1311868232.053452 depth/1311868232.053452.png +1311868232.084470 rgb/1311868232.084470.png 1311868232.082697 depth/1311868232.082697.png +1311868232.111198 rgb/1311868232.111198.png 1311868232.117808 depth/1311868232.117808.png +1311868232.143235 rgb/1311868232.143235.png 1311868232.150460 depth/1311868232.150460.png +1311868232.180728 rgb/1311868232.180728.png 1311868232.180762 depth/1311868232.180762.png +1311868232.211380 rgb/1311868232.211380.png 1311868232.220546 depth/1311868232.220546.png +1311868232.243208 rgb/1311868232.243208.png 1311868232.250282 depth/1311868232.250282.png +1311868232.280974 rgb/1311868232.280974.png 1311868232.280983 depth/1311868232.280983.png +1311868232.311279 rgb/1311868232.311279.png 1311868232.318613 depth/1311868232.318613.png +1311868232.343193 rgb/1311868232.343193.png 1311868232.349347 depth/1311868232.349347.png +1311868232.380596 rgb/1311868232.380596.png 1311868232.380604 depth/1311868232.380604.png +1311868232.411402 rgb/1311868232.411402.png 1311868232.417365 depth/1311868232.417365.png +1311868232.443259 rgb/1311868232.443259.png 1311868232.449624 depth/1311868232.449624.png +1311868232.482622 rgb/1311868232.482622.png 1311868232.482363 depth/1311868232.482363.png +1311868232.511307 rgb/1311868232.511307.png 1311868232.517622 depth/1311868232.517622.png +1311868232.543326 rgb/1311868232.543326.png 1311868232.549644 depth/1311868232.549644.png +1311868232.583131 rgb/1311868232.583131.png 1311868232.583150 depth/1311868232.583150.png +1311868232.611461 rgb/1311868232.611461.png 1311868232.618049 depth/1311868232.618049.png +1311868232.643442 rgb/1311868232.643442.png 1311868232.651240 depth/1311868232.651240.png +1311868232.683408 rgb/1311868232.683408.png 1311868232.683275 depth/1311868232.683275.png +1311868232.711301 rgb/1311868232.711301.png 1311868232.717433 depth/1311868232.717433.png +1311868232.744002 rgb/1311868232.744002.png 1311868232.760567 depth/1311868232.760567.png +1311868232.779268 rgb/1311868232.779268.png 1311868232.788795 depth/1311868232.788795.png +1311868232.811594 rgb/1311868232.811594.png 1311868232.821899 depth/1311868232.821899.png +1311868232.843289 rgb/1311868232.843289.png 1311868232.849796 depth/1311868232.849796.png +1311868232.879421 rgb/1311868232.879421.png 1311868232.886899 depth/1311868232.886899.png +1311868232.911483 rgb/1311868232.911483.png 1311868232.917623 depth/1311868232.917623.png +1311868232.943301 rgb/1311868232.943301.png 1311868232.950276 depth/1311868232.950276.png +1311868232.979469 rgb/1311868232.979469.png 1311868232.988268 depth/1311868232.988268.png +1311868233.011303 rgb/1311868233.011303.png 1311868233.017130 depth/1311868233.017130.png +1311868233.043607 rgb/1311868233.043607.png 1311868233.053790 depth/1311868233.053790.png +1311868233.079646 rgb/1311868233.079646.png 1311868233.087365 depth/1311868233.087365.png +1311868233.111321 rgb/1311868233.111321.png 1311868233.120528 depth/1311868233.120528.png +1311868233.143478 rgb/1311868233.143478.png 1311868233.150808 depth/1311868233.150808.png +1311868233.179701 rgb/1311868233.179701.png 1311868233.190997 depth/1311868233.190997.png +1311868233.211366 rgb/1311868233.211366.png 1311868233.217818 depth/1311868233.217818.png +1311868233.243606 rgb/1311868233.243606.png 1311868233.255486 depth/1311868233.255486.png +1311868233.279654 rgb/1311868233.279654.png 1311868233.286477 depth/1311868233.286477.png +1311868233.311396 rgb/1311868233.311396.png 1311868233.317556 depth/1311868233.317556.png +1311868233.343465 rgb/1311868233.343465.png 1311868233.351808 depth/1311868233.351808.png +1311868233.379449 rgb/1311868233.379449.png 1311868233.389965 depth/1311868233.389965.png +1311868233.411418 rgb/1311868233.411418.png 1311868233.423306 depth/1311868233.423306.png +1311868233.443336 rgb/1311868233.443336.png 1311868233.450921 depth/1311868233.450921.png +1311868233.479382 rgb/1311868233.479382.png 1311868233.487479 depth/1311868233.487479.png +1311868233.511408 rgb/1311868233.511408.png 1311868233.519239 depth/1311868233.519239.png +1311868233.543443 rgb/1311868233.543443.png 1311868233.552597 depth/1311868233.552597.png +1311868233.579545 rgb/1311868233.579545.png 1311868233.588303 depth/1311868233.588303.png +1311868233.611453 rgb/1311868233.611453.png 1311868233.622230 depth/1311868233.622230.png +1311868233.643320 rgb/1311868233.643320.png 1311868233.650993 depth/1311868233.650993.png +1311868233.679470 rgb/1311868233.679470.png 1311868233.691955 depth/1311868233.691955.png +1311868233.711536 rgb/1311868233.711536.png 1311868233.720779 depth/1311868233.720779.png +1311868233.743366 rgb/1311868233.743366.png 1311868233.751733 depth/1311868233.751733.png +1311868233.779597 rgb/1311868233.779597.png 1311868233.787975 depth/1311868233.787975.png +1311868233.811509 rgb/1311868233.811509.png 1311868233.818118 depth/1311868233.818118.png +1311868233.843614 rgb/1311868233.843614.png 1311868233.851616 depth/1311868233.851616.png +1311868233.879475 rgb/1311868233.879475.png 1311868233.889151 depth/1311868233.889151.png +1311868233.911537 rgb/1311868233.911537.png 1311868233.923064 depth/1311868233.923064.png +1311868233.943472 rgb/1311868233.943472.png 1311868233.955333 depth/1311868233.955333.png +1311868233.979347 rgb/1311868233.979347.png 1311868233.986443 depth/1311868233.986443.png +1311868234.011459 rgb/1311868234.011459.png 1311868234.021528 depth/1311868234.021528.png +1311868234.043413 rgb/1311868234.043413.png 1311868234.056173 depth/1311868234.056173.png +1311868234.079556 rgb/1311868234.079556.png 1311868234.088018 depth/1311868234.088018.png +1311868234.111633 rgb/1311868234.111633.png 1311868234.119824 depth/1311868234.119824.png +1311868234.143456 rgb/1311868234.143456.png 1311868234.158777 depth/1311868234.158777.png +1311868234.179448 rgb/1311868234.179448.png 1311868234.190031 depth/1311868234.190031.png +1311868234.211483 rgb/1311868234.211483.png 1311868234.217779 depth/1311868234.217779.png +1311868234.243581 rgb/1311868234.243581.png 1311868234.260062 depth/1311868234.260062.png +1311868234.279402 rgb/1311868234.279402.png 1311868234.288925 depth/1311868234.288925.png +1311868234.311515 rgb/1311868234.311515.png 1311868234.317660 depth/1311868234.317660.png +1311868234.343505 rgb/1311868234.343505.png 1311868234.358032 depth/1311868234.358032.png +1311868234.379573 rgb/1311868234.379573.png 1311868234.387788 depth/1311868234.387788.png +1311868234.411591 rgb/1311868234.411591.png 1311868234.420269 depth/1311868234.420269.png +1311868234.443480 rgb/1311868234.443480.png 1311868234.458374 depth/1311868234.458374.png +1311868234.479529 rgb/1311868234.479529.png 1311868234.489425 depth/1311868234.489425.png +1311868234.511642 rgb/1311868234.511642.png 1311868234.522233 depth/1311868234.522233.png +1311868234.543567 rgb/1311868234.543567.png 1311868234.555122 depth/1311868234.555122.png +1311868234.579412 rgb/1311868234.579412.png 1311868234.585931 depth/1311868234.585931.png +1311868234.611718 rgb/1311868234.611718.png 1311868234.622267 depth/1311868234.622267.png +1311868234.643547 rgb/1311868234.643547.png 1311868234.659470 depth/1311868234.659470.png +1311868234.679531 rgb/1311868234.679531.png 1311868234.687519 depth/1311868234.687519.png +1311868234.711442 rgb/1311868234.711442.png 1311868234.719153 depth/1311868234.719153.png +1311868234.743637 rgb/1311868234.743637.png 1311868234.758006 depth/1311868234.758006.png +1311868234.779522 rgb/1311868234.779522.png 1311868234.787070 depth/1311868234.787070.png +1311868234.811711 rgb/1311868234.811711.png 1311868234.822201 depth/1311868234.822201.png +1311868234.843512 rgb/1311868234.843512.png 1311868234.859209 depth/1311868234.859209.png +1311868234.879399 rgb/1311868234.879399.png 1311868234.888554 depth/1311868234.888554.png +1311868234.911468 rgb/1311868234.911468.png 1311868234.920603 depth/1311868234.920603.png +1311868234.943562 rgb/1311868234.943562.png 1311868234.957717 depth/1311868234.957717.png +1311868234.979489 rgb/1311868234.979489.png 1311868234.986417 depth/1311868234.986417.png +1311868235.011644 rgb/1311868235.011644.png 1311868235.023210 depth/1311868235.023210.png +1311868235.043680 rgb/1311868235.043680.png 1311868235.059341 depth/1311868235.059341.png +1311868235.079664 rgb/1311868235.079664.png 1311868235.087705 depth/1311868235.087705.png +1311868235.111629 rgb/1311868235.111629.png 1311868235.122347 depth/1311868235.122347.png +1311868235.143595 rgb/1311868235.143595.png 1311868235.156195 depth/1311868235.156195.png +1311868235.179665 rgb/1311868235.179665.png 1311868235.188790 depth/1311868235.188790.png +1311868235.211489 rgb/1311868235.211489.png 1311868235.226668 depth/1311868235.226668.png +1311868235.243614 rgb/1311868235.243614.png 1311868235.256378 depth/1311868235.256378.png +1311868235.279710 rgb/1311868235.279710.png 1311868235.289189 depth/1311868235.289189.png +1311868235.311695 rgb/1311868235.311695.png 1311868235.325958 depth/1311868235.325958.png +1311868235.343699 rgb/1311868235.343699.png 1311868235.358123 depth/1311868235.358123.png +1311868235.379762 rgb/1311868235.379762.png 1311868235.390186 depth/1311868235.390186.png +1311868235.411537 rgb/1311868235.411537.png 1311868235.423937 depth/1311868235.423937.png +1311868235.443732 rgb/1311868235.443732.png 1311868235.458843 depth/1311868235.458843.png +1311868235.479571 rgb/1311868235.479571.png 1311868235.487231 depth/1311868235.487231.png +1311868235.511713 rgb/1311868235.511713.png 1311868235.526273 depth/1311868235.526273.png +1311868235.543566 rgb/1311868235.543566.png 1311868235.557763 depth/1311868235.557763.png +1311868235.579657 rgb/1311868235.579657.png 1311868235.590548 depth/1311868235.590548.png +1311868235.611793 rgb/1311868235.611793.png 1311868235.627906 depth/1311868235.627906.png +1311868235.643525 rgb/1311868235.643525.png 1311868235.656834 depth/1311868235.656834.png +1311868235.679690 rgb/1311868235.679690.png 1311868235.686960 depth/1311868235.686960.png +1311868235.711568 rgb/1311868235.711568.png 1311868235.725908 depth/1311868235.725908.png +1311868235.743898 rgb/1311868235.743898.png 1311868235.754141 depth/1311868235.754141.png +1311868235.779537 rgb/1311868235.779537.png 1311868235.788257 depth/1311868235.788257.png +1311868235.811896 rgb/1311868235.811896.png 1311868235.825362 depth/1311868235.825362.png +1311868235.843663 rgb/1311868235.843663.png 1311868235.858308 depth/1311868235.858308.png +1311868235.879619 rgb/1311868235.879619.png 1311868235.888708 depth/1311868235.888708.png +1311868235.911551 rgb/1311868235.911551.png 1311868235.921561 depth/1311868235.921561.png +1311868235.943694 rgb/1311868235.943694.png 1311868235.956001 depth/1311868235.956001.png +1311868235.979648 rgb/1311868235.979648.png 1311868235.988034 depth/1311868235.988034.png +1311868236.011678 rgb/1311868236.011678.png 1311868236.025635 depth/1311868236.025635.png +1311868236.043684 rgb/1311868236.043684.png 1311868236.060014 depth/1311868236.060014.png +1311868236.079629 rgb/1311868236.079629.png 1311868236.088707 depth/1311868236.088707.png +1311868236.111800 rgb/1311868236.111800.png 1311868236.126979 depth/1311868236.126979.png +1311868236.143661 rgb/1311868236.143661.png 1311868236.161045 depth/1311868236.161045.png +1311868236.179561 rgb/1311868236.179561.png 1311868236.189928 depth/1311868236.189928.png +1311868236.211655 rgb/1311868236.211655.png 1311868236.224661 depth/1311868236.224661.png +1311868236.243642 rgb/1311868236.243642.png 1311868236.258926 depth/1311868236.258926.png +1311868236.279495 rgb/1311868236.279495.png 1311868236.287882 depth/1311868236.287882.png +1311868236.311580 rgb/1311868236.311580.png 1311868236.326498 depth/1311868236.326498.png +1311868236.343770 rgb/1311868236.343770.png 1311868236.354671 depth/1311868236.354671.png +1311868236.379539 rgb/1311868236.379539.png 1311868236.392383 depth/1311868236.392383.png +1311868236.412852 rgb/1311868236.412852.png 1311868236.424464 depth/1311868236.424464.png +1311868236.443514 rgb/1311868236.443514.png 1311868236.456467 depth/1311868236.456467.png +1311868236.479602 rgb/1311868236.479602.png 1311868236.492818 depth/1311868236.492818.png +1311868236.511583 rgb/1311868236.511583.png 1311868236.524614 depth/1311868236.524614.png +1311868236.543672 rgb/1311868236.543672.png 1311868236.559314 depth/1311868236.559314.png +1311868236.579656 rgb/1311868236.579656.png 1311868236.590405 depth/1311868236.590405.png +1311868236.611596 rgb/1311868236.611596.png 1311868236.624908 depth/1311868236.624908.png +1311868236.647654 rgb/1311868236.647654.png 1311868236.657752 depth/1311868236.657752.png +1311868236.679569 rgb/1311868236.679569.png 1311868236.690922 depth/1311868236.690922.png +1311868236.711710 rgb/1311868236.711710.png 1311868236.725385 depth/1311868236.725385.png +1311868236.747574 rgb/1311868236.747574.png 1311868236.757142 depth/1311868236.757142.png +1311868236.779605 rgb/1311868236.779605.png 1311868236.791103 depth/1311868236.791103.png +1311868236.811656 rgb/1311868236.811656.png 1311868236.828096 depth/1311868236.828096.png +1311868236.847644 rgb/1311868236.847644.png 1311868236.860331 depth/1311868236.860331.png +1311868236.879498 rgb/1311868236.879498.png 1311868236.892124 depth/1311868236.892124.png +1311868236.911822 rgb/1311868236.911822.png 1311868236.926204 depth/1311868236.926204.png +1311868236.947572 rgb/1311868236.947572.png 1311868236.957016 depth/1311868236.957016.png +1311868236.979635 rgb/1311868236.979635.png 1311868236.996099 depth/1311868236.996099.png +1311868237.011585 rgb/1311868237.011585.png 1311868237.026224 depth/1311868237.026224.png +1311868237.047783 rgb/1311868237.047783.png 1311868237.056067 depth/1311868237.056067.png +1311868237.079739 rgb/1311868237.079739.png 1311868237.098161 depth/1311868237.098161.png +1311868237.111617 rgb/1311868237.111617.png 1311868237.122381 depth/1311868237.122381.png +1311868237.147698 rgb/1311868237.147698.png 1311868237.156983 depth/1311868237.156983.png +1311868237.179506 rgb/1311868237.179506.png 1311868237.190662 depth/1311868237.190662.png +1311868237.211747 rgb/1311868237.211747.png 1311868237.226916 depth/1311868237.226916.png +1311868237.247704 rgb/1311868237.247704.png 1311868237.258394 depth/1311868237.258394.png +1311868237.279719 rgb/1311868237.279719.png 1311868237.295102 depth/1311868237.295102.png +1311868237.311685 rgb/1311868237.311685.png 1311868237.327288 depth/1311868237.327288.png +1311868237.347705 rgb/1311868237.347705.png 1311868237.359320 depth/1311868237.359320.png +1311868237.379984 rgb/1311868237.379984.png 1311868237.390722 depth/1311868237.390722.png +1311868237.411750 rgb/1311868237.411750.png 1311868237.424941 depth/1311868237.424941.png +1311868237.447678 rgb/1311868237.447678.png 1311868237.456755 depth/1311868237.456755.png +1311868237.479718 rgb/1311868237.479718.png 1311868237.492241 depth/1311868237.492241.png +1311868237.511663 rgb/1311868237.511663.png 1311868237.526821 depth/1311868237.526821.png +1311868237.547675 rgb/1311868237.547675.png 1311868237.557656 depth/1311868237.557656.png +1311868237.579714 rgb/1311868237.579714.png 1311868237.594326 depth/1311868237.594326.png +1311868237.611575 rgb/1311868237.611575.png 1311868237.623046 depth/1311868237.623046.png +1311868237.647688 rgb/1311868237.647688.png 1311868237.659855 depth/1311868237.659855.png +1311868237.679616 rgb/1311868237.679616.png 1311868237.693300 depth/1311868237.693300.png +1311868237.711933 rgb/1311868237.711933.png 1311868237.726827 depth/1311868237.726827.png +1311868237.747723 rgb/1311868237.747723.png 1311868237.763258 depth/1311868237.763258.png +1311868237.779615 rgb/1311868237.779615.png 1311868237.791001 depth/1311868237.791001.png +1311868237.811811 rgb/1311868237.811811.png 1311868237.826566 depth/1311868237.826566.png +1311868237.847748 rgb/1311868237.847748.png 1311868237.862605 depth/1311868237.862605.png +1311868237.879660 rgb/1311868237.879660.png 1311868237.891412 depth/1311868237.891412.png +1311868237.911846 rgb/1311868237.911846.png 1311868237.926276 depth/1311868237.926276.png +1311868237.947730 rgb/1311868237.947730.png 1311868237.961661 depth/1311868237.961661.png +1311868237.979641 rgb/1311868237.979641.png 1311868237.994909 depth/1311868237.994909.png +1311868238.011682 rgb/1311868238.011682.png 1311868238.021950 depth/1311868238.021950.png +1311868238.047724 rgb/1311868238.047724.png 1311868238.060620 depth/1311868238.060620.png +1311868238.079831 rgb/1311868238.079831.png 1311868238.093002 depth/1311868238.093002.png +1311868238.111670 rgb/1311868238.111670.png 1311868238.123324 depth/1311868238.123324.png +1311868238.147711 rgb/1311868238.147711.png 1311868238.160289 depth/1311868238.160289.png +1311868238.179768 rgb/1311868238.179768.png 1311868238.192548 depth/1311868238.192548.png +1311868238.211730 rgb/1311868238.211730.png 1311868238.224936 depth/1311868238.224936.png +1311868238.247769 rgb/1311868238.247769.png 1311868238.262497 depth/1311868238.262497.png +1311868238.279669 rgb/1311868238.279669.png 1311868238.291972 depth/1311868238.291972.png +1311868238.311749 rgb/1311868238.311749.png 1311868238.325272 depth/1311868238.325272.png +1311868238.347701 rgb/1311868238.347701.png 1311868238.363991 depth/1311868238.363991.png +1311868238.379617 rgb/1311868238.379617.png 1311868238.389787 depth/1311868238.389787.png +1311868238.411808 rgb/1311868238.411808.png 1311868238.425382 depth/1311868238.425382.png +1311868238.447579 rgb/1311868238.447579.png 1311868238.459693 depth/1311868238.459693.png +1311868238.479644 rgb/1311868238.479644.png 1311868238.491772 depth/1311868238.491772.png +1311868238.511638 rgb/1311868238.511638.png 1311868238.521638 depth/1311868238.521638.png +1311868238.547647 rgb/1311868238.547647.png 1311868238.560011 depth/1311868238.560011.png +1311868238.579703 rgb/1311868238.579703.png 1311868238.590363 depth/1311868238.590363.png +1311868238.611939 rgb/1311868238.611939.png 1311868238.623375 depth/1311868238.623375.png +1311868238.647718 rgb/1311868238.647718.png 1311868238.659595 depth/1311868238.659595.png +1311868238.679756 rgb/1311868238.679756.png 1311868238.691258 depth/1311868238.691258.png +1311868238.711811 rgb/1311868238.711811.png 1311868238.725761 depth/1311868238.725761.png +1311868238.747681 rgb/1311868238.747681.png 1311868238.758028 depth/1311868238.758028.png +1311868238.779734 rgb/1311868238.779734.png 1311868238.792777 depth/1311868238.792777.png +1311868238.811727 rgb/1311868238.811727.png 1311868238.822174 depth/1311868238.822174.png +1311868238.847715 rgb/1311868238.847715.png 1311868238.861426 depth/1311868238.861426.png +1311868238.879655 rgb/1311868238.879655.png 1311868238.891057 depth/1311868238.891057.png +1311868238.911768 rgb/1311868238.911768.png 1311868238.923426 depth/1311868238.923426.png +1311868238.947727 rgb/1311868238.947727.png 1311868238.960206 depth/1311868238.960206.png +1311868238.979698 rgb/1311868238.979698.png 1311868238.991958 depth/1311868238.991958.png +1311868239.011813 rgb/1311868239.011813.png 1311868239.026818 depth/1311868239.026818.png +1311868239.047859 rgb/1311868239.047859.png 1311868239.058701 depth/1311868239.058701.png +1311868239.079767 rgb/1311868239.079767.png 1311868239.091227 depth/1311868239.091227.png +1311868239.111923 rgb/1311868239.111923.png 1311868239.125133 depth/1311868239.125133.png +1311868239.147701 rgb/1311868239.147701.png 1311868239.161796 depth/1311868239.161796.png +1311868239.179952 rgb/1311868239.179952.png 1311868239.191238 depth/1311868239.191238.png +1311868239.211956 rgb/1311868239.211956.png 1311868239.227023 depth/1311868239.227023.png +1311868239.247740 rgb/1311868239.247740.png 1311868239.260889 depth/1311868239.260889.png +1311868239.279647 rgb/1311868239.279647.png 1311868239.289618 depth/1311868239.289618.png +1311868239.311701 rgb/1311868239.311701.png 1311868239.325948 depth/1311868239.325948.png +1311868239.347666 rgb/1311868239.347666.png 1311868239.359050 depth/1311868239.359050.png +1311868239.379722 rgb/1311868239.379722.png 1311868239.389867 depth/1311868239.389867.png +1311868239.411681 rgb/1311868239.411681.png 1311868239.425044 depth/1311868239.425044.png +1311868239.447769 rgb/1311868239.447769.png 1311868239.458929 depth/1311868239.458929.png +1311868239.479757 rgb/1311868239.479757.png 1311868239.490755 depth/1311868239.490755.png +1311868239.511807 rgb/1311868239.511807.png 1311868239.529646 depth/1311868239.529646.png +1311868239.547793 rgb/1311868239.547793.png 1311868239.558282 depth/1311868239.558282.png +1311868239.579832 rgb/1311868239.579832.png 1311868239.591313 depth/1311868239.591313.png +1311868239.611936 rgb/1311868239.611936.png 1311868239.625302 depth/1311868239.625302.png +1311868239.647799 rgb/1311868239.647799.png 1311868239.660758 depth/1311868239.660758.png +1311868239.679838 rgb/1311868239.679838.png 1311868239.689895 depth/1311868239.689895.png +1311868239.711814 rgb/1311868239.711814.png 1311868239.727318 depth/1311868239.727318.png +1311868239.747890 rgb/1311868239.747890.png 1311868239.760894 depth/1311868239.760894.png +1311868239.779802 rgb/1311868239.779802.png 1311868239.793392 depth/1311868239.793392.png +1311868239.811866 rgb/1311868239.811866.png 1311868239.826228 depth/1311868239.826228.png +1311868239.847692 rgb/1311868239.847692.png 1311868239.859950 depth/1311868239.859950.png +1311868239.879821 rgb/1311868239.879821.png 1311868239.892565 depth/1311868239.892565.png +1311868239.912048 rgb/1311868239.912048.png 1311868239.927517 depth/1311868239.927517.png +1311868239.947914 rgb/1311868239.947914.png 1311868239.961332 depth/1311868239.961332.png +1311868239.979870 rgb/1311868239.979870.png 1311868239.992583 depth/1311868239.992583.png +1311868240.012203 rgb/1311868240.012203.png 1311868240.030627 depth/1311868240.030627.png +1311868240.047963 rgb/1311868240.047963.png 1311868240.060019 depth/1311868240.060019.png +1311868240.079916 rgb/1311868240.079916.png 1311868240.092708 depth/1311868240.092708.png +1311868240.111831 rgb/1311868240.111831.png 1311868240.125948 depth/1311868240.125948.png +1311868240.147812 rgb/1311868240.147812.png 1311868240.159774 depth/1311868240.159774.png +1311868240.180037 rgb/1311868240.180037.png 1311868240.194947 depth/1311868240.194947.png +1311868240.211870 rgb/1311868240.211870.png 1311868240.228459 depth/1311868240.228459.png +1311868240.247823 rgb/1311868240.247823.png 1311868240.258951 depth/1311868240.258951.png +1311868240.279833 rgb/1311868240.279833.png 1311868240.293365 depth/1311868240.293365.png +1311868240.311899 rgb/1311868240.311899.png 1311868240.325864 depth/1311868240.325864.png +1311868240.347732 rgb/1311868240.347732.png 1311868240.357706 depth/1311868240.357706.png +1311868240.379758 rgb/1311868240.379758.png 1311868240.394263 depth/1311868240.394263.png +1311868240.412142 rgb/1311868240.412142.png 1311868240.427587 depth/1311868240.427587.png +1311868240.447900 rgb/1311868240.447900.png 1311868240.460674 depth/1311868240.460674.png +1311868240.480028 rgb/1311868240.480028.png 1311868240.496243 depth/1311868240.496243.png +1311868240.512225 rgb/1311868240.512225.png 1311868240.525348 depth/1311868240.525348.png +1311868240.547745 rgb/1311868240.547745.png 1311868240.559654 depth/1311868240.559654.png +1311868240.579717 rgb/1311868240.579717.png 1311868240.594851 depth/1311868240.594851.png +1311868240.611779 rgb/1311868240.611779.png 1311868240.626849 depth/1311868240.626849.png +1311868240.647892 rgb/1311868240.647892.png 1311868240.659999 depth/1311868240.659999.png +1311868240.679815 rgb/1311868240.679815.png 1311868240.694244 depth/1311868240.694244.png +1311868240.711873 rgb/1311868240.711873.png 1311868240.729530 depth/1311868240.729530.png +1311868240.748004 rgb/1311868240.748004.png 1311868240.759700 depth/1311868240.759700.png +1311868240.779858 rgb/1311868240.779858.png 1311868240.793847 depth/1311868240.793847.png +1311868240.811863 rgb/1311868240.811863.png 1311868240.826433 depth/1311868240.826433.png +1311868240.879754 rgb/1311868240.879754.png 1311868240.868050 depth/1311868240.868050.png +1311868240.911960 rgb/1311868240.911960.png 1311868240.926676 depth/1311868240.926676.png +1311868240.947862 rgb/1311868240.947862.png 1311868240.958642 depth/1311868240.958642.png +1311868240.980015 rgb/1311868240.980015.png 1311868240.996545 depth/1311868240.996545.png +1311868241.011989 rgb/1311868241.011989.png 1311868241.026135 depth/1311868241.026135.png +1311868241.047933 rgb/1311868241.047933.png 1311868241.061283 depth/1311868241.061283.png +1311868241.079985 rgb/1311868241.079985.png 1311868241.094743 depth/1311868241.094743.png +1311868241.111816 rgb/1311868241.111816.png 1311868241.126527 depth/1311868241.126527.png +1311868241.148015 rgb/1311868241.148015.png 1311868241.160868 depth/1311868241.160868.png +1311868241.179775 rgb/1311868241.179775.png 1311868241.195828 depth/1311868241.195828.png +1311868241.211864 rgb/1311868241.211864.png 1311868241.225637 depth/1311868241.225637.png +1311868241.247832 rgb/1311868241.247832.png 1311868241.260669 depth/1311868241.260669.png +1311868241.279951 rgb/1311868241.279951.png 1311868241.295619 depth/1311868241.295619.png +1311868241.311846 rgb/1311868241.311846.png 1311868241.327348 depth/1311868241.327348.png +1311868241.348159 rgb/1311868241.348159.png 1311868241.361428 depth/1311868241.361428.png +1311868241.379991 rgb/1311868241.379991.png 1311868241.394814 depth/1311868241.394814.png +1311868241.411927 rgb/1311868241.411927.png 1311868241.427858 depth/1311868241.427858.png +1311868241.447810 rgb/1311868241.447810.png 1311868241.462746 depth/1311868241.462746.png +1311868241.479924 rgb/1311868241.479924.png 1311868241.495494 depth/1311868241.495494.png +1311868241.512153 rgb/1311868241.512153.png 1311868241.528389 depth/1311868241.528389.png +1311868241.579911 rgb/1311868241.579911.png 1311868241.563938 depth/1311868241.563938.png +1311868241.611956 rgb/1311868241.611956.png 1311868241.627214 depth/1311868241.627214.png +1311868241.648036 rgb/1311868241.648036.png 1311868241.662749 depth/1311868241.662749.png +1311868241.679969 rgb/1311868241.679969.png 1311868241.694677 depth/1311868241.694677.png +1311868241.712640 rgb/1311868241.712640.png 1311868241.726612 depth/1311868241.726612.png +1311868241.747996 rgb/1311868241.747996.png 1311868241.762745 depth/1311868241.762745.png +1311868241.779865 rgb/1311868241.779865.png 1311868241.793970 depth/1311868241.793970.png +1311868241.811843 rgb/1311868241.811843.png 1311868241.825481 depth/1311868241.825481.png +1311868241.847976 rgb/1311868241.847976.png 1311868241.861957 depth/1311868241.861957.png +1311868241.879857 rgb/1311868241.879857.png 1311868241.893685 depth/1311868241.893685.png +1311868241.911969 rgb/1311868241.911969.png 1311868241.925761 depth/1311868241.925761.png +1311868241.947838 rgb/1311868241.947838.png 1311868241.962577 depth/1311868241.962577.png +1311868241.979902 rgb/1311868241.979902.png 1311868241.993950 depth/1311868241.993950.png +1311868242.011931 rgb/1311868242.011931.png 1311868242.028824 depth/1311868242.028824.png +1311868242.047949 rgb/1311868242.047949.png 1311868242.063442 depth/1311868242.063442.png +1311868242.080011 rgb/1311868242.080011.png 1311868242.096649 depth/1311868242.096649.png +1311868242.111944 rgb/1311868242.111944.png 1311868242.126174 depth/1311868242.126174.png +1311868242.147934 rgb/1311868242.147934.png 1311868242.162661 depth/1311868242.162661.png +1311868242.180028 rgb/1311868242.180028.png 1311868242.196561 depth/1311868242.196561.png +1311868242.212185 rgb/1311868242.212185.png 1311868242.226612 depth/1311868242.226612.png +1311868242.247919 rgb/1311868242.247919.png 1311868242.261886 depth/1311868242.261886.png +1311868242.279969 rgb/1311868242.279969.png 1311868242.294353 depth/1311868242.294353.png +1311868242.312146 rgb/1311868242.312146.png 1311868242.327605 depth/1311868242.327605.png +1311868242.347903 rgb/1311868242.347903.png 1311868242.362223 depth/1311868242.362223.png +1311868242.379943 rgb/1311868242.379943.png 1311868242.394235 depth/1311868242.394235.png +1311868242.412008 rgb/1311868242.412008.png 1311868242.427036 depth/1311868242.427036.png +1311868242.447942 rgb/1311868242.447942.png 1311868242.462353 depth/1311868242.462353.png +1311868242.479984 rgb/1311868242.479984.png 1311868242.493946 depth/1311868242.493946.png +1311868242.511969 rgb/1311868242.511969.png 1311868242.526615 depth/1311868242.526615.png +1311868242.580083 rgb/1311868242.580083.png 1311868242.566495 depth/1311868242.566495.png +1311868242.612269 rgb/1311868242.612269.png 1311868242.627472 depth/1311868242.627472.png +1311868242.679930 rgb/1311868242.679930.png 1311868242.667488 depth/1311868242.667488.png +1311868242.712253 rgb/1311868242.712253.png 1311868242.694130 depth/1311868242.694130.png +1311868242.747909 rgb/1311868242.747909.png 1311868242.732996 depth/1311868242.732996.png +1311868242.779977 rgb/1311868242.779977.png 1311868242.793489 depth/1311868242.793489.png +1311868242.847992 rgb/1311868242.847992.png 1311868242.863742 depth/1311868242.863742.png +1311868242.879888 rgb/1311868242.879888.png 1311868242.893625 depth/1311868242.893625.png +1311868242.912047 rgb/1311868242.912047.png 1311868242.931911 depth/1311868242.931911.png +1311868242.948092 rgb/1311868242.948092.png 1311868242.962237 depth/1311868242.962237.png +1311868243.012214 rgb/1311868243.012214.png 1311868242.999440 depth/1311868242.999440.png +1311868243.048093 rgb/1311868243.048093.png 1311868243.030267 depth/1311868243.030267.png +1311868243.079963 rgb/1311868243.079963.png 1311868243.065614 depth/1311868243.065614.png +1311868243.111904 rgb/1311868243.111904.png 1311868243.094622 depth/1311868243.094622.png +1311868243.148081 rgb/1311868243.148081.png 1311868243.131233 depth/1311868243.131233.png +1311868243.180098 rgb/1311868243.180098.png 1311868243.165261 depth/1311868243.165261.png +1311868243.211968 rgb/1311868243.211968.png 1311868243.195099 depth/1311868243.195099.png +1311868243.248114 rgb/1311868243.248114.png 1311868243.232137 depth/1311868243.232137.png +1311868243.280037 rgb/1311868243.280037.png 1311868243.267009 depth/1311868243.267009.png +1311868243.312010 rgb/1311868243.312010.png 1311868243.299211 depth/1311868243.299211.png +1311868243.348087 rgb/1311868243.348087.png 1311868243.363556 depth/1311868243.363556.png +1311868243.411942 rgb/1311868243.411942.png 1311868243.398679 depth/1311868243.398679.png +1311868243.448204 rgb/1311868243.448204.png 1311868243.433005 depth/1311868243.433005.png +1311868243.480135 rgb/1311868243.480135.png 1311868243.495035 depth/1311868243.495035.png +1311868243.548097 rgb/1311868243.548097.png 1311868243.532500 depth/1311868243.532500.png +1311868243.580031 rgb/1311868243.580031.png 1311868243.567513 depth/1311868243.567513.png +1311868243.611954 rgb/1311868243.611954.png 1311868243.593573 depth/1311868243.593573.png +1311868243.648052 rgb/1311868243.648052.png 1311868243.632824 depth/1311868243.632824.png +1311868243.680036 rgb/1311868243.680036.png 1311868243.668349 depth/1311868243.668349.png +1311868243.712048 rgb/1311868243.712048.png 1311868243.696565 depth/1311868243.696565.png +1311868243.747912 rgb/1311868243.747912.png 1311868243.732961 depth/1311868243.732961.png +1311868243.779970 rgb/1311868243.779970.png 1311868243.766757 depth/1311868243.766757.png +1311868243.811933 rgb/1311868243.811933.png 1311868243.795568 depth/1311868243.795568.png +1311868243.848171 rgb/1311868243.848171.png 1311868243.829790 depth/1311868243.829790.png +1311868243.880069 rgb/1311868243.880069.png 1311868243.866513 depth/1311868243.866513.png +1311868243.912060 rgb/1311868243.912060.png 1311868243.901901 depth/1311868243.901901.png +1311868243.948200 rgb/1311868243.948200.png 1311868243.929651 depth/1311868243.929651.png +1311868243.979984 rgb/1311868243.979984.png 1311868243.966068 depth/1311868243.966068.png +1311868244.012101 rgb/1311868244.012101.png 1311868243.997409 depth/1311868243.997409.png +1311868244.048067 rgb/1311868244.048067.png 1311868244.030514 depth/1311868244.030514.png +1311868244.080141 rgb/1311868244.080141.png 1311868244.066062 depth/1311868244.066062.png +1311868244.112211 rgb/1311868244.112211.png 1311868244.098434 depth/1311868244.098434.png +1311868244.148092 rgb/1311868244.148092.png 1311868244.162988 depth/1311868244.162988.png +1311868244.212047 rgb/1311868244.212047.png 1311868244.198839 depth/1311868244.198839.png +1311868244.248025 rgb/1311868244.248025.png 1311868244.262109 depth/1311868244.262109.png +1311868244.312192 rgb/1311868244.312192.png 1311868244.297550 depth/1311868244.297550.png +1311868244.348251 rgb/1311868244.348251.png 1311868244.330150 depth/1311868244.330150.png +1311868244.380022 rgb/1311868244.380022.png 1311868244.365236 depth/1311868244.365236.png +1311868244.412124 rgb/1311868244.412124.png 1311868244.398588 depth/1311868244.398588.png +1311868244.448220 rgb/1311868244.448220.png 1311868244.430616 depth/1311868244.430616.png +1311868244.480101 rgb/1311868244.480101.png 1311868244.465583 depth/1311868244.465583.png +1311868244.512251 rgb/1311868244.512251.png 1311868244.497460 depth/1311868244.497460.png +1311868244.548269 rgb/1311868244.548269.png 1311868244.530488 depth/1311868244.530488.png +1311868244.580149 rgb/1311868244.580149.png 1311868244.566405 depth/1311868244.566405.png +1311868244.612250 rgb/1311868244.612250.png 1311868244.598720 depth/1311868244.598720.png +1311868244.648157 rgb/1311868244.648157.png 1311868244.663355 depth/1311868244.663355.png +1311868244.712115 rgb/1311868244.712115.png 1311868244.701010 depth/1311868244.701010.png +1311868244.748285 rgb/1311868244.748285.png 1311868244.734571 depth/1311868244.734571.png +1311868244.780046 rgb/1311868244.780046.png 1311868244.767062 depth/1311868244.767062.png +1311868244.812104 rgb/1311868244.812104.png 1311868244.797579 depth/1311868244.797579.png +1311868244.848096 rgb/1311868244.848096.png 1311868244.833981 depth/1311868244.833981.png +1311868244.880436 rgb/1311868244.880436.png 1311868244.863194 depth/1311868244.863194.png +1311868244.912189 rgb/1311868244.912189.png 1311868244.899663 depth/1311868244.899663.png +1311868244.948056 rgb/1311868244.948056.png 1311868244.930652 depth/1311868244.930652.png +1311868244.980073 rgb/1311868244.980073.png 1311868244.966161 depth/1311868244.966161.png +1311868245.012295 rgb/1311868245.012295.png 1311868244.997817 depth/1311868244.997817.png +1311868245.048320 rgb/1311868245.048320.png 1311868245.030713 depth/1311868245.030713.png +1311868245.080152 rgb/1311868245.080152.png 1311868245.068230 depth/1311868245.068230.png +1311868245.112252 rgb/1311868245.112252.png 1311868245.100094 depth/1311868245.100094.png +1311868245.148152 rgb/1311868245.148152.png 1311868245.132550 depth/1311868245.132550.png +1311868245.179920 rgb/1311868245.179920.png 1311868245.168625 depth/1311868245.168625.png +1311868245.212180 rgb/1311868245.212180.png 1311868245.198748 depth/1311868245.198748.png +1311868245.248256 rgb/1311868245.248256.png 1311868245.230284 depth/1311868245.230284.png +1311868245.280237 rgb/1311868245.280237.png 1311868245.268076 depth/1311868245.268076.png +1311868245.312188 rgb/1311868245.312188.png 1311868245.297794 depth/1311868245.297794.png +1311868245.348205 rgb/1311868245.348205.png 1311868245.330195 depth/1311868245.330195.png +1311868245.380074 rgb/1311868245.380074.png 1311868245.368326 depth/1311868245.368326.png +1311868245.412242 rgb/1311868245.412242.png 1311868245.397655 depth/1311868245.397655.png +1311868245.448230 rgb/1311868245.448230.png 1311868245.433333 depth/1311868245.433333.png +1311868245.480081 rgb/1311868245.480081.png 1311868245.469521 depth/1311868245.469521.png +1311868245.512280 rgb/1311868245.512280.png 1311868245.499686 depth/1311868245.499686.png +1311868245.548216 rgb/1311868245.548216.png 1311868245.532317 depth/1311868245.532317.png +1311868245.580262 rgb/1311868245.580262.png 1311868245.569225 depth/1311868245.569225.png +1311868245.612262 rgb/1311868245.612262.png 1311868245.600933 depth/1311868245.600933.png +1311868245.648241 rgb/1311868245.648241.png 1311868245.632668 depth/1311868245.632668.png +1311868245.680250 rgb/1311868245.680250.png 1311868245.669122 depth/1311868245.669122.png +1311868245.716121 rgb/1311868245.716121.png 1311868245.702053 depth/1311868245.702053.png +1311868245.748208 rgb/1311868245.748208.png 1311868245.733429 depth/1311868245.733429.png +1311868245.780177 rgb/1311868245.780177.png 1311868245.769680 depth/1311868245.769680.png +1311868245.816257 rgb/1311868245.816257.png 1311868245.799797 depth/1311868245.799797.png +1311868245.848193 rgb/1311868245.848193.png 1311868245.835753 depth/1311868245.835753.png +1311868245.880182 rgb/1311868245.880182.png 1311868245.869256 depth/1311868245.869256.png +1311868245.916227 rgb/1311868245.916227.png 1311868245.898307 depth/1311868245.898307.png +1311868245.948179 rgb/1311868245.948179.png 1311868245.935377 depth/1311868245.935377.png +1311868245.980265 rgb/1311868245.980265.png 1311868245.965600 depth/1311868245.965600.png +1311868246.016098 rgb/1311868246.016098.png 1311868246.000465 depth/1311868246.000465.png +1311868246.048196 rgb/1311868246.048196.png 1311868246.032994 depth/1311868246.032994.png +1311868246.080289 rgb/1311868246.080289.png 1311868246.069608 depth/1311868246.069608.png +1311868246.116229 rgb/1311868246.116229.png 1311868246.098082 depth/1311868246.098082.png +1311868246.148198 rgb/1311868246.148198.png 1311868246.134697 depth/1311868246.134697.png +1311868246.180201 rgb/1311868246.180201.png 1311868246.168861 depth/1311868246.168861.png +1311868246.216086 rgb/1311868246.216086.png 1311868246.201654 depth/1311868246.201654.png +1311868246.248127 rgb/1311868246.248127.png 1311868246.232147 depth/1311868246.232147.png +1311868246.280157 rgb/1311868246.280157.png 1311868246.267610 depth/1311868246.267610.png +1311868246.316184 rgb/1311868246.316184.png 1311868246.299361 depth/1311868246.299361.png +1311868246.348101 rgb/1311868246.348101.png 1311868246.332354 depth/1311868246.332354.png +1311868246.380220 rgb/1311868246.380220.png 1311868246.369599 depth/1311868246.369599.png +1311868246.416139 rgb/1311868246.416139.png 1311868246.400571 depth/1311868246.400571.png +1311868246.448298 rgb/1311868246.448298.png 1311868246.437181 depth/1311868246.437181.png +1311868246.480362 rgb/1311868246.480362.png 1311868246.466561 depth/1311868246.466561.png +1311868246.516170 rgb/1311868246.516170.png 1311868246.500549 depth/1311868246.500549.png +1311868246.548357 rgb/1311868246.548357.png 1311868246.537414 depth/1311868246.537414.png +1311868246.580161 rgb/1311868246.580161.png 1311868246.567438 depth/1311868246.567438.png +1311868246.616068 rgb/1311868246.616068.png 1311868246.598763 depth/1311868246.598763.png +1311868246.648250 rgb/1311868246.648250.png 1311868246.634586 depth/1311868246.634586.png +1311868246.680335 rgb/1311868246.680335.png 1311868246.666996 depth/1311868246.666996.png +1311868246.716264 rgb/1311868246.716264.png 1311868246.700669 depth/1311868246.700669.png +1311868246.748855 rgb/1311868246.748855.png 1311868246.737587 depth/1311868246.737587.png +1311868246.780364 rgb/1311868246.780364.png 1311868246.769254 depth/1311868246.769254.png +1311868246.816180 rgb/1311868246.816180.png 1311868246.798114 depth/1311868246.798114.png +1311868246.848370 rgb/1311868246.848370.png 1311868246.837574 depth/1311868246.837574.png +1311868246.880261 rgb/1311868246.880261.png 1311868246.869140 depth/1311868246.869140.png +1311868246.916243 rgb/1311868246.916243.png 1311868246.899105 depth/1311868246.899105.png +1311868246.948199 rgb/1311868246.948199.png 1311868246.939224 depth/1311868246.939224.png +1311868246.980258 rgb/1311868246.980258.png 1311868246.965703 depth/1311868246.965703.png +1311868247.016214 rgb/1311868247.016214.png 1311868246.997807 depth/1311868246.997807.png +1311868247.048425 rgb/1311868247.048425.png 1311868247.038653 depth/1311868247.038653.png +1311868247.080182 rgb/1311868247.080182.png 1311868247.066828 depth/1311868247.066828.png +1311868247.116311 rgb/1311868247.116311.png 1311868247.099315 depth/1311868247.099315.png +1311868247.148430 rgb/1311868247.148430.png 1311868247.137293 depth/1311868247.137293.png +1311868247.180293 rgb/1311868247.180293.png 1311868247.168256 depth/1311868247.168256.png +1311868247.216432 rgb/1311868247.216432.png 1311868247.199154 depth/1311868247.199154.png +1311868247.248170 rgb/1311868247.248170.png 1311868247.234191 depth/1311868247.234191.png +1311868247.280345 rgb/1311868247.280345.png 1311868247.268034 depth/1311868247.268034.png +1311868247.316293 rgb/1311868247.316293.png 1311868247.301142 depth/1311868247.301142.png +1311868247.348285 rgb/1311868247.348285.png 1311868247.334618 depth/1311868247.334618.png +1311868247.380602 rgb/1311868247.380602.png 1311868247.368875 depth/1311868247.368875.png +1311868247.416268 rgb/1311868247.416268.png 1311868247.398608 depth/1311868247.398608.png +1311868247.448333 rgb/1311868247.448333.png 1311868247.437852 depth/1311868247.437852.png +1311868247.480433 rgb/1311868247.480433.png 1311868247.469227 depth/1311868247.469227.png +1311868247.516146 rgb/1311868247.516146.png 1311868247.499036 depth/1311868247.499036.png +1311868247.548460 rgb/1311868247.548460.png 1311868247.537336 depth/1311868247.537336.png +1311868247.580231 rgb/1311868247.580231.png 1311868247.570321 depth/1311868247.570321.png +1311868247.616424 rgb/1311868247.616424.png 1311868247.605218 depth/1311868247.605218.png +1311868247.648229 rgb/1311868247.648229.png 1311868247.637508 depth/1311868247.637508.png +1311868247.680389 rgb/1311868247.680389.png 1311868247.665759 depth/1311868247.665759.png +1311868247.716208 rgb/1311868247.716208.png 1311868247.703260 depth/1311868247.703260.png +1311868247.748343 rgb/1311868247.748343.png 1311868247.737791 depth/1311868247.737791.png +1311868247.780427 rgb/1311868247.780427.png 1311868247.769288 depth/1311868247.769288.png +1311868247.816205 rgb/1311868247.816205.png 1311868247.803052 depth/1311868247.803052.png +1311868247.848368 rgb/1311868247.848368.png 1311868247.837312 depth/1311868247.837312.png +1311868247.880235 rgb/1311868247.880235.png 1311868247.865912 depth/1311868247.865912.png +1311868247.916219 rgb/1311868247.916219.png 1311868247.902738 depth/1311868247.902738.png +1311868247.948167 rgb/1311868247.948167.png 1311868247.933774 depth/1311868247.933774.png +1311868247.980227 rgb/1311868247.980227.png 1311868247.965890 depth/1311868247.965890.png +1311868248.016215 rgb/1311868248.016215.png 1311868248.002931 depth/1311868248.002931.png +1311868248.048245 rgb/1311868248.048245.png 1311868248.034882 depth/1311868248.034882.png +1311868248.080326 rgb/1311868248.080326.png 1311868248.065902 depth/1311868248.065902.png +1311868248.116239 rgb/1311868248.116239.png 1311868248.102546 depth/1311868248.102546.png +1311868248.148302 rgb/1311868248.148302.png 1311868248.135080 depth/1311868248.135080.png +1311868248.180377 rgb/1311868248.180377.png 1311868248.166295 depth/1311868248.166295.png +1311868248.216356 rgb/1311868248.216356.png 1311868248.201776 depth/1311868248.201776.png +1311868248.248345 rgb/1311868248.248345.png 1311868248.239703 depth/1311868248.239703.png +1311868248.280257 rgb/1311868248.280257.png 1311868248.265695 depth/1311868248.265695.png +1311868248.316226 rgb/1311868248.316226.png 1311868248.301724 depth/1311868248.301724.png +1311868248.348315 rgb/1311868248.348315.png 1311868248.335023 depth/1311868248.335023.png +1311868248.380451 rgb/1311868248.380451.png 1311868248.367024 depth/1311868248.367024.png +1311868248.416340 rgb/1311868248.416340.png 1311868248.401736 depth/1311868248.401736.png +1311868248.448353 rgb/1311868248.448353.png 1311868248.434097 depth/1311868248.434097.png +1311868248.480364 rgb/1311868248.480364.png 1311868248.467522 depth/1311868248.467522.png +1311868248.516261 rgb/1311868248.516261.png 1311868248.503344 depth/1311868248.503344.png +1311868248.548298 rgb/1311868248.548298.png 1311868248.536471 depth/1311868248.536471.png +1311868248.580330 rgb/1311868248.580330.png 1311868248.566838 depth/1311868248.566838.png +1311868248.616364 rgb/1311868248.616364.png 1311868248.602761 depth/1311868248.602761.png +1311868248.648465 rgb/1311868248.648465.png 1311868248.634678 depth/1311868248.634678.png +1311868248.680356 rgb/1311868248.680356.png 1311868248.667205 depth/1311868248.667205.png +1311868248.716495 rgb/1311868248.716495.png 1311868248.702846 depth/1311868248.702846.png +1311868248.748482 rgb/1311868248.748482.png 1311868248.734052 depth/1311868248.734052.png +1311868248.780288 rgb/1311868248.780288.png 1311868248.766346 depth/1311868248.766346.png +1311868248.816469 rgb/1311868248.816469.png 1311868248.802354 depth/1311868248.802354.png +1311868248.848299 rgb/1311868248.848299.png 1311868248.837692 depth/1311868248.837692.png +1311868248.880380 rgb/1311868248.880380.png 1311868248.870600 depth/1311868248.870600.png +1311868248.916530 rgb/1311868248.916530.png 1311868248.907596 depth/1311868248.907596.png +1311868248.948257 rgb/1311868248.948257.png 1311868248.935123 depth/1311868248.935123.png +1311868248.980371 rgb/1311868248.980371.png 1311868248.972389 depth/1311868248.972389.png +1311868249.016517 rgb/1311868249.016517.png 1311868249.003866 depth/1311868249.003866.png +1311868249.048258 rgb/1311868249.048258.png 1311868249.033950 depth/1311868249.033950.png +1311868249.080657 rgb/1311868249.080657.png 1311868249.071928 depth/1311868249.071928.png +1311868249.116343 rgb/1311868249.116343.png 1311868249.102655 depth/1311868249.102655.png +1311868249.148549 rgb/1311868249.148549.png 1311868249.137507 depth/1311868249.137507.png +1311868249.180476 rgb/1311868249.180476.png 1311868249.169827 depth/1311868249.169827.png +1311868249.216410 rgb/1311868249.216410.png 1311868249.205621 depth/1311868249.205621.png +1311868249.248249 rgb/1311868249.248249.png 1311868249.234582 depth/1311868249.234582.png +1311868249.280715 rgb/1311868249.280715.png 1311868249.270200 depth/1311868249.270200.png +1311868249.316586 rgb/1311868249.316586.png 1311868249.302950 depth/1311868249.302950.png +1311868249.348357 rgb/1311868249.348357.png 1311868249.334354 depth/1311868249.334354.png +1311868249.380649 rgb/1311868249.380649.png 1311868249.369867 depth/1311868249.369867.png +1311868249.416459 rgb/1311868249.416459.png 1311868249.401709 depth/1311868249.401709.png +1311868249.448316 rgb/1311868249.448316.png 1311868249.435326 depth/1311868249.435326.png +1311868249.480373 rgb/1311868249.480373.png 1311868249.471210 depth/1311868249.471210.png +1311868249.516272 rgb/1311868249.516272.png 1311868249.503250 depth/1311868249.503250.png +1311868249.548294 rgb/1311868249.548294.png 1311868249.535792 depth/1311868249.535792.png +1311868249.580331 rgb/1311868249.580331.png 1311868249.569940 depth/1311868249.569940.png +1311868249.616312 rgb/1311868249.616312.png 1311868249.603120 depth/1311868249.603120.png +1311868249.648364 rgb/1311868249.648364.png 1311868249.633985 depth/1311868249.633985.png +1311868249.680685 rgb/1311868249.680685.png 1311868249.669894 depth/1311868249.669894.png +1311868249.716340 rgb/1311868249.716340.png 1311868249.701887 depth/1311868249.701887.png +1311868249.748334 rgb/1311868249.748334.png 1311868249.733888 depth/1311868249.733888.png +1311868249.780683 rgb/1311868249.780683.png 1311868249.770990 depth/1311868249.770990.png +1311868249.816620 rgb/1311868249.816620.png 1311868249.805210 depth/1311868249.805210.png +1311868249.848322 rgb/1311868249.848322.png 1311868249.834454 depth/1311868249.834454.png +1311868249.880507 rgb/1311868249.880507.png 1311868249.869851 depth/1311868249.869851.png +1311868249.916563 rgb/1311868249.916563.png 1311868249.901831 depth/1311868249.901831.png +1311868249.948306 rgb/1311868249.948306.png 1311868249.935668 depth/1311868249.935668.png +1311868249.980348 rgb/1311868249.980348.png 1311868249.971837 depth/1311868249.971837.png +1311868250.016358 rgb/1311868250.016358.png 1311868250.002150 depth/1311868250.002150.png +1311868250.048559 rgb/1311868250.048559.png 1311868250.034645 depth/1311868250.034645.png +1311868250.080466 rgb/1311868250.080466.png 1311868250.071665 depth/1311868250.071665.png +1311868250.116495 rgb/1311868250.116495.png 1311868250.103399 depth/1311868250.103399.png +1311868250.148589 rgb/1311868250.148589.png 1311868250.142995 depth/1311868250.142995.png +1311868250.180457 rgb/1311868250.180457.png 1311868250.171268 depth/1311868250.171268.png +1311868250.216361 rgb/1311868250.216361.png 1311868250.202986 depth/1311868250.202986.png +1311868250.248624 rgb/1311868250.248624.png 1311868250.241329 depth/1311868250.241329.png +1311868250.280374 rgb/1311868250.280374.png 1311868250.270874 depth/1311868250.270874.png +1311868250.316452 rgb/1311868250.316452.png 1311868250.306018 depth/1311868250.306018.png +1311868250.348963 rgb/1311868250.348963.png 1311868250.340082 depth/1311868250.340082.png +1311868250.380598 rgb/1311868250.380598.png 1311868250.370257 depth/1311868250.370257.png +1311868250.416431 rgb/1311868250.416431.png 1311868250.403761 depth/1311868250.403761.png +1311868250.448319 rgb/1311868250.448319.png 1311868250.438294 depth/1311868250.438294.png +1311868250.480450 rgb/1311868250.480450.png 1311868250.469889 depth/1311868250.469889.png +1311868250.516364 rgb/1311868250.516364.png 1311868250.502216 depth/1311868250.502216.png +1311868250.548715 rgb/1311868250.548715.png 1311868250.538123 depth/1311868250.538123.png +1311868250.580440 rgb/1311868250.580440.png 1311868250.571480 depth/1311868250.571480.png +1311868250.616408 rgb/1311868250.616408.png 1311868250.602134 depth/1311868250.602134.png +1311868250.648757 rgb/1311868250.648757.png 1311868250.637824 depth/1311868250.637824.png +1311868250.680503 rgb/1311868250.680503.png 1311868250.672483 depth/1311868250.672483.png +1311868250.716511 rgb/1311868250.716511.png 1311868250.703217 depth/1311868250.703217.png +1311868250.748430 rgb/1311868250.748430.png 1311868250.740204 depth/1311868250.740204.png +1311868250.780601 rgb/1311868250.780601.png 1311868250.770588 depth/1311868250.770588.png +1311868250.816420 rgb/1311868250.816420.png 1311868250.802296 depth/1311868250.802296.png +1311868250.848395 rgb/1311868250.848395.png 1311868250.838519 depth/1311868250.838519.png +1311868250.880463 rgb/1311868250.880463.png 1311868250.871167 depth/1311868250.871167.png +1311868250.916361 rgb/1311868250.916361.png 1311868250.902364 depth/1311868250.902364.png +1311868250.948745 rgb/1311868250.948745.png 1311868250.938035 depth/1311868250.938035.png +1311868250.980502 rgb/1311868250.980502.png 1311868250.970114 depth/1311868250.970114.png +1311868251.016390 rgb/1311868251.016390.png 1311868251.004302 depth/1311868251.004302.png +1311868251.048640 rgb/1311868251.048640.png 1311868251.039099 depth/1311868251.039099.png +1311868251.080543 rgb/1311868251.080543.png 1311868251.070062 depth/1311868251.070062.png +1311868251.116502 rgb/1311868251.116502.png 1311868251.102836 depth/1311868251.102836.png +1311868251.148411 rgb/1311868251.148411.png 1311868251.138815 depth/1311868251.138815.png +1311868251.180611 rgb/1311868251.180611.png 1311868251.171110 depth/1311868251.171110.png +1311868251.216444 rgb/1311868251.216444.png 1311868251.201988 depth/1311868251.201988.png +1311868251.248388 rgb/1311868251.248388.png 1311868251.238021 depth/1311868251.238021.png +1311868251.280411 rgb/1311868251.280411.png 1311868251.269877 depth/1311868251.269877.png +1311868251.316903 rgb/1311868251.316903.png 1311868251.307441 depth/1311868251.307441.png +1311868251.348494 rgb/1311868251.348494.png 1311868251.338709 depth/1311868251.338709.png +1311868251.380800 rgb/1311868251.380800.png 1311868251.371768 depth/1311868251.371768.png +1311868251.416874 rgb/1311868251.416874.png 1311868251.409690 depth/1311868251.409690.png +1311868251.448794 rgb/1311868251.448794.png 1311868251.442505 depth/1311868251.442505.png +1311868251.480572 rgb/1311868251.480572.png 1311868251.471430 depth/1311868251.471430.png +1311868251.516467 rgb/1311868251.516467.png 1311868251.506071 depth/1311868251.506071.png +1311868251.548661 rgb/1311868251.548661.png 1311868251.541665 depth/1311868251.541665.png +1311868251.580755 rgb/1311868251.580755.png 1311868251.573860 depth/1311868251.573860.png +1311868251.616591 rgb/1311868251.616591.png 1311868251.608834 depth/1311868251.608834.png +1311868251.649011 rgb/1311868251.649011.png 1311868251.642071 depth/1311868251.642071.png +1311868251.681056 rgb/1311868251.681056.png 1311868251.672750 depth/1311868251.672750.png +1311868251.716509 rgb/1311868251.716509.png 1311868251.706095 depth/1311868251.706095.png +1311868251.748667 rgb/1311868251.748667.png 1311868251.740405 depth/1311868251.740405.png +1311868251.780606 rgb/1311868251.780606.png 1311868251.770114 depth/1311868251.770114.png +1311868251.816706 rgb/1311868251.816706.png 1311868251.808202 depth/1311868251.808202.png +1311868251.848729 rgb/1311868251.848729.png 1311868251.843159 depth/1311868251.843159.png +1311868251.881180 rgb/1311868251.881180.png 1311868251.871734 depth/1311868251.871734.png +1311868251.916574 rgb/1311868251.916574.png 1311868251.907729 depth/1311868251.907729.png +1311868251.948786 rgb/1311868251.948786.png 1311868251.941716 depth/1311868251.941716.png +1311868251.980523 rgb/1311868251.980523.png 1311868251.972312 depth/1311868251.972312.png +1311868252.016633 rgb/1311868252.016633.png 1311868252.008720 depth/1311868252.008720.png +1311868252.048722 rgb/1311868252.048722.png 1311868252.042678 depth/1311868252.042678.png +1311868252.081141 rgb/1311868252.081141.png 1311868252.073898 depth/1311868252.073898.png +1311868252.116709 rgb/1311868252.116709.png 1311868252.108550 depth/1311868252.108550.png +1311868252.148733 rgb/1311868252.148733.png 1311868252.141590 depth/1311868252.141590.png +1311868252.180550 rgb/1311868252.180550.png 1311868252.171057 depth/1311868252.171057.png +1311868252.216665 rgb/1311868252.216665.png 1311868252.209444 depth/1311868252.209444.png +1311868252.249056 rgb/1311868252.249056.png 1311868252.243429 depth/1311868252.243429.png +1311868252.280693 rgb/1311868252.280693.png 1311868252.271730 depth/1311868252.271730.png +1311868252.316579 rgb/1311868252.316579.png 1311868252.309247 depth/1311868252.309247.png +1311868252.348634 rgb/1311868252.348634.png 1311868252.339215 depth/1311868252.339215.png +1311868252.380676 rgb/1311868252.380676.png 1311868252.373399 depth/1311868252.373399.png +1311868252.416673 rgb/1311868252.416673.png 1311868252.408545 depth/1311868252.408545.png +1311868252.448807 rgb/1311868252.448807.png 1311868252.443048 depth/1311868252.443048.png +1311868252.480598 rgb/1311868252.480598.png 1311868252.471397 depth/1311868252.471397.png +1311868252.516633 rgb/1311868252.516633.png 1311868252.507776 depth/1311868252.507776.png +1311868252.550037 rgb/1311868252.550037.png 1311868252.543394 depth/1311868252.543394.png +1311868252.580747 rgb/1311868252.580747.png 1311868252.575078 depth/1311868252.575078.png +1311868252.616626 rgb/1311868252.616626.png 1311868252.606712 depth/1311868252.606712.png +1311868252.649109 rgb/1311868252.649109.png 1311868252.640952 depth/1311868252.640952.png +1311868252.680706 rgb/1311868252.680706.png 1311868252.675892 depth/1311868252.675892.png +1311868252.716568 rgb/1311868252.716568.png 1311868252.706908 depth/1311868252.706908.png +1311868252.748687 rgb/1311868252.748687.png 1311868252.740004 depth/1311868252.740004.png +1311868252.780724 rgb/1311868252.780724.png 1311868252.774814 depth/1311868252.774814.png +1311868252.816693 rgb/1311868252.816693.png 1311868252.807295 depth/1311868252.807295.png +1311868252.848740 rgb/1311868252.848740.png 1311868252.841919 depth/1311868252.841919.png +1311868252.880663 rgb/1311868252.880663.png 1311868252.877430 depth/1311868252.877430.png +1311868252.916592 rgb/1311868252.916592.png 1311868252.906062 depth/1311868252.906062.png +1311868252.948689 rgb/1311868252.948689.png 1311868252.938457 depth/1311868252.938457.png +1311868252.980733 rgb/1311868252.980733.png 1311868252.977036 depth/1311868252.977036.png +1311868253.016742 rgb/1311868253.016742.png 1311868253.009329 depth/1311868253.009329.png +1311868253.048837 rgb/1311868253.048837.png 1311868253.041027 depth/1311868253.041027.png +1311868253.080812 rgb/1311868253.080812.png 1311868253.075229 depth/1311868253.075229.png +1311868253.116735 rgb/1311868253.116735.png 1311868253.109584 depth/1311868253.109584.png +1311868253.148796 rgb/1311868253.148796.png 1311868253.139324 depth/1311868253.139324.png +1311868253.181948 rgb/1311868253.181948.png 1311868253.177590 depth/1311868253.177590.png +1311868253.216569 rgb/1311868253.216569.png 1311868253.206544 depth/1311868253.206544.png +1311868253.248725 rgb/1311868253.248725.png 1311868253.238418 depth/1311868253.238418.png +1311868253.280713 rgb/1311868253.280713.png 1311868253.276220 depth/1311868253.276220.png +1311868253.316664 rgb/1311868253.316664.png 1311868253.306046 depth/1311868253.306046.png +1311868253.348831 rgb/1311868253.348831.png 1311868253.341767 depth/1311868253.341767.png +1311868253.381067 rgb/1311868253.381067.png 1311868253.378465 depth/1311868253.378465.png +1311868253.416763 rgb/1311868253.416763.png 1311868253.408530 depth/1311868253.408530.png +1311868253.448691 rgb/1311868253.448691.png 1311868253.440717 depth/1311868253.440717.png +1311868253.480853 rgb/1311868253.480853.png 1311868253.474540 depth/1311868253.474540.png +1311868253.516704 rgb/1311868253.516704.png 1311868253.508676 depth/1311868253.508676.png +1311868253.548549 rgb/1311868253.548549.png 1311868253.539781 depth/1311868253.539781.png +1311868253.581530 rgb/1311868253.581530.png 1311868253.576628 depth/1311868253.576628.png +1311868253.616743 rgb/1311868253.616743.png 1311868253.606357 depth/1311868253.606357.png +1311868253.648742 rgb/1311868253.648742.png 1311868253.638854 depth/1311868253.638854.png +1311868253.680645 rgb/1311868253.680645.png 1311868253.675346 depth/1311868253.675346.png +1311868253.716771 rgb/1311868253.716771.png 1311868253.706080 depth/1311868253.706080.png +1311868253.748837 rgb/1311868253.748837.png 1311868253.738308 depth/1311868253.738308.png +1311868253.780775 rgb/1311868253.780775.png 1311868253.774636 depth/1311868253.774636.png +1311868253.816654 rgb/1311868253.816654.png 1311868253.806191 depth/1311868253.806191.png +1311868253.848746 rgb/1311868253.848746.png 1311868253.845257 depth/1311868253.845257.png +1311868253.880980 rgb/1311868253.880980.png 1311868253.874264 depth/1311868253.874264.png +1311868253.916916 rgb/1311868253.916916.png 1311868253.907739 depth/1311868253.907739.png +1311868253.948752 rgb/1311868253.948752.png 1311868253.942162 depth/1311868253.942162.png +1311868253.980731 rgb/1311868253.980731.png 1311868253.977273 depth/1311868253.977273.png +1311868254.016718 rgb/1311868254.016718.png 1311868254.009005 depth/1311868254.009005.png +1311868254.049168 rgb/1311868254.049168.png 1311868254.049214 depth/1311868254.049214.png +1311868254.080850 rgb/1311868254.080850.png 1311868254.078460 depth/1311868254.078460.png +1311868254.116780 rgb/1311868254.116780.png 1311868254.106940 depth/1311868254.106940.png +1311868254.148648 rgb/1311868254.148648.png 1311868254.142043 depth/1311868254.142043.png +1311868254.180791 rgb/1311868254.180791.png 1311868254.177201 depth/1311868254.177201.png +1311868254.216747 rgb/1311868254.216747.png 1311868254.206278 depth/1311868254.206278.png +1311868254.248926 rgb/1311868254.248926.png 1311868254.245618 depth/1311868254.245618.png +1311868254.281235 rgb/1311868254.281235.png 1311868254.275142 depth/1311868254.275142.png +1311868254.316692 rgb/1311868254.316692.png 1311868254.306491 depth/1311868254.306491.png +1311868254.348771 rgb/1311868254.348771.png 1311868254.346697 depth/1311868254.346697.png +1311868254.380853 rgb/1311868254.380853.png 1311868254.375530 depth/1311868254.375530.png +1311868254.416896 rgb/1311868254.416896.png 1311868254.406292 depth/1311868254.406292.png +1311868254.448907 rgb/1311868254.448907.png 1311868254.445676 depth/1311868254.445676.png +1311868254.481183 rgb/1311868254.481183.png 1311868254.476974 depth/1311868254.476974.png +1311868254.516676 rgb/1311868254.516676.png 1311868254.507711 depth/1311868254.507711.png +1311868254.548867 rgb/1311868254.548867.png 1311868254.543991 depth/1311868254.543991.png +1311868254.580918 rgb/1311868254.580918.png 1311868254.577386 depth/1311868254.577386.png +1311868254.616771 rgb/1311868254.616771.png 1311868254.606685 depth/1311868254.606685.png +1311868254.648657 rgb/1311868254.648657.png 1311868254.647558 depth/1311868254.647558.png +1311868254.680858 rgb/1311868254.680858.png 1311868254.677930 depth/1311868254.677930.png +1311868254.716785 rgb/1311868254.716785.png 1311868254.707057 depth/1311868254.707057.png +1311868254.748845 rgb/1311868254.748845.png 1311868254.742368 depth/1311868254.742368.png +1311868254.784875 rgb/1311868254.784875.png 1311868254.777541 depth/1311868254.777541.png +1311868254.816878 rgb/1311868254.816878.png 1311868254.809838 depth/1311868254.809838.png +1311868254.848916 rgb/1311868254.848916.png 1311868254.844351 depth/1311868254.844351.png +1311868254.885176 rgb/1311868254.885176.png 1311868254.879181 depth/1311868254.879181.png +1311868254.916952 rgb/1311868254.916952.png 1311868254.910622 depth/1311868254.910622.png +1311868254.948966 rgb/1311868254.948966.png 1311868254.942354 depth/1311868254.942354.png +1311868254.984826 rgb/1311868254.984826.png 1311868254.980186 depth/1311868254.980186.png +1311868255.016920 rgb/1311868255.016920.png 1311868255.013136 depth/1311868255.013136.png +1311868255.049320 rgb/1311868255.049320.png 1311868255.044172 depth/1311868255.044172.png +1311868255.084997 rgb/1311868255.084997.png 1311868255.074563 depth/1311868255.074563.png +1311868255.116728 rgb/1311868255.116728.png 1311868255.113381 depth/1311868255.113381.png +1311868255.148803 rgb/1311868255.148803.png 1311868255.145550 depth/1311868255.145550.png +1311868255.185128 rgb/1311868255.185128.png 1311868255.174737 depth/1311868255.174737.png +1311868255.216885 rgb/1311868255.216885.png 1311868255.213189 depth/1311868255.213189.png +1311868255.248740 rgb/1311868255.248740.png 1311868255.242406 depth/1311868255.242406.png +1311868255.285013 rgb/1311868255.285013.png 1311868255.276545 depth/1311868255.276545.png +1311868255.316993 rgb/1311868255.316993.png 1311868255.313626 depth/1311868255.313626.png +1311868255.349004 rgb/1311868255.349004.png 1311868255.345527 depth/1311868255.345527.png +1311868255.384831 rgb/1311868255.384831.png 1311868255.374387 depth/1311868255.374387.png +1311868255.417465 rgb/1311868255.417465.png 1311868255.411752 depth/1311868255.411752.png +1311868255.448957 rgb/1311868255.448957.png 1311868255.445257 depth/1311868255.445257.png +1311868255.484846 rgb/1311868255.484846.png 1311868255.476682 depth/1311868255.476682.png +1311868255.517093 rgb/1311868255.517093.png 1311868255.512434 depth/1311868255.512434.png +1311868255.548944 rgb/1311868255.548944.png 1311868255.542336 depth/1311868255.542336.png +1311868255.585756 rgb/1311868255.585756.png 1311868255.578739 depth/1311868255.578739.png +1311868255.616865 rgb/1311868255.616865.png 1311868255.616229 depth/1311868255.616229.png +1311868255.649271 rgb/1311868255.649271.png 1311868255.646008 depth/1311868255.646008.png +1311868255.684941 rgb/1311868255.684941.png 1311868255.675734 depth/1311868255.675734.png +1311868255.716862 rgb/1311868255.716862.png 1311868255.714709 depth/1311868255.714709.png +1311868255.748794 rgb/1311868255.748794.png 1311868255.742472 depth/1311868255.742472.png +1311868255.784952 rgb/1311868255.784952.png 1311868255.776905 depth/1311868255.776905.png +1311868255.817549 rgb/1311868255.817549.png 1311868255.814553 depth/1311868255.814553.png +1311868255.848787 rgb/1311868255.848787.png 1311868255.843682 depth/1311868255.843682.png +1311868255.884951 rgb/1311868255.884951.png 1311868255.875647 depth/1311868255.875647.png +1311868255.916866 rgb/1311868255.916866.png 1311868255.913435 depth/1311868255.913435.png +1311868255.948865 rgb/1311868255.948865.png 1311868255.942450 depth/1311868255.942450.png +1311868255.984771 rgb/1311868255.984771.png 1311868255.974226 depth/1311868255.974226.png +1311868256.017528 rgb/1311868256.017528.png 1311868256.017537 depth/1311868256.017537.png +1311868256.048877 rgb/1311868256.048877.png 1311868256.044139 depth/1311868256.044139.png +1311868256.084847 rgb/1311868256.084847.png 1311868256.075533 depth/1311868256.075533.png +1311868256.117284 rgb/1311868256.117284.png 1311868256.113864 depth/1311868256.113864.png +1311868256.149657 rgb/1311868256.149657.png 1311868256.145094 depth/1311868256.145094.png +1311868256.184808 rgb/1311868256.184808.png 1311868256.174467 depth/1311868256.174467.png +1311868256.216920 rgb/1311868256.216920.png 1311868256.214231 depth/1311868256.214231.png +1311868256.248884 rgb/1311868256.248884.png 1311868256.244139 depth/1311868256.244139.png +1311868256.284837 rgb/1311868256.284837.png 1311868256.279573 depth/1311868256.279573.png +1311868256.316827 rgb/1311868256.316827.png 1311868256.312468 depth/1311868256.312468.png +1311868256.348901 rgb/1311868256.348901.png 1311868256.346601 depth/1311868256.346601.png +1311868256.385489 rgb/1311868256.385489.png 1311868256.380368 depth/1311868256.380368.png +1311868256.417708 rgb/1311868256.417708.png 1311868256.417723 depth/1311868256.417723.png +1311868256.448918 rgb/1311868256.448918.png 1311868256.444304 depth/1311868256.444304.png +1311868256.484903 rgb/1311868256.484903.png 1311868256.481461 depth/1311868256.481461.png +1311868256.517192 rgb/1311868256.517192.png 1311868256.513423 depth/1311868256.513423.png +1311868256.548816 rgb/1311868256.548816.png 1311868256.542631 depth/1311868256.542631.png +1311868256.584898 rgb/1311868256.584898.png 1311868256.578502 depth/1311868256.578502.png +1311868256.616929 rgb/1311868256.616929.png 1311868256.612858 depth/1311868256.612858.png +1311868256.649078 rgb/1311868256.649078.png 1311868256.643525 depth/1311868256.643525.png +1311868256.684944 rgb/1311868256.684944.png 1311868256.680977 depth/1311868256.680977.png +1311868256.717133 rgb/1311868256.717133.png 1311868256.715852 depth/1311868256.715852.png +1311868256.749056 rgb/1311868256.749056.png 1311868256.742686 depth/1311868256.742686.png +1311868256.785171 rgb/1311868256.785171.png 1311868256.781989 depth/1311868256.781989.png +1311868256.816832 rgb/1311868256.816832.png 1311868256.815457 depth/1311868256.815457.png +1311868256.848894 rgb/1311868256.848894.png 1311868256.843853 depth/1311868256.843853.png +1311868256.885027 rgb/1311868256.885027.png 1311868256.881870 depth/1311868256.881870.png +1311868256.916906 rgb/1311868256.916906.png 1311868256.910285 depth/1311868256.910285.png +1311868256.949184 rgb/1311868256.949184.png 1311868256.943253 depth/1311868256.943253.png +1311868256.984945 rgb/1311868256.984945.png 1311868256.979646 depth/1311868256.979646.png +1311868257.017144 rgb/1311868257.017144.png 1311868257.010623 depth/1311868257.010623.png +1311868257.049224 rgb/1311868257.049224.png 1311868257.046340 depth/1311868257.046340.png +1311868257.085190 rgb/1311868257.085190.png 1311868257.081240 depth/1311868257.081240.png +1311868257.116964 rgb/1311868257.116964.png 1311868257.110972 depth/1311868257.110972.png +1311868257.149165 rgb/1311868257.149165.png 1311868257.145087 depth/1311868257.145087.png +1311868257.184982 rgb/1311868257.184982.png 1311868257.182971 depth/1311868257.182971.png +1311868257.216830 rgb/1311868257.216830.png 1311868257.211776 depth/1311868257.211776.png +1311868257.248914 rgb/1311868257.248914.png 1311868257.244222 depth/1311868257.244222.png +1311868257.284925 rgb/1311868257.284925.png 1311868257.278283 depth/1311868257.278283.png +1311868257.317019 rgb/1311868257.317019.png 1311868257.311876 depth/1311868257.311876.png +1311868257.348967 rgb/1311868257.348967.png 1311868257.344870 depth/1311868257.344870.png +1311868257.384936 rgb/1311868257.384936.png 1311868257.378252 depth/1311868257.378252.png +1311868257.416835 rgb/1311868257.416835.png 1311868257.410362 depth/1311868257.410362.png +1311868257.449069 rgb/1311868257.449069.png 1311868257.445493 depth/1311868257.445493.png +1311868257.485023 rgb/1311868257.485023.png 1311868257.478276 depth/1311868257.478276.png +1311868257.516816 rgb/1311868257.516816.png 1311868257.510320 depth/1311868257.510320.png +1311868257.549492 rgb/1311868257.549492.png 1311868257.549508 depth/1311868257.549508.png +1311868257.585336 rgb/1311868257.585336.png 1311868257.580687 depth/1311868257.580687.png +1311868257.617970 rgb/1311868257.617970.png 1311868257.613445 depth/1311868257.613445.png +1311868257.649061 rgb/1311868257.649061.png 1311868257.649072 depth/1311868257.649072.png +1311868257.684916 rgb/1311868257.684916.png 1311868257.679183 depth/1311868257.679183.png +1311868257.717951 rgb/1311868257.717951.png 1311868257.713715 depth/1311868257.713715.png +1311868257.749626 rgb/1311868257.749626.png 1311868257.746865 depth/1311868257.746865.png +1311868257.785459 rgb/1311868257.785459.png 1311868257.780361 depth/1311868257.780361.png +1311868257.816852 rgb/1311868257.816852.png 1311868257.812435 depth/1311868257.812435.png +1311868257.849241 rgb/1311868257.849241.png 1311868257.848216 depth/1311868257.848216.png +1311868257.885261 rgb/1311868257.885261.png 1311868257.878977 depth/1311868257.878977.png +1311868257.917005 rgb/1311868257.917005.png 1311868257.910339 depth/1311868257.910339.png +1311868257.949031 rgb/1311868257.949031.png 1311868257.946098 depth/1311868257.946098.png +1311868257.985217 rgb/1311868257.985217.png 1311868257.981851 depth/1311868257.981851.png +1311868258.016837 rgb/1311868258.016837.png 1311868258.011809 depth/1311868258.011809.png +1311868258.048909 rgb/1311868258.048909.png 1311868258.047417 depth/1311868258.047417.png +1311868258.086178 rgb/1311868258.086178.png 1311868258.080461 depth/1311868258.080461.png +1311868258.117570 rgb/1311868258.117570.png 1311868258.112975 depth/1311868258.112975.png +1311868258.149278 rgb/1311868258.149278.png 1311868258.149289 depth/1311868258.149289.png +1311868258.185124 rgb/1311868258.185124.png 1311868258.178249 depth/1311868258.178249.png +1311868258.216937 rgb/1311868258.216937.png 1311868258.212794 depth/1311868258.212794.png +1311868258.251845 rgb/1311868258.251845.png 1311868258.251851 depth/1311868258.251851.png +1311868258.285207 rgb/1311868258.285207.png 1311868258.281239 depth/1311868258.281239.png +1311868258.317231 rgb/1311868258.317231.png 1311868258.310618 depth/1311868258.310618.png +1311868258.349077 rgb/1311868258.349077.png 1311868258.346583 depth/1311868258.346583.png +1311868258.384969 rgb/1311868258.384969.png 1311868258.378857 depth/1311868258.378857.png +1311868258.416975 rgb/1311868258.416975.png 1311868258.412501 depth/1311868258.412501.png +1311868258.449148 rgb/1311868258.449148.png 1311868258.446276 depth/1311868258.446276.png +1311868258.484910 rgb/1311868258.484910.png 1311868258.478853 depth/1311868258.478853.png +1311868258.517262 rgb/1311868258.517262.png 1311868258.511933 depth/1311868258.511933.png +1311868258.549307 rgb/1311868258.549307.png 1311868258.549314 depth/1311868258.549314.png +1311868258.585124 rgb/1311868258.585124.png 1311868258.579437 depth/1311868258.579437.png +1311868258.616904 rgb/1311868258.616904.png 1311868258.610780 depth/1311868258.610780.png +1311868258.648890 rgb/1311868258.648890.png 1311868258.647483 depth/1311868258.647483.png +1311868258.685108 rgb/1311868258.685108.png 1311868258.680659 depth/1311868258.680659.png +1311868258.716929 rgb/1311868258.716929.png 1311868258.714945 depth/1311868258.714945.png +1311868258.749015 rgb/1311868258.749015.png 1311868258.746669 depth/1311868258.746669.png +1311868258.785039 rgb/1311868258.785039.png 1311868258.778477 depth/1311868258.778477.png +1311868258.817013 rgb/1311868258.817013.png 1311868258.817027 depth/1311868258.817027.png +1311868258.848932 rgb/1311868258.848932.png 1311868258.848121 depth/1311868258.848121.png +1311868258.885648 rgb/1311868258.885648.png 1311868258.880629 depth/1311868258.880629.png +1311868258.917705 rgb/1311868258.917705.png 1311868258.917712 depth/1311868258.917712.png +1311868258.949852 rgb/1311868258.949852.png 1311868258.952816 depth/1311868258.952816.png +1311868258.985070 rgb/1311868258.985070.png 1311868258.979187 depth/1311868258.979187.png +1311868259.017026 rgb/1311868259.017026.png 1311868259.015276 depth/1311868259.015276.png +1311868259.048922 rgb/1311868259.048922.png 1311868259.046173 depth/1311868259.046173.png +1311868259.085232 rgb/1311868259.085232.png 1311868259.078286 depth/1311868259.078286.png +1311868259.116919 rgb/1311868259.116919.png 1311868259.116291 depth/1311868259.116291.png +1311868259.149197 rgb/1311868259.149197.png 1311868259.146207 depth/1311868259.146207.png +1311868259.185707 rgb/1311868259.185707.png 1311868259.179623 depth/1311868259.179623.png +1311868259.216979 rgb/1311868259.216979.png 1311868259.215477 depth/1311868259.215477.png +1311868259.248996 rgb/1311868259.248996.png 1311868259.249045 depth/1311868259.249045.png +1311868259.285039 rgb/1311868259.285039.png 1311868259.278157 depth/1311868259.278157.png +1311868259.316960 rgb/1311868259.316960.png 1311868259.316647 depth/1311868259.316647.png +1311868259.350162 rgb/1311868259.350162.png 1311868259.347717 depth/1311868259.347717.png +1311868259.385116 rgb/1311868259.385116.png 1311868259.378293 depth/1311868259.378293.png +1311868259.417128 rgb/1311868259.417128.png 1311868259.414464 depth/1311868259.414464.png +1311868259.449140 rgb/1311868259.449140.png 1311868259.446253 depth/1311868259.446253.png +1311868259.485201 rgb/1311868259.485201.png 1311868259.478144 depth/1311868259.478144.png +1311868259.517235 rgb/1311868259.517235.png 1311868259.515800 depth/1311868259.515800.png +1311868259.549524 rgb/1311868259.549524.png 1311868259.546344 depth/1311868259.546344.png +1311868259.585081 rgb/1311868259.585081.png 1311868259.578929 depth/1311868259.578929.png +1311868259.617127 rgb/1311868259.617127.png 1311868259.614250 depth/1311868259.614250.png +1311868259.649289 rgb/1311868259.649289.png 1311868259.649301 depth/1311868259.649301.png +1311868259.685014 rgb/1311868259.685014.png 1311868259.678658 depth/1311868259.678658.png +1311868259.717139 rgb/1311868259.717139.png 1311868259.714458 depth/1311868259.714458.png +1311868259.749049 rgb/1311868259.749049.png 1311868259.746178 depth/1311868259.746178.png +1311868259.785037 rgb/1311868259.785037.png 1311868259.778932 depth/1311868259.778932.png +1311868259.818043 rgb/1311868259.818043.png 1311868259.818056 depth/1311868259.818056.png +1311868259.849187 rgb/1311868259.849187.png 1311868259.846243 depth/1311868259.846243.png +1311868259.885215 rgb/1311868259.885215.png 1311868259.878572 depth/1311868259.878572.png +1311868259.917493 rgb/1311868259.917493.png 1311868259.917515 depth/1311868259.917515.png +1311868259.949104 rgb/1311868259.949104.png 1311868259.946174 depth/1311868259.946174.png +1311868259.984972 rgb/1311868259.984972.png 1311868259.983338 depth/1311868259.983338.png +1311868260.017107 rgb/1311868260.017107.png 1311868260.014161 depth/1311868260.014161.png +1311868260.049125 rgb/1311868260.049125.png 1311868260.048211 depth/1311868260.048211.png +1311868260.085277 rgb/1311868260.085277.png 1311868260.082184 depth/1311868260.082184.png +1311868260.116985 rgb/1311868260.116985.png 1311868260.114743 depth/1311868260.114743.png +1311868260.149117 rgb/1311868260.149117.png 1311868260.146239 depth/1311868260.146239.png +1311868260.184916 rgb/1311868260.184916.png 1311868260.183834 depth/1311868260.183834.png +1311868260.217009 rgb/1311868260.217009.png 1311868260.214450 depth/1311868260.214450.png +1311868260.249110 rgb/1311868260.249110.png 1311868260.246542 depth/1311868260.246542.png +1311868260.285037 rgb/1311868260.285037.png 1311868260.284135 depth/1311868260.284135.png +1311868260.317238 rgb/1311868260.317238.png 1311868260.315778 depth/1311868260.315778.png +1311868260.349210 rgb/1311868260.349210.png 1311868260.346391 depth/1311868260.346391.png +1311868260.385901 rgb/1311868260.385901.png 1311868260.385908 depth/1311868260.385908.png +1311868260.417177 rgb/1311868260.417177.png 1311868260.414797 depth/1311868260.414797.png +1311868260.449188 rgb/1311868260.449188.png 1311868260.446575 depth/1311868260.446575.png +1311868260.485105 rgb/1311868260.485105.png 1311868260.482440 depth/1311868260.482440.png +1311868260.517155 rgb/1311868260.517155.png 1311868260.514754 depth/1311868260.514754.png +1311868260.549278 rgb/1311868260.549278.png 1311868260.546370 depth/1311868260.546370.png +1311868260.588498 rgb/1311868260.588498.png 1311868260.588507 depth/1311868260.588507.png +1311868260.617023 rgb/1311868260.617023.png 1311868260.615833 depth/1311868260.615833.png +1311868260.649220 rgb/1311868260.649220.png 1311868260.646588 depth/1311868260.646588.png +1311868260.685161 rgb/1311868260.685161.png 1311868260.682811 depth/1311868260.682811.png +1311868260.717031 rgb/1311868260.717031.png 1311868260.715415 depth/1311868260.715415.png +1311868260.749052 rgb/1311868260.749052.png 1311868260.746446 depth/1311868260.746446.png +1311868260.785032 rgb/1311868260.785032.png 1311868260.783695 depth/1311868260.783695.png +1311868260.817354 rgb/1311868260.817354.png 1311868260.815058 depth/1311868260.815058.png +1311868260.849412 rgb/1311868260.849412.png 1311868260.846558 depth/1311868260.846558.png +1311868260.885138 rgb/1311868260.885138.png 1311868260.882914 depth/1311868260.882914.png +1311868260.917044 rgb/1311868260.917044.png 1311868260.914428 depth/1311868260.914428.png +1311868260.949176 rgb/1311868260.949176.png 1311868260.946230 depth/1311868260.946230.png +1311868260.985735 rgb/1311868260.985735.png 1311868260.982386 depth/1311868260.982386.png +1311868261.017109 rgb/1311868261.017109.png 1311868261.014265 depth/1311868261.014265.png +1311868261.049410 rgb/1311868261.049410.png 1311868261.046223 depth/1311868261.046223.png +1311868261.085064 rgb/1311868261.085064.png 1311868261.082974 depth/1311868261.082974.png +1311868261.117521 rgb/1311868261.117521.png 1311868261.114432 depth/1311868261.114432.png +1311868261.149243 rgb/1311868261.149243.png 1311868261.146208 depth/1311868261.146208.png +1311868261.185057 rgb/1311868261.185057.png 1311868261.182814 depth/1311868261.182814.png +1311868261.217343 rgb/1311868261.217343.png 1311868261.214895 depth/1311868261.214895.png +1311868261.250674 rgb/1311868261.250674.png 1311868261.250688 depth/1311868261.250688.png +1311868261.285209 rgb/1311868261.285209.png 1311868261.282599 depth/1311868261.282599.png +1311868261.317339 rgb/1311868261.317339.png 1311868261.315052 depth/1311868261.315052.png +1311868261.350547 rgb/1311868261.350547.png 1311868261.350587 depth/1311868261.350587.png +1311868261.385162 rgb/1311868261.385162.png 1311868261.383099 depth/1311868261.383099.png +1311868261.417214 rgb/1311868261.417214.png 1311868261.414396 depth/1311868261.414396.png +1311868261.450926 rgb/1311868261.450926.png 1311868261.451520 depth/1311868261.451520.png +1311868261.485265 rgb/1311868261.485265.png 1311868261.485277 depth/1311868261.485277.png +1311868261.517293 rgb/1311868261.517293.png 1311868261.515046 depth/1311868261.515046.png +1311868261.553565 rgb/1311868261.553565.png 1311868261.553583 depth/1311868261.553583.png +1311868261.586338 rgb/1311868261.586338.png 1311868261.586519 depth/1311868261.586519.png +1311868261.617239 rgb/1311868261.617239.png 1311868261.614699 depth/1311868261.614699.png +1311868261.654121 rgb/1311868261.654121.png 1311868261.654137 depth/1311868261.654137.png +1311868261.685195 rgb/1311868261.685195.png 1311868261.684839 depth/1311868261.684839.png +1311868261.719495 rgb/1311868261.719495.png 1311868261.719540 depth/1311868261.719540.png +1311868261.751682 rgb/1311868261.751682.png 1311868261.751691 depth/1311868261.751691.png +1311868261.787133 rgb/1311868261.787133.png 1311868261.787339 depth/1311868261.787339.png +1311868261.817195 rgb/1311868261.817195.png 1311868261.815089 depth/1311868261.815089.png +1311868261.853032 rgb/1311868261.853032.png 1311868261.853042 depth/1311868261.853042.png +1311868261.885094 rgb/1311868261.885094.png 1311868261.884022 depth/1311868261.884022.png +1311868261.917121 rgb/1311868261.917121.png 1311868261.916925 depth/1311868261.916925.png +1311868261.953503 rgb/1311868261.953503.png 1311868261.957504 depth/1311868261.957504.png +1311868261.985273 rgb/1311868261.985273.png 1311868261.982533 depth/1311868261.982533.png +1311868262.018018 rgb/1311868262.018018.png 1311868262.014541 depth/1311868262.014541.png +1311868262.053615 rgb/1311868262.053615.png 1311868262.053641 depth/1311868262.053641.png +1311868262.085382 rgb/1311868262.085382.png 1311868262.082463 depth/1311868262.082463.png +1311868262.117887 rgb/1311868262.117887.png 1311868262.117904 depth/1311868262.117904.png +1311868262.150528 rgb/1311868262.150528.png 1311868262.150538 depth/1311868262.150538.png +1311868262.185453 rgb/1311868262.185453.png 1311868262.185471 depth/1311868262.185471.png +1311868262.217304 rgb/1311868262.217304.png 1311868262.214323 depth/1311868262.214323.png +1311868262.253167 rgb/1311868262.253167.png 1311868262.253178 depth/1311868262.253178.png +1311868262.287398 rgb/1311868262.287398.png 1311868262.287414 depth/1311868262.287414.png +1311868262.317336 rgb/1311868262.317336.png 1311868262.315421 depth/1311868262.315421.png +1311868262.351121 rgb/1311868262.351121.png 1311868262.351149 depth/1311868262.351149.png +1311868262.386061 rgb/1311868262.386061.png 1311868262.386104 depth/1311868262.386104.png +1311868262.419248 rgb/1311868262.419248.png 1311868262.419289 depth/1311868262.419289.png +1311868262.453041 rgb/1311868262.453041.png 1311868262.453084 depth/1311868262.453084.png +1311868262.485168 rgb/1311868262.485168.png 1311868262.483233 depth/1311868262.483233.png +1311868262.521495 rgb/1311868262.521495.png 1311868262.521526 depth/1311868262.521526.png +1311868262.550967 rgb/1311868262.550967.png 1311868262.550977 depth/1311868262.550977.png +1311868262.585111 rgb/1311868262.585111.png 1311868262.583605 depth/1311868262.583605.png +1311868262.621668 rgb/1311868262.621668.png 1311868262.621716 depth/1311868262.621716.png +1311868262.650784 rgb/1311868262.650784.png 1311868262.650793 depth/1311868262.650793.png +1311868262.685330 rgb/1311868262.685330.png 1311868262.682453 depth/1311868262.682453.png +1311868262.721190 rgb/1311868262.721190.png 1311868262.721201 depth/1311868262.721201.png +1311868262.750486 rgb/1311868262.750486.png 1311868262.750492 depth/1311868262.750492.png +1311868262.785224 rgb/1311868262.785224.png 1311868262.783129 depth/1311868262.783129.png +1311868262.821620 rgb/1311868262.821620.png 1311868262.821651 depth/1311868262.821651.png +1311868262.850602 rgb/1311868262.850602.png 1311868262.850608 depth/1311868262.850608.png +1311868262.885337 rgb/1311868262.885337.png 1311868262.884225 depth/1311868262.884225.png +1311868262.922678 rgb/1311868262.922678.png 1311868262.922686 depth/1311868262.922686.png +1311868262.950706 rgb/1311868262.950706.png 1311868262.950713 depth/1311868262.950713.png +1311868262.985587 rgb/1311868262.985587.png 1311868262.985630 depth/1311868262.985630.png +1311868263.020693 rgb/1311868263.020693.png 1311868263.020700 depth/1311868263.020700.png +1311868263.053350 rgb/1311868263.053350.png 1311868263.053360 depth/1311868263.053360.png +1311868263.085224 rgb/1311868263.085224.png 1311868263.082803 depth/1311868263.082803.png +1311868263.121396 rgb/1311868263.121396.png 1311868263.121413 depth/1311868263.121413.png +1311868263.154334 rgb/1311868263.154334.png 1311868263.154346 depth/1311868263.154346.png +1311868263.185529 rgb/1311868263.185529.png 1311868263.184152 depth/1311868263.184152.png diff --git a/Examples/RGB-D/associations/fr2_xyz.txt b/Examples/RGB-D/associations/fr2_xyz.txt new file mode 100644 index 0000000000..71ea21434a --- /dev/null +++ b/Examples/RGB-D/associations/fr2_xyz.txt @@ -0,0 +1,3615 @@ +1311867170.462290 rgb/1311867170.462290.png 1311867170.450076 depth/1311867170.450076.png +1311867170.494139 rgb/1311867170.494139.png 1311867170.483500 depth/1311867170.483500.png +1311867170.526429 rgb/1311867170.526429.png 1311867170.516818 depth/1311867170.516818.png +1311867170.562349 rgb/1311867170.562349.png 1311867170.551384 depth/1311867170.551384.png +1311867170.594217 rgb/1311867170.594217.png 1311867170.580990 depth/1311867170.580990.png +1311867170.626087 rgb/1311867170.626087.png 1311867170.617942 depth/1311867170.617942.png +1311867170.662140 rgb/1311867170.662140.png 1311867170.649674 depth/1311867170.649674.png +1311867170.694205 rgb/1311867170.694205.png 1311867170.680532 depth/1311867170.680532.png +1311867170.726388 rgb/1311867170.726388.png 1311867170.717358 depth/1311867170.717358.png +1311867170.762019 rgb/1311867170.762019.png 1311867170.749451 depth/1311867170.749451.png +1311867170.794192 rgb/1311867170.794192.png 1311867170.780364 depth/1311867170.780364.png +1311867170.826282 rgb/1311867170.826282.png 1311867170.816535 depth/1311867170.816535.png +1311867170.862221 rgb/1311867170.862221.png 1311867170.850616 depth/1311867170.850616.png +1311867170.894378 rgb/1311867170.894378.png 1311867170.882672 depth/1311867170.882672.png +1311867170.926352 rgb/1311867170.926352.png 1311867170.917264 depth/1311867170.917264.png +1311867170.962147 rgb/1311867170.962147.png 1311867170.949643 depth/1311867170.949643.png +1311867170.994263 rgb/1311867170.994263.png 1311867170.986197 depth/1311867170.986197.png +1311867171.026274 rgb/1311867171.026274.png 1311867171.019831 depth/1311867171.019831.png +1311867171.062352 rgb/1311867171.062352.png 1311867171.052592 depth/1311867171.052592.png +1311867171.094235 rgb/1311867171.094235.png 1311867171.084303 depth/1311867171.084303.png +1311867171.126251 rgb/1311867171.126251.png 1311867171.116865 depth/1311867171.116865.png +1311867171.162247 rgb/1311867171.162247.png 1311867171.150265 depth/1311867171.150265.png +1311867171.194269 rgb/1311867171.194269.png 1311867171.188157 depth/1311867171.188157.png +1311867171.226253 rgb/1311867171.226253.png 1311867171.215808 depth/1311867171.215808.png +1311867171.262244 rgb/1311867171.262244.png 1311867171.250755 depth/1311867171.250755.png +1311867171.294341 rgb/1311867171.294341.png 1311867171.288603 depth/1311867171.288603.png +1311867171.326387 rgb/1311867171.326387.png 1311867171.320387 depth/1311867171.320387.png +1311867171.362246 rgb/1311867171.362246.png 1311867171.348416 depth/1311867171.348416.png +1311867171.394143 rgb/1311867171.394143.png 1311867171.386411 depth/1311867171.386411.png +1311867171.426288 rgb/1311867171.426288.png 1311867171.418257 depth/1311867171.418257.png +1311867171.462244 rgb/1311867171.462244.png 1311867171.450724 depth/1311867171.450724.png +1311867171.494404 rgb/1311867171.494404.png 1311867171.485965 depth/1311867171.485965.png +1311867171.526178 rgb/1311867171.526178.png 1311867171.516537 depth/1311867171.516537.png +1311867171.562297 rgb/1311867171.562297.png 1311867171.552054 depth/1311867171.552054.png +1311867171.594293 rgb/1311867171.594293.png 1311867171.587078 depth/1311867171.587078.png +1311867171.626340 rgb/1311867171.626340.png 1311867171.619828 depth/1311867171.619828.png +1311867171.662256 rgb/1311867171.662256.png 1311867171.651108 depth/1311867171.651108.png +1311867171.694344 rgb/1311867171.694344.png 1311867171.685447 depth/1311867171.685447.png +1311867171.726244 rgb/1311867171.726244.png 1311867171.716495 depth/1311867171.716495.png +1311867171.762119 rgb/1311867171.762119.png 1311867171.752030 depth/1311867171.752030.png +1311867171.794171 rgb/1311867171.794171.png 1311867171.787543 depth/1311867171.787543.png +1311867171.826255 rgb/1311867171.826255.png 1311867171.816493 depth/1311867171.816493.png +1311867171.862359 rgb/1311867171.862359.png 1311867171.852528 depth/1311867171.852528.png +1311867171.894443 rgb/1311867171.894443.png 1311867171.887719 depth/1311867171.887719.png +1311867171.926222 rgb/1311867171.926222.png 1311867171.916475 depth/1311867171.916475.png +1311867171.962467 rgb/1311867171.962467.png 1311867171.951952 depth/1311867171.951952.png +1311867171.994671 rgb/1311867171.994671.png 1311867171.988074 depth/1311867171.988074.png +1311867172.026268 rgb/1311867172.026268.png 1311867172.016436 depth/1311867172.016436.png +1311867172.062288 rgb/1311867172.062288.png 1311867172.049438 depth/1311867172.049438.png +1311867172.094196 rgb/1311867172.094196.png 1311867172.088132 depth/1311867172.088132.png +1311867172.126369 rgb/1311867172.126369.png 1311867172.117248 depth/1311867172.117248.png +1311867172.162335 rgb/1311867172.162335.png 1311867172.152282 depth/1311867172.152282.png +1311867172.194427 rgb/1311867172.194427.png 1311867172.188469 depth/1311867172.188469.png +1311867172.226441 rgb/1311867172.226441.png 1311867172.219929 depth/1311867172.219929.png +1311867172.262228 rgb/1311867172.262228.png 1311867172.252969 depth/1311867172.252969.png +1311867172.294483 rgb/1311867172.294483.png 1311867172.286931 depth/1311867172.286931.png +1311867172.326338 rgb/1311867172.326338.png 1311867172.318507 depth/1311867172.318507.png +1311867172.362401 rgb/1311867172.362401.png 1311867172.355461 depth/1311867172.355461.png +1311867172.394289 rgb/1311867172.394289.png 1311867172.387297 depth/1311867172.387297.png +1311867172.426522 rgb/1311867172.426522.png 1311867172.417192 depth/1311867172.417192.png +1311867172.462350 rgb/1311867172.462350.png 1311867172.455419 depth/1311867172.455419.png +1311867172.495267 rgb/1311867172.495267.png 1311867172.487872 depth/1311867172.487872.png +1311867172.526306 rgb/1311867172.526306.png 1311867172.517723 depth/1311867172.517723.png +1311867172.562493 rgb/1311867172.562493.png 1311867172.556634 depth/1311867172.556634.png +1311867172.594544 rgb/1311867172.594544.png 1311867172.589554 depth/1311867172.589554.png +1311867172.626370 rgb/1311867172.626370.png 1311867172.618563 depth/1311867172.618563.png +1311867172.662442 rgb/1311867172.662442.png 1311867172.652198 depth/1311867172.652198.png +1311867172.694545 rgb/1311867172.694545.png 1311867172.686797 depth/1311867172.686797.png +1311867172.726393 rgb/1311867172.726393.png 1311867172.716473 depth/1311867172.716473.png +1311867172.762374 rgb/1311867172.762374.png 1311867172.755581 depth/1311867172.755581.png +1311867172.794451 rgb/1311867172.794451.png 1311867172.784603 depth/1311867172.784603.png +1311867172.826309 rgb/1311867172.826309.png 1311867172.819640 depth/1311867172.819640.png +1311867172.863231 rgb/1311867172.863231.png 1311867172.856187 depth/1311867172.856187.png +1311867172.894465 rgb/1311867172.894465.png 1311867172.888261 depth/1311867172.888261.png +1311867172.926322 rgb/1311867172.926322.png 1311867172.920135 depth/1311867172.920135.png +1311867172.962331 rgb/1311867172.962331.png 1311867172.955319 depth/1311867172.955319.png +1311867172.994527 rgb/1311867172.994527.png 1311867172.987530 depth/1311867172.987530.png +1311867173.026263 rgb/1311867173.026263.png 1311867173.016636 depth/1311867173.016636.png +1311867173.062463 rgb/1311867173.062463.png 1311867173.055015 depth/1311867173.055015.png +1311867173.094518 rgb/1311867173.094518.png 1311867173.085411 depth/1311867173.085411.png +1311867173.126782 rgb/1311867173.126782.png 1311867173.118688 depth/1311867173.118688.png +1311867173.162231 rgb/1311867173.162231.png 1311867173.152903 depth/1311867173.152903.png +1311867173.194301 rgb/1311867173.194301.png 1311867173.186066 depth/1311867173.186066.png +1311867173.226445 rgb/1311867173.226445.png 1311867173.217457 depth/1311867173.217457.png +1311867173.262202 rgb/1311867173.262202.png 1311867173.252384 depth/1311867173.252384.png +1311867173.294268 rgb/1311867173.294268.png 1311867173.286128 depth/1311867173.286128.png +1311867173.326288 rgb/1311867173.326288.png 1311867173.316543 depth/1311867173.316543.png +1311867173.362328 rgb/1311867173.362328.png 1311867173.355753 depth/1311867173.355753.png +1311867173.394287 rgb/1311867173.394287.png 1311867173.384413 depth/1311867173.384413.png +1311867173.426279 rgb/1311867173.426279.png 1311867173.416714 depth/1311867173.416714.png +1311867173.462290 rgb/1311867173.462290.png 1311867173.455557 depth/1311867173.455557.png +1311867173.494339 rgb/1311867173.494339.png 1311867173.484349 depth/1311867173.484349.png +1311867173.526390 rgb/1311867173.526390.png 1311867173.521797 depth/1311867173.521797.png +1311867173.562437 rgb/1311867173.562437.png 1311867173.552167 depth/1311867173.552167.png +1311867173.594311 rgb/1311867173.594311.png 1311867173.584281 depth/1311867173.584281.png +1311867173.626396 rgb/1311867173.626396.png 1311867173.622125 depth/1311867173.622125.png +1311867173.662330 rgb/1311867173.662330.png 1311867173.652630 depth/1311867173.652630.png +1311867173.694354 rgb/1311867173.694354.png 1311867173.686190 depth/1311867173.686190.png +1311867173.726797 rgb/1311867173.726797.png 1311867173.721725 depth/1311867173.721725.png +1311867173.762397 rgb/1311867173.762397.png 1311867173.756464 depth/1311867173.756464.png +1311867173.794356 rgb/1311867173.794356.png 1311867173.785162 depth/1311867173.785162.png +1311867173.826567 rgb/1311867173.826567.png 1311867173.821195 depth/1311867173.821195.png +1311867173.863580 rgb/1311867173.863580.png 1311867173.852567 depth/1311867173.852567.png +1311867173.894608 rgb/1311867173.894608.png 1311867173.884587 depth/1311867173.884587.png +1311867173.926697 rgb/1311867173.926697.png 1311867173.921914 depth/1311867173.921914.png +1311867173.962546 rgb/1311867173.962546.png 1311867173.953686 depth/1311867173.953686.png +1311867173.994431 rgb/1311867173.994431.png 1311867173.989219 depth/1311867173.989219.png +1311867174.026426 rgb/1311867174.026426.png 1311867174.024019 depth/1311867174.024019.png +1311867174.062463 rgb/1311867174.062463.png 1311867174.054183 depth/1311867174.054183.png +1311867174.094519 rgb/1311867174.094519.png 1311867174.086830 depth/1311867174.086830.png +1311867174.126454 rgb/1311867174.126454.png 1311867174.124495 depth/1311867174.124495.png +1311867174.162433 rgb/1311867174.162433.png 1311867174.155288 depth/1311867174.155288.png +1311867174.194398 rgb/1311867174.194398.png 1311867174.184582 depth/1311867174.184582.png +1311867174.226758 rgb/1311867174.226758.png 1311867174.220459 depth/1311867174.220459.png +1311867174.262677 rgb/1311867174.262677.png 1311867174.252364 depth/1311867174.252364.png +1311867174.294528 rgb/1311867174.294528.png 1311867174.285999 depth/1311867174.285999.png +1311867174.326574 rgb/1311867174.326574.png 1311867174.323248 depth/1311867174.323248.png +1311867174.362433 rgb/1311867174.362433.png 1311867174.354525 depth/1311867174.354525.png +1311867174.394636 rgb/1311867174.394636.png 1311867174.385575 depth/1311867174.385575.png +1311867174.426679 rgb/1311867174.426679.png 1311867174.420747 depth/1311867174.420747.png +1311867174.463016 rgb/1311867174.463016.png 1311867174.456817 depth/1311867174.456817.png +1311867174.494567 rgb/1311867174.494567.png 1311867174.484843 depth/1311867174.484843.png +1311867174.526752 rgb/1311867174.526752.png 1311867174.523854 depth/1311867174.523854.png +1311867174.562350 rgb/1311867174.562350.png 1311867174.552584 depth/1311867174.552584.png +1311867174.594488 rgb/1311867174.594488.png 1311867174.587453 depth/1311867174.587453.png +1311867174.626546 rgb/1311867174.626546.png 1311867174.620460 depth/1311867174.620460.png +1311867174.662491 rgb/1311867174.662491.png 1311867174.657131 depth/1311867174.657131.png +1311867174.694591 rgb/1311867174.694591.png 1311867174.689552 depth/1311867174.689552.png +1311867174.726563 rgb/1311867174.726563.png 1311867174.720531 depth/1311867174.720531.png +1311867174.762376 rgb/1311867174.762376.png 1311867174.755617 depth/1311867174.755617.png +1311867174.794474 rgb/1311867174.794474.png 1311867174.791669 depth/1311867174.791669.png +1311867174.827330 rgb/1311867174.827330.png 1311867174.827340 depth/1311867174.827340.png +1311867174.862423 rgb/1311867174.862423.png 1311867174.852853 depth/1311867174.852853.png +1311867174.894420 rgb/1311867174.894420.png 1311867174.892876 depth/1311867174.892876.png +1311867174.926975 rgb/1311867174.926975.png 1311867174.927018 depth/1311867174.927018.png +1311867174.962643 rgb/1311867174.962643.png 1311867174.954480 depth/1311867174.954480.png +1311867174.994335 rgb/1311867174.994335.png 1311867174.993193 depth/1311867174.993193.png +1311867175.026551 rgb/1311867175.026551.png 1311867175.020706 depth/1311867175.020706.png +1311867175.063312 rgb/1311867175.063312.png 1311867175.057641 depth/1311867175.057641.png +1311867175.094719 rgb/1311867175.094719.png 1311867175.091331 depth/1311867175.091331.png +1311867175.126531 rgb/1311867175.126531.png 1311867175.120766 depth/1311867175.120766.png +1311867175.162518 rgb/1311867175.162518.png 1311867175.156149 depth/1311867175.156149.png +1311867175.194640 rgb/1311867175.194640.png 1311867175.188878 depth/1311867175.188878.png +1311867175.227005 rgb/1311867175.227005.png 1311867175.220693 depth/1311867175.220693.png +1311867175.262467 rgb/1311867175.262467.png 1311867175.252815 depth/1311867175.252815.png +1311867175.294451 rgb/1311867175.294451.png 1311867175.289629 depth/1311867175.289629.png +1311867175.326706 rgb/1311867175.326706.png 1311867175.323775 depth/1311867175.323775.png +1311867175.362565 rgb/1311867175.362565.png 1311867175.353647 depth/1311867175.353647.png +1311867175.394599 rgb/1311867175.394599.png 1311867175.388820 depth/1311867175.388820.png +1311867175.426606 rgb/1311867175.426606.png 1311867175.423375 depth/1311867175.423375.png +1311867175.462600 rgb/1311867175.462600.png 1311867175.454628 depth/1311867175.454628.png +1311867175.494573 rgb/1311867175.494573.png 1311867175.488524 depth/1311867175.488524.png +1311867175.526427 rgb/1311867175.526427.png 1311867175.520404 depth/1311867175.520404.png +1311867175.562570 rgb/1311867175.562570.png 1311867175.555278 depth/1311867175.555278.png +1311867175.594664 rgb/1311867175.594664.png 1311867175.588623 depth/1311867175.588623.png +1311867175.626480 rgb/1311867175.626480.png 1311867175.622267 depth/1311867175.622267.png +1311867175.662493 rgb/1311867175.662493.png 1311867175.652465 depth/1311867175.652465.png +1311867175.694700 rgb/1311867175.694700.png 1311867175.691635 depth/1311867175.691635.png +1311867175.727312 rgb/1311867175.727312.png 1311867175.720574 depth/1311867175.720574.png +1311867175.762497 rgb/1311867175.762497.png 1311867175.752846 depth/1311867175.752846.png +1311867175.794862 rgb/1311867175.794862.png 1311867175.788225 depth/1311867175.788225.png +1311867175.828797 rgb/1311867175.828797.png 1311867175.822546 depth/1311867175.822546.png +1311867175.862552 rgb/1311867175.862552.png 1311867175.852791 depth/1311867175.852791.png +1311867175.894608 rgb/1311867175.894608.png 1311867175.888452 depth/1311867175.888452.png +1311867175.928243 rgb/1311867175.928243.png 1311867175.922221 depth/1311867175.922221.png +1311867175.962937 rgb/1311867175.962937.png 1311867175.956655 depth/1311867175.956655.png +1311867175.998300 rgb/1311867175.998300.png 1311867175.988251 depth/1311867175.988251.png +1311867176.026851 rgb/1311867176.026851.png 1311867176.022409 depth/1311867176.022409.png +1311867176.062706 rgb/1311867176.062706.png 1311867176.057742 depth/1311867176.057742.png +1311867176.094660 rgb/1311867176.094660.png 1311867176.089212 depth/1311867176.089212.png +1311867176.126812 rgb/1311867176.126812.png 1311867176.123317 depth/1311867176.123317.png +1311867176.162590 rgb/1311867176.162590.png 1311867176.156464 depth/1311867176.156464.png +1311867176.194692 rgb/1311867176.194692.png 1311867176.188489 depth/1311867176.188489.png +1311867176.226536 rgb/1311867176.226536.png 1311867176.220801 depth/1311867176.220801.png +1311867176.262502 rgb/1311867176.262502.png 1311867176.256432 depth/1311867176.256432.png +1311867176.294611 rgb/1311867176.294611.png 1311867176.289298 depth/1311867176.289298.png +1311867176.326602 rgb/1311867176.326602.png 1311867176.320323 depth/1311867176.320323.png +1311867176.362456 rgb/1311867176.362456.png 1311867176.356783 depth/1311867176.356783.png +1311867176.395244 rgb/1311867176.395244.png 1311867176.389335 depth/1311867176.389335.png +1311867176.426836 rgb/1311867176.426836.png 1311867176.421363 depth/1311867176.421363.png +1311867176.462966 rgb/1311867176.462966.png 1311867176.456687 depth/1311867176.456687.png +1311867176.494581 rgb/1311867176.494581.png 1311867176.488951 depth/1311867176.488951.png +1311867176.526621 rgb/1311867176.526621.png 1311867176.521537 depth/1311867176.521537.png +1311867176.563639 rgb/1311867176.563639.png 1311867176.558631 depth/1311867176.558631.png +1311867176.594609 rgb/1311867176.594609.png 1311867176.593559 depth/1311867176.593559.png +1311867176.628384 rgb/1311867176.628384.png 1311867176.621080 depth/1311867176.621080.png +1311867176.662578 rgb/1311867176.662578.png 1311867176.660404 depth/1311867176.660404.png +1311867176.694518 rgb/1311867176.694518.png 1311867176.689453 depth/1311867176.689453.png +1311867176.726589 rgb/1311867176.726589.png 1311867176.724143 depth/1311867176.724143.png +1311867176.763233 rgb/1311867176.763233.png 1311867176.758500 depth/1311867176.758500.png +1311867176.794768 rgb/1311867176.794768.png 1311867176.790063 depth/1311867176.790063.png +1311867176.826677 rgb/1311867176.826677.png 1311867176.820696 depth/1311867176.820696.png +1311867176.862731 rgb/1311867176.862731.png 1311867176.858590 depth/1311867176.858590.png +1311867176.894955 rgb/1311867176.894955.png 1311867176.890342 depth/1311867176.890342.png +1311867176.926818 rgb/1311867176.926818.png 1311867176.922599 depth/1311867176.922599.png +1311867176.965061 rgb/1311867176.965061.png 1311867176.960668 depth/1311867176.960668.png +1311867176.994748 rgb/1311867176.994748.png 1311867176.989703 depth/1311867176.989703.png +1311867177.026728 rgb/1311867177.026728.png 1311867177.020601 depth/1311867177.020601.png +1311867177.062634 rgb/1311867177.062634.png 1311867177.056330 depth/1311867177.056330.png +1311867177.094685 rgb/1311867177.094685.png 1311867177.090969 depth/1311867177.090969.png +1311867177.126615 rgb/1311867177.126615.png 1311867177.122005 depth/1311867177.122005.png +1311867177.162730 rgb/1311867177.162730.png 1311867177.157538 depth/1311867177.157538.png +1311867177.194646 rgb/1311867177.194646.png 1311867177.188556 depth/1311867177.188556.png +1311867177.226473 rgb/1311867177.226473.png 1311867177.226035 depth/1311867177.226035.png +1311867177.263864 rgb/1311867177.263864.png 1311867177.258123 depth/1311867177.258123.png +1311867177.294618 rgb/1311867177.294618.png 1311867177.289343 depth/1311867177.289343.png +1311867177.327609 rgb/1311867177.327609.png 1311867177.324415 depth/1311867177.324415.png +1311867177.362771 rgb/1311867177.362771.png 1311867177.356930 depth/1311867177.356930.png +1311867177.394609 rgb/1311867177.394609.png 1311867177.389075 depth/1311867177.389075.png +1311867177.426748 rgb/1311867177.426748.png 1311867177.431286 depth/1311867177.431286.png +1311867177.462604 rgb/1311867177.462604.png 1311867177.458323 depth/1311867177.458323.png +1311867177.494643 rgb/1311867177.494643.png 1311867177.489115 depth/1311867177.489115.png +1311867177.527617 rgb/1311867177.527617.png 1311867177.527632 depth/1311867177.527632.png +1311867177.562640 rgb/1311867177.562640.png 1311867177.556823 depth/1311867177.556823.png +1311867177.594731 rgb/1311867177.594731.png 1311867177.588870 depth/1311867177.588870.png +1311867177.631145 rgb/1311867177.631145.png 1311867177.624638 depth/1311867177.624638.png +1311867177.662483 rgb/1311867177.662483.png 1311867177.656627 depth/1311867177.656627.png +1311867177.694561 rgb/1311867177.694561.png 1311867177.688761 depth/1311867177.688761.png +1311867177.730584 rgb/1311867177.730584.png 1311867177.724609 depth/1311867177.724609.png +1311867177.762538 rgb/1311867177.762538.png 1311867177.756593 depth/1311867177.756593.png +1311867177.794559 rgb/1311867177.794559.png 1311867177.788810 depth/1311867177.788810.png +1311867177.830915 rgb/1311867177.830915.png 1311867177.827577 depth/1311867177.827577.png +1311867177.862532 rgb/1311867177.862532.png 1311867177.856268 depth/1311867177.856268.png +1311867177.894692 rgb/1311867177.894692.png 1311867177.888928 depth/1311867177.888928.png +1311867177.931786 rgb/1311867177.931786.png 1311867177.926179 depth/1311867177.926179.png +1311867177.962791 rgb/1311867177.962791.png 1311867177.956891 depth/1311867177.956891.png +1311867177.994777 rgb/1311867177.994777.png 1311867177.989128 depth/1311867177.989128.png +1311867178.030610 rgb/1311867178.030610.png 1311867178.025481 depth/1311867178.025481.png +1311867178.063448 rgb/1311867178.063448.png 1311867178.058077 depth/1311867178.058077.png +1311867178.095114 rgb/1311867178.095114.png 1311867178.089617 depth/1311867178.089617.png +1311867178.130791 rgb/1311867178.130791.png 1311867178.127721 depth/1311867178.127721.png +1311867178.162747 rgb/1311867178.162747.png 1311867178.157550 depth/1311867178.157550.png +1311867178.195046 rgb/1311867178.195046.png 1311867178.192727 depth/1311867178.192727.png +1311867178.230719 rgb/1311867178.230719.png 1311867178.224296 depth/1311867178.224296.png +1311867178.262894 rgb/1311867178.262894.png 1311867178.256639 depth/1311867178.256639.png +1311867178.295490 rgb/1311867178.295490.png 1311867178.288842 depth/1311867178.288842.png +1311867178.330667 rgb/1311867178.330667.png 1311867178.324664 depth/1311867178.324664.png +1311867178.362723 rgb/1311867178.362723.png 1311867178.360490 depth/1311867178.360490.png +1311867178.394944 rgb/1311867178.394944.png 1311867178.388795 depth/1311867178.388795.png +1311867178.430658 rgb/1311867178.430658.png 1311867178.427504 depth/1311867178.427504.png +1311867178.462874 rgb/1311867178.462874.png 1311867178.456833 depth/1311867178.456833.png +1311867178.494644 rgb/1311867178.494644.png 1311867178.493591 depth/1311867178.493591.png +1311867178.530627 rgb/1311867178.530627.png 1311867178.524720 depth/1311867178.524720.png +1311867178.562642 rgb/1311867178.562642.png 1311867178.556910 depth/1311867178.556910.png +1311867178.594700 rgb/1311867178.594700.png 1311867178.593205 depth/1311867178.593205.png +1311867178.630690 rgb/1311867178.630690.png 1311867178.627593 depth/1311867178.627593.png +1311867178.662641 rgb/1311867178.662641.png 1311867178.660756 depth/1311867178.660756.png +1311867178.694612 rgb/1311867178.694612.png 1311867178.693715 depth/1311867178.693715.png +1311867178.730745 rgb/1311867178.730745.png 1311867178.724521 depth/1311867178.724521.png +1311867178.763235 rgb/1311867178.763235.png 1311867178.757396 depth/1311867178.757396.png +1311867178.800680 rgb/1311867178.800680.png 1311867178.799313 depth/1311867178.799313.png +1311867178.830950 rgb/1311867178.830950.png 1311867178.824972 depth/1311867178.824972.png +1311867178.862794 rgb/1311867178.862794.png 1311867178.857434 depth/1311867178.857434.png +1311867178.895017 rgb/1311867178.895017.png 1311867178.895228 depth/1311867178.895228.png +1311867178.930621 rgb/1311867178.930621.png 1311867178.925076 depth/1311867178.925076.png +1311867178.962761 rgb/1311867178.962761.png 1311867178.958688 depth/1311867178.958688.png +1311867178.994683 rgb/1311867178.994683.png 1311867178.993422 depth/1311867178.993422.png +1311867179.030916 rgb/1311867179.030916.png 1311867179.026970 depth/1311867179.026970.png +1311867179.062812 rgb/1311867179.062812.png 1311867179.057601 depth/1311867179.057601.png +1311867179.096812 rgb/1311867179.096812.png 1311867179.096820 depth/1311867179.096820.png +1311867179.131037 rgb/1311867179.131037.png 1311867179.124823 depth/1311867179.124823.png +1311867179.162754 rgb/1311867179.162754.png 1311867179.156587 depth/1311867179.156587.png +1311867179.195685 rgb/1311867179.195685.png 1311867179.195701 depth/1311867179.195701.png +1311867179.230747 rgb/1311867179.230747.png 1311867179.224644 depth/1311867179.224644.png +1311867179.263461 rgb/1311867179.263461.png 1311867179.257244 depth/1311867179.257244.png +1311867179.295920 rgb/1311867179.295920.png 1311867179.295933 depth/1311867179.295933.png +1311867179.330715 rgb/1311867179.330715.png 1311867179.327496 depth/1311867179.327496.png +1311867179.362930 rgb/1311867179.362930.png 1311867179.356659 depth/1311867179.356659.png +1311867179.394849 rgb/1311867179.394849.png 1311867179.393013 depth/1311867179.393013.png +1311867179.430804 rgb/1311867179.430804.png 1311867179.428452 depth/1311867179.428452.png +1311867179.463746 rgb/1311867179.463746.png 1311867179.458555 depth/1311867179.458555.png +1311867179.494947 rgb/1311867179.494947.png 1311867179.492659 depth/1311867179.492659.png +1311867179.530780 rgb/1311867179.530780.png 1311867179.524514 depth/1311867179.524514.png +1311867179.562761 rgb/1311867179.562761.png 1311867179.556366 depth/1311867179.556366.png +1311867179.594674 rgb/1311867179.594674.png 1311867179.593206 depth/1311867179.593206.png +1311867179.630690 rgb/1311867179.630690.png 1311867179.624449 depth/1311867179.624449.png +1311867179.662575 rgb/1311867179.662575.png 1311867179.661662 depth/1311867179.661662.png +1311867179.694605 rgb/1311867179.694605.png 1311867179.694458 depth/1311867179.694458.png +1311867179.730947 rgb/1311867179.730947.png 1311867179.724734 depth/1311867179.724734.png +1311867179.762727 rgb/1311867179.762727.png 1311867179.761284 depth/1311867179.761284.png +1311867179.794891 rgb/1311867179.794891.png 1311867179.792803 depth/1311867179.792803.png +1311867179.830753 rgb/1311867179.830753.png 1311867179.824885 depth/1311867179.824885.png +1311867179.862798 rgb/1311867179.862798.png 1311867179.861218 depth/1311867179.861218.png +1311867179.894804 rgb/1311867179.894804.png 1311867179.892712 depth/1311867179.892712.png +1311867179.930905 rgb/1311867179.930905.png 1311867179.924723 depth/1311867179.924723.png +1311867179.963493 rgb/1311867179.963493.png 1311867179.963538 depth/1311867179.963538.png +1311867179.995888 rgb/1311867179.995888.png 1311867179.992996 depth/1311867179.992996.png +1311867180.030977 rgb/1311867180.030977.png 1311867180.026152 depth/1311867180.026152.png +1311867180.062647 rgb/1311867180.062647.png 1311867180.060614 depth/1311867180.060614.png +1311867180.094773 rgb/1311867180.094773.png 1311867180.092930 depth/1311867180.092930.png +1311867180.130773 rgb/1311867180.130773.png 1311867180.125768 depth/1311867180.125768.png +1311867180.163680 rgb/1311867180.163680.png 1311867180.163690 depth/1311867180.163690.png +1311867180.194909 rgb/1311867180.194909.png 1311867180.192644 depth/1311867180.192644.png +1311867180.230814 rgb/1311867180.230814.png 1311867180.224846 depth/1311867180.224846.png +1311867180.263762 rgb/1311867180.263762.png 1311867180.261752 depth/1311867180.261752.png +1311867180.294755 rgb/1311867180.294755.png 1311867180.293896 depth/1311867180.293896.png +1311867180.330867 rgb/1311867180.330867.png 1311867180.327074 depth/1311867180.327074.png +1311867180.365820 rgb/1311867180.365820.png 1311867180.365829 depth/1311867180.365829.png +1311867180.396166 rgb/1311867180.396166.png 1311867180.396411 depth/1311867180.396411.png +1311867180.430915 rgb/1311867180.430915.png 1311867180.427854 depth/1311867180.427854.png +1311867180.467067 rgb/1311867180.467067.png 1311867180.461765 depth/1311867180.461765.png +1311867180.494756 rgb/1311867180.494756.png 1311867180.493086 depth/1311867180.493086.png +1311867180.530888 rgb/1311867180.530888.png 1311867180.525941 depth/1311867180.525941.png +1311867180.562951 rgb/1311867180.562951.png 1311867180.560710 depth/1311867180.560710.png +1311867180.594691 rgb/1311867180.594691.png 1311867180.593978 depth/1311867180.593978.png +1311867180.630813 rgb/1311867180.630813.png 1311867180.627066 depth/1311867180.627066.png +1311867180.664091 rgb/1311867180.664091.png 1311867180.661734 depth/1311867180.661734.png +1311867180.695760 rgb/1311867180.695760.png 1311867180.695786 depth/1311867180.695786.png +1311867180.730974 rgb/1311867180.730974.png 1311867180.724682 depth/1311867180.724682.png +1311867180.765038 rgb/1311867180.765038.png 1311867180.765083 depth/1311867180.765083.png +1311867180.794928 rgb/1311867180.794928.png 1311867180.793675 depth/1311867180.793675.png +1311867180.830924 rgb/1311867180.830924.png 1311867180.828968 depth/1311867180.828968.png +1311867180.865254 rgb/1311867180.865254.png 1311867180.865270 depth/1311867180.865270.png +1311867180.896647 rgb/1311867180.896647.png 1311867180.896192 depth/1311867180.896192.png +1311867180.930605 rgb/1311867180.930605.png 1311867180.929785 depth/1311867180.929785.png +1311867180.963183 rgb/1311867180.963183.png 1311867180.962601 depth/1311867180.962601.png +1311867180.994818 rgb/1311867180.994818.png 1311867180.992656 depth/1311867180.992656.png +1311867181.030831 rgb/1311867181.030831.png 1311867181.030155 depth/1311867181.030155.png +1311867181.062783 rgb/1311867181.062783.png 1311867181.062610 depth/1311867181.062610.png +1311867181.094872 rgb/1311867181.094872.png 1311867181.093163 depth/1311867181.093163.png +1311867181.131191 rgb/1311867181.131191.png 1311867181.128759 depth/1311867181.128759.png +1311867181.162904 rgb/1311867181.162904.png 1311867181.162953 depth/1311867181.162953.png +1311867181.197251 rgb/1311867181.197251.png 1311867181.197283 depth/1311867181.197283.png +1311867181.234246 rgb/1311867181.234246.png 1311867181.231080 depth/1311867181.231080.png +1311867181.262936 rgb/1311867181.262936.png 1311867181.262009 depth/1311867181.262009.png +1311867181.294809 rgb/1311867181.294809.png 1311867181.294030 depth/1311867181.294030.png +1311867181.331699 rgb/1311867181.331699.png 1311867181.331714 depth/1311867181.331714.png +1311867181.362671 rgb/1311867181.362671.png 1311867181.362187 depth/1311867181.362187.png +1311867181.394822 rgb/1311867181.394822.png 1311867181.393741 depth/1311867181.393741.png +1311867181.430895 rgb/1311867181.430895.png 1311867181.429039 depth/1311867181.429039.png +1311867181.462831 rgb/1311867181.462831.png 1311867181.461533 depth/1311867181.461533.png +1311867181.496340 rgb/1311867181.496340.png 1311867181.496361 depth/1311867181.496361.png +1311867181.535911 rgb/1311867181.535911.png 1311867181.530602 depth/1311867181.530602.png +1311867181.563214 rgb/1311867181.563214.png 1311867181.567172 depth/1311867181.567172.png +1311867181.594861 rgb/1311867181.594861.png 1311867181.594580 depth/1311867181.594580.png +1311867181.630984 rgb/1311867181.630984.png 1311867181.631359 depth/1311867181.631359.png +1311867181.662857 rgb/1311867181.662857.png 1311867181.660906 depth/1311867181.660906.png +1311867181.694923 rgb/1311867181.694923.png 1311867181.692771 depth/1311867181.692771.png +1311867181.731083 rgb/1311867181.731083.png 1311867181.730273 depth/1311867181.730273.png +1311867181.763477 rgb/1311867181.763477.png 1311867181.763484 depth/1311867181.763484.png +1311867181.794898 rgb/1311867181.794898.png 1311867181.792947 depth/1311867181.792947.png +1311867181.830801 rgb/1311867181.830801.png 1311867181.828757 depth/1311867181.828757.png +1311867181.862798 rgb/1311867181.862798.png 1311867181.862225 depth/1311867181.862225.png +1311867181.894929 rgb/1311867181.894929.png 1311867181.892924 depth/1311867181.892924.png +1311867181.930799 rgb/1311867181.930799.png 1311867181.929356 depth/1311867181.929356.png +1311867181.962919 rgb/1311867181.962919.png 1311867181.960985 depth/1311867181.960985.png +1311867181.995551 rgb/1311867181.995551.png 1311867181.995560 depth/1311867181.995560.png +1311867182.031939 rgb/1311867182.031939.png 1311867182.032064 depth/1311867182.032064.png +1311867182.062900 rgb/1311867182.062900.png 1311867182.060982 depth/1311867182.060982.png +1311867182.094884 rgb/1311867182.094884.png 1311867182.093419 depth/1311867182.093419.png +1311867182.131453 rgb/1311867182.131453.png 1311867182.131484 depth/1311867182.131484.png +1311867182.162992 rgb/1311867182.162992.png 1311867182.160935 depth/1311867182.160935.png +1311867182.199442 rgb/1311867182.199442.png 1311867182.199450 depth/1311867182.199450.png +1311867182.230774 rgb/1311867182.230774.png 1311867182.229453 depth/1311867182.229453.png +1311867182.262912 rgb/1311867182.262912.png 1311867182.261573 depth/1311867182.261573.png +1311867182.297304 rgb/1311867182.297304.png 1311867182.297354 depth/1311867182.297354.png +1311867182.330846 rgb/1311867182.330846.png 1311867182.328882 depth/1311867182.328882.png +1311867182.362967 rgb/1311867182.362967.png 1311867182.360555 depth/1311867182.360555.png +1311867182.399028 rgb/1311867182.399028.png 1311867182.399037 depth/1311867182.399037.png +1311867182.430812 rgb/1311867182.430812.png 1311867182.428810 depth/1311867182.428810.png +1311867182.462944 rgb/1311867182.462944.png 1311867182.460845 depth/1311867182.460845.png +1311867182.496953 rgb/1311867182.496953.png 1311867182.496960 depth/1311867182.496960.png +1311867182.530950 rgb/1311867182.530950.png 1311867182.528654 depth/1311867182.528654.png +1311867182.562970 rgb/1311867182.562970.png 1311867182.561034 depth/1311867182.561034.png +1311867182.603637 rgb/1311867182.603637.png 1311867182.600491 depth/1311867182.600491.png +1311867182.630845 rgb/1311867182.630845.png 1311867182.630737 depth/1311867182.630737.png +1311867182.663572 rgb/1311867182.663572.png 1311867182.663592 depth/1311867182.663592.png +1311867182.696991 rgb/1311867182.696991.png 1311867182.697002 depth/1311867182.697002.png +1311867182.733050 rgb/1311867182.733050.png 1311867182.733064 depth/1311867182.733064.png +1311867182.763107 rgb/1311867182.763107.png 1311867182.763113 depth/1311867182.763113.png +1311867182.797044 rgb/1311867182.797044.png 1311867182.797055 depth/1311867182.797055.png +1311867182.830690 rgb/1311867182.830690.png 1311867182.830699 depth/1311867182.830699.png +1311867182.864091 rgb/1311867182.864091.png 1311867182.864117 depth/1311867182.864117.png +1311867182.896985 rgb/1311867182.896985.png 1311867182.896997 depth/1311867182.896997.png +1311867182.931887 rgb/1311867182.931887.png 1311867182.931899 depth/1311867182.931899.png +1311867182.963056 rgb/1311867182.963056.png 1311867182.963072 depth/1311867182.963072.png +1311867182.998350 rgb/1311867182.998350.png 1311867182.998395 depth/1311867182.998395.png +1311867183.030883 rgb/1311867183.030883.png 1311867183.029566 depth/1311867183.029566.png +1311867183.062860 rgb/1311867183.062860.png 1311867183.061472 depth/1311867183.061472.png +1311867183.100040 rgb/1311867183.100040.png 1311867183.100050 depth/1311867183.100050.png +1311867183.134468 rgb/1311867183.134468.png 1311867183.134478 depth/1311867183.134478.png +1311867183.167324 rgb/1311867183.167324.png 1311867183.161718 depth/1311867183.161718.png +1311867183.200473 rgb/1311867183.200473.png 1311867183.200492 depth/1311867183.200492.png +1311867183.231128 rgb/1311867183.231128.png 1311867183.230460 depth/1311867183.230460.png +1311867183.263324 rgb/1311867183.263324.png 1311867183.263335 depth/1311867183.263335.png +1311867183.299097 rgb/1311867183.299097.png 1311867183.299110 depth/1311867183.299110.png +1311867183.332092 rgb/1311867183.332092.png 1311867183.329084 depth/1311867183.329084.png +1311867183.369524 rgb/1311867183.369524.png 1311867183.368481 depth/1311867183.368481.png +1311867183.398546 rgb/1311867183.398546.png 1311867183.398621 depth/1311867183.398621.png +1311867183.431155 rgb/1311867183.431155.png 1311867183.430378 depth/1311867183.430378.png +1311867183.466738 rgb/1311867183.466738.png 1311867183.466745 depth/1311867183.466745.png +1311867183.498828 rgb/1311867183.498828.png 1311867183.498834 depth/1311867183.498834.png +1311867183.532172 rgb/1311867183.532172.png 1311867183.532183 depth/1311867183.532183.png +1311867183.566151 rgb/1311867183.566151.png 1311867183.566161 depth/1311867183.566161.png +1311867183.598535 rgb/1311867183.598535.png 1311867183.598548 depth/1311867183.598548.png +1311867183.631088 rgb/1311867183.631088.png 1311867183.629509 depth/1311867183.629509.png +1311867183.664879 rgb/1311867183.664879.png 1311867183.664926 depth/1311867183.664926.png +1311867183.699353 rgb/1311867183.699353.png 1311867183.699395 depth/1311867183.699395.png +1311867183.730893 rgb/1311867183.730893.png 1311867183.729812 depth/1311867183.729812.png +1311867183.767624 rgb/1311867183.767624.png 1311867183.767648 depth/1311867183.767648.png +1311867183.797176 rgb/1311867183.797176.png 1311867183.797187 depth/1311867183.797187.png +1311867183.830907 rgb/1311867183.830907.png 1311867183.829710 depth/1311867183.829710.png +1311867183.865499 rgb/1311867183.865499.png 1311867183.865505 depth/1311867183.865505.png +1311867183.897086 rgb/1311867183.897086.png 1311867183.897097 depth/1311867183.897097.png +1311867183.931483 rgb/1311867183.931483.png 1311867183.931494 depth/1311867183.931494.png +1311867183.965821 rgb/1311867183.965821.png 1311867183.965832 depth/1311867183.965832.png +1311867183.996668 rgb/1311867183.996668.png 1311867183.996678 depth/1311867183.996678.png +1311867184.030969 rgb/1311867184.030969.png 1311867184.030585 depth/1311867184.030585.png +1311867184.064723 rgb/1311867184.064723.png 1311867184.064785 depth/1311867184.064785.png +1311867184.096811 rgb/1311867184.096811.png 1311867184.096889 depth/1311867184.096889.png +1311867184.131226 rgb/1311867184.131226.png 1311867184.129342 depth/1311867184.129342.png +1311867184.165054 rgb/1311867184.165054.png 1311867184.165064 depth/1311867184.165064.png +1311867184.196946 rgb/1311867184.196946.png 1311867184.196956 depth/1311867184.196956.png +1311867184.230936 rgb/1311867184.230936.png 1311867184.228912 depth/1311867184.228912.png +1311867184.268102 rgb/1311867184.268102.png 1311867184.268137 depth/1311867184.268137.png +1311867184.298370 rgb/1311867184.298370.png 1311867184.298390 depth/1311867184.298390.png +1311867184.331470 rgb/1311867184.331470.png 1311867184.329391 depth/1311867184.329391.png +1311867184.369763 rgb/1311867184.369763.png 1311867184.369784 depth/1311867184.369784.png +1311867184.400006 rgb/1311867184.400006.png 1311867184.400022 depth/1311867184.400022.png +1311867184.431061 rgb/1311867184.431061.png 1311867184.429210 depth/1311867184.429210.png +1311867184.465574 rgb/1311867184.465574.png 1311867184.465581 depth/1311867184.465581.png +1311867184.503767 rgb/1311867184.503767.png 1311867184.503424 depth/1311867184.503424.png +1311867184.531088 rgb/1311867184.531088.png 1311867184.529928 depth/1311867184.529928.png +1311867184.568280 rgb/1311867184.568280.png 1311867184.568293 depth/1311867184.568293.png +1311867184.597993 rgb/1311867184.597993.png 1311867184.601807 depth/1311867184.601807.png +1311867184.635545 rgb/1311867184.635545.png 1311867184.636740 depth/1311867184.636740.png +1311867184.666244 rgb/1311867184.666244.png 1311867184.665906 depth/1311867184.665906.png +1311867184.699477 rgb/1311867184.699477.png 1311867184.699493 depth/1311867184.699493.png +1311867184.735909 rgb/1311867184.735909.png 1311867184.735916 depth/1311867184.735916.png +1311867184.769022 rgb/1311867184.769022.png 1311867184.769069 depth/1311867184.769069.png +1311867184.799534 rgb/1311867184.799534.png 1311867184.800128 depth/1311867184.800128.png +1311867184.834825 rgb/1311867184.834825.png 1311867184.834844 depth/1311867184.834844.png +1311867184.868574 rgb/1311867184.868574.png 1311867184.869066 depth/1311867184.869066.png +1311867184.905521 rgb/1311867184.905521.png 1311867184.900567 depth/1311867184.900567.png +1311867184.933218 rgb/1311867184.933218.png 1311867184.933228 depth/1311867184.933228.png +1311867184.965627 rgb/1311867184.965627.png 1311867184.965641 depth/1311867184.965641.png +1311867184.998315 rgb/1311867184.998315.png 1311867184.998325 depth/1311867184.998325.png +1311867185.036045 rgb/1311867185.036045.png 1311867185.036055 depth/1311867185.036055.png +1311867185.065223 rgb/1311867185.065223.png 1311867185.065235 depth/1311867185.065235.png +1311867185.099109 rgb/1311867185.099109.png 1311867185.099128 depth/1311867185.099128.png +1311867185.136065 rgb/1311867185.136065.png 1311867185.136078 depth/1311867185.136078.png +1311867185.164814 rgb/1311867185.164814.png 1311867185.164871 depth/1311867185.164871.png +1311867185.200008 rgb/1311867185.200008.png 1311867185.200072 depth/1311867185.200072.png +1311867185.234264 rgb/1311867185.234264.png 1311867185.234292 depth/1311867185.234292.png +1311867185.266332 rgb/1311867185.266332.png 1311867185.266395 depth/1311867185.266395.png +1311867185.297013 rgb/1311867185.297013.png 1311867185.297055 depth/1311867185.297055.png +1311867185.335984 rgb/1311867185.335984.png 1311867185.336014 depth/1311867185.336014.png +1311867185.368164 rgb/1311867185.368164.png 1311867185.368178 depth/1311867185.368178.png +1311867185.403637 rgb/1311867185.403637.png 1311867185.403651 depth/1311867185.403651.png +1311867185.437322 rgb/1311867185.437322.png 1311867185.438639 depth/1311867185.438639.png +1311867185.465497 rgb/1311867185.465497.png 1311867185.465545 depth/1311867185.465545.png +1311867185.500623 rgb/1311867185.500623.png 1311867185.501391 depth/1311867185.501391.png +1311867185.533624 rgb/1311867185.533624.png 1311867185.533633 depth/1311867185.533633.png +1311867185.566669 rgb/1311867185.566669.png 1311867185.566680 depth/1311867185.566680.png +1311867185.596975 rgb/1311867185.596975.png 1311867185.597054 depth/1311867185.597054.png +1311867185.632940 rgb/1311867185.632940.png 1311867185.632947 depth/1311867185.632947.png +1311867185.666408 rgb/1311867185.666408.png 1311867185.666418 depth/1311867185.666418.png +1311867185.697332 rgb/1311867185.697332.png 1311867185.697339 depth/1311867185.697339.png +1311867185.735179 rgb/1311867185.735179.png 1311867185.735190 depth/1311867185.735190.png +1311867185.764971 rgb/1311867185.764971.png 1311867185.764977 depth/1311867185.764977.png +1311867185.798952 rgb/1311867185.798952.png 1311867185.798965 depth/1311867185.798965.png +1311867185.832792 rgb/1311867185.832792.png 1311867185.832800 depth/1311867185.832800.png +1311867185.864904 rgb/1311867185.864904.png 1311867185.864910 depth/1311867185.864910.png +1311867185.895173 rgb/1311867185.895173.png 1311867185.903042 depth/1311867185.903042.png +1311867185.935978 rgb/1311867185.935978.png 1311867185.939679 depth/1311867185.939679.png +1311867185.965051 rgb/1311867185.965051.png 1311867185.965061 depth/1311867185.965061.png +1311867185.995231 rgb/1311867185.995231.png 1311867186.003947 depth/1311867186.003947.png +1311867186.035964 rgb/1311867186.035964.png 1311867186.039692 depth/1311867186.039692.png +1311867186.065305 rgb/1311867186.065305.png 1311867186.065324 depth/1311867186.065324.png +1311867186.095284 rgb/1311867186.095284.png 1311867186.104734 depth/1311867186.104734.png +1311867186.136102 rgb/1311867186.136102.png 1311867186.136118 depth/1311867186.136118.png +1311867186.164936 rgb/1311867186.164936.png 1311867186.164945 depth/1311867186.164945.png +1311867186.195188 rgb/1311867186.195188.png 1311867186.204475 depth/1311867186.204475.png +1311867186.235893 rgb/1311867186.235893.png 1311867186.235966 depth/1311867186.235966.png +1311867186.267490 rgb/1311867186.267490.png 1311867186.267308 depth/1311867186.267308.png +1311867186.295199 rgb/1311867186.295199.png 1311867186.303084 depth/1311867186.303084.png +1311867186.334915 rgb/1311867186.334915.png 1311867186.334927 depth/1311867186.334927.png +1311867186.366964 rgb/1311867186.366964.png 1311867186.367016 depth/1311867186.367016.png +1311867186.395131 rgb/1311867186.395131.png 1311867186.401985 depth/1311867186.401985.png +1311867186.436010 rgb/1311867186.436010.png 1311867186.436021 depth/1311867186.436021.png +1311867186.465948 rgb/1311867186.465948.png 1311867186.465889 depth/1311867186.465889.png +1311867186.495214 rgb/1311867186.495214.png 1311867186.503114 depth/1311867186.503114.png +1311867186.536274 rgb/1311867186.536274.png 1311867186.536317 depth/1311867186.536317.png +1311867186.565107 rgb/1311867186.565107.png 1311867186.565113 depth/1311867186.565113.png +1311867186.595160 rgb/1311867186.595160.png 1311867186.601422 depth/1311867186.601422.png +1311867186.636236 rgb/1311867186.636236.png 1311867186.636263 depth/1311867186.636263.png +1311867186.665014 rgb/1311867186.665014.png 1311867186.665048 depth/1311867186.665048.png +1311867186.704365 rgb/1311867186.704365.png 1311867186.704381 depth/1311867186.704381.png +1311867186.733752 rgb/1311867186.733752.png 1311867186.733775 depth/1311867186.733775.png +1311867186.767288 rgb/1311867186.767288.png 1311867186.767318 depth/1311867186.767318.png +1311867186.804720 rgb/1311867186.804720.png 1311867186.804730 depth/1311867186.804730.png +1311867186.834068 rgb/1311867186.834068.png 1311867186.834075 depth/1311867186.834075.png +1311867186.869100 rgb/1311867186.869100.png 1311867186.877600 depth/1311867186.877600.png +1311867186.905187 rgb/1311867186.905187.png 1311867186.905210 depth/1311867186.905210.png +1311867186.933418 rgb/1311867186.933418.png 1311867186.933424 depth/1311867186.933424.png +1311867186.965693 rgb/1311867186.965693.png 1311867186.966338 depth/1311867186.966338.png +1311867187.001705 rgb/1311867187.001705.png 1311867187.001714 depth/1311867187.001714.png +1311867187.033640 rgb/1311867187.033640.png 1311867187.033646 depth/1311867187.033646.png +1311867187.063280 rgb/1311867187.063280.png 1311867187.074935 depth/1311867187.074935.png +1311867187.101595 rgb/1311867187.101595.png 1311867187.101603 depth/1311867187.101603.png +1311867187.133979 rgb/1311867187.133979.png 1311867187.134207 depth/1311867187.134207.png +1311867187.163262 rgb/1311867187.163262.png 1311867187.171021 depth/1311867187.171021.png +1311867187.204123 rgb/1311867187.204123.png 1311867187.204137 depth/1311867187.204137.png +1311867187.233159 rgb/1311867187.233159.png 1311867187.233166 depth/1311867187.233166.png +1311867187.263350 rgb/1311867187.263350.png 1311867187.270763 depth/1311867187.270763.png +1311867187.301486 rgb/1311867187.301486.png 1311867187.301506 depth/1311867187.301506.png +1311867187.333649 rgb/1311867187.333649.png 1311867187.333657 depth/1311867187.333657.png +1311867187.363171 rgb/1311867187.363171.png 1311867187.370759 depth/1311867187.370759.png +1311867187.403345 rgb/1311867187.403345.png 1311867187.403353 depth/1311867187.403353.png +1311867187.433580 rgb/1311867187.433580.png 1311867187.433590 depth/1311867187.433590.png +1311867187.463190 rgb/1311867187.463190.png 1311867187.476316 depth/1311867187.476316.png +1311867187.505626 rgb/1311867187.505626.png 1311867187.505640 depth/1311867187.505640.png +1311867187.534189 rgb/1311867187.534189.png 1311867187.534219 depth/1311867187.534219.png +1311867187.563217 rgb/1311867187.563217.png 1311867187.570968 depth/1311867187.570968.png +1311867187.604561 rgb/1311867187.604561.png 1311867187.604579 depth/1311867187.604579.png +1311867187.635392 rgb/1311867187.635392.png 1311867187.633614 depth/1311867187.633614.png +1311867187.663270 rgb/1311867187.663270.png 1311867187.670769 depth/1311867187.670769.png +1311867187.703564 rgb/1311867187.703564.png 1311867187.703577 depth/1311867187.703577.png +1311867187.734539 rgb/1311867187.734539.png 1311867187.734548 depth/1311867187.734548.png +1311867187.763190 rgb/1311867187.763190.png 1311867187.770782 depth/1311867187.770782.png +1311867187.801705 rgb/1311867187.801705.png 1311867187.801751 depth/1311867187.801751.png +1311867187.833949 rgb/1311867187.833949.png 1311867187.833961 depth/1311867187.833961.png +1311867187.863411 rgb/1311867187.863411.png 1311867187.870809 depth/1311867187.870809.png +1311867187.903871 rgb/1311867187.903871.png 1311867187.903881 depth/1311867187.903881.png +1311867187.933221 rgb/1311867187.933221.png 1311867187.936300 depth/1311867187.936300.png +1311867187.963534 rgb/1311867187.963534.png 1311867187.971342 depth/1311867187.971342.png +1311867188.004742 rgb/1311867188.004742.png 1311867188.004757 depth/1311867188.004757.png +1311867188.033304 rgb/1311867188.033304.png 1311867188.033311 depth/1311867188.033311.png +1311867188.063418 rgb/1311867188.063418.png 1311867188.069870 depth/1311867188.069870.png +1311867188.108880 rgb/1311867188.108880.png 1311867188.104646 depth/1311867188.104646.png +1311867188.135990 rgb/1311867188.135990.png 1311867188.135997 depth/1311867188.135997.png +1311867188.163360 rgb/1311867188.163360.png 1311867188.170335 depth/1311867188.170335.png +1311867188.202654 rgb/1311867188.202654.png 1311867188.202672 depth/1311867188.202672.png +1311867188.235201 rgb/1311867188.235201.png 1311867188.235245 depth/1311867188.235245.png +1311867188.263272 rgb/1311867188.263272.png 1311867188.270646 depth/1311867188.270646.png +1311867188.304719 rgb/1311867188.304719.png 1311867188.304734 depth/1311867188.304734.png +1311867188.331453 rgb/1311867188.331453.png 1311867188.339880 depth/1311867188.339880.png +1311867188.363382 rgb/1311867188.363382.png 1311867188.371880 depth/1311867188.371880.png +1311867188.402043 rgb/1311867188.402043.png 1311867188.405447 depth/1311867188.405447.png +1311867188.431385 rgb/1311867188.431385.png 1311867188.439879 depth/1311867188.439879.png +1311867188.463247 rgb/1311867188.463247.png 1311867188.472450 depth/1311867188.472450.png +1311867188.504901 rgb/1311867188.504901.png 1311867188.504916 depth/1311867188.504916.png +1311867188.531435 rgb/1311867188.531435.png 1311867188.538999 depth/1311867188.538999.png +1311867188.563332 rgb/1311867188.563332.png 1311867188.572389 depth/1311867188.572389.png +1311867188.604580 rgb/1311867188.604580.png 1311867188.604596 depth/1311867188.604596.png +1311867188.631500 rgb/1311867188.631500.png 1311867188.639834 depth/1311867188.639834.png +1311867188.663337 rgb/1311867188.663337.png 1311867188.671508 depth/1311867188.671508.png +1311867188.703814 rgb/1311867188.703814.png 1311867188.703830 depth/1311867188.703830.png +1311867188.731585 rgb/1311867188.731585.png 1311867188.739383 depth/1311867188.739383.png +1311867188.763294 rgb/1311867188.763294.png 1311867188.772105 depth/1311867188.772105.png +1311867188.804516 rgb/1311867188.804516.png 1311867188.804522 depth/1311867188.804522.png +1311867188.831350 rgb/1311867188.831350.png 1311867188.840243 depth/1311867188.840243.png +1311867188.863544 rgb/1311867188.863544.png 1311867188.870599 depth/1311867188.870599.png +1311867188.901620 rgb/1311867188.901620.png 1311867188.901631 depth/1311867188.901631.png +1311867188.931465 rgb/1311867188.931465.png 1311867188.940177 depth/1311867188.940177.png +1311867188.963444 rgb/1311867188.963444.png 1311867188.970999 depth/1311867188.970999.png +1311867189.005216 rgb/1311867189.005216.png 1311867189.005226 depth/1311867189.005226.png +1311867189.031438 rgb/1311867189.031438.png 1311867189.040010 depth/1311867189.040010.png +1311867189.063539 rgb/1311867189.063539.png 1311867189.072433 depth/1311867189.072433.png +1311867189.102629 rgb/1311867189.102629.png 1311867189.102636 depth/1311867189.102636.png +1311867189.131312 rgb/1311867189.131312.png 1311867189.141764 depth/1311867189.141764.png +1311867189.163420 rgb/1311867189.163420.png 1311867189.171792 depth/1311867189.171792.png +1311867189.201890 rgb/1311867189.201890.png 1311867189.201907 depth/1311867189.201907.png +1311867189.231285 rgb/1311867189.231285.png 1311867189.239063 depth/1311867189.239063.png +1311867189.263345 rgb/1311867189.263345.png 1311867189.272264 depth/1311867189.272264.png +1311867189.304679 rgb/1311867189.304679.png 1311867189.304380 depth/1311867189.304380.png +1311867189.331405 rgb/1311867189.331405.png 1311867189.339797 depth/1311867189.339797.png +1311867189.363335 rgb/1311867189.363335.png 1311867189.372036 depth/1311867189.372036.png +1311867189.405684 rgb/1311867189.405684.png 1311867189.405695 depth/1311867189.405695.png +1311867189.431458 rgb/1311867189.431458.png 1311867189.440502 depth/1311867189.440502.png +1311867189.463454 rgb/1311867189.463454.png 1311867189.472913 depth/1311867189.472913.png +1311867189.505937 rgb/1311867189.505937.png 1311867189.506040 depth/1311867189.506040.png +1311867189.531417 rgb/1311867189.531417.png 1311867189.539429 depth/1311867189.539429.png +1311867189.563319 rgb/1311867189.563319.png 1311867189.572027 depth/1311867189.572027.png +1311867189.599369 rgb/1311867189.599369.png 1311867189.611291 depth/1311867189.611291.png +1311867189.631378 rgb/1311867189.631378.png 1311867189.642422 depth/1311867189.642422.png +1311867189.663469 rgb/1311867189.663469.png 1311867189.672840 depth/1311867189.672840.png +1311867189.699784 rgb/1311867189.699784.png 1311867189.706587 depth/1311867189.706587.png +1311867189.731458 rgb/1311867189.731458.png 1311867189.740172 depth/1311867189.740172.png +1311867189.763361 rgb/1311867189.763361.png 1311867189.772976 depth/1311867189.772976.png +1311867189.799486 rgb/1311867189.799486.png 1311867189.807397 depth/1311867189.807397.png +1311867189.831366 rgb/1311867189.831366.png 1311867189.840531 depth/1311867189.840531.png +1311867189.863410 rgb/1311867189.863410.png 1311867189.871353 depth/1311867189.871353.png +1311867189.899521 rgb/1311867189.899521.png 1311867189.910268 depth/1311867189.910268.png +1311867189.931364 rgb/1311867189.931364.png 1311867189.940226 depth/1311867189.940226.png +1311867189.963340 rgb/1311867189.963340.png 1311867189.972762 depth/1311867189.972762.png +1311867189.999434 rgb/1311867189.999434.png 1311867190.010701 depth/1311867190.010701.png +1311867190.031516 rgb/1311867190.031516.png 1311867190.040293 depth/1311867190.040293.png +1311867190.063454 rgb/1311867190.063454.png 1311867190.071904 depth/1311867190.071904.png +1311867190.099590 rgb/1311867190.099590.png 1311867190.109654 depth/1311867190.109654.png +1311867190.131422 rgb/1311867190.131422.png 1311867190.139637 depth/1311867190.139637.png +1311867190.163525 rgb/1311867190.163525.png 1311867190.170638 depth/1311867190.170638.png +1311867190.199492 rgb/1311867190.199492.png 1311867190.209602 depth/1311867190.209602.png +1311867190.231389 rgb/1311867190.231389.png 1311867190.239433 depth/1311867190.239433.png +1311867190.263381 rgb/1311867190.263381.png 1311867190.271481 depth/1311867190.271481.png +1311867190.299376 rgb/1311867190.299376.png 1311867190.307270 depth/1311867190.307270.png +1311867190.331359 rgb/1311867190.331359.png 1311867190.341473 depth/1311867190.341473.png +1311867190.363437 rgb/1311867190.363437.png 1311867190.371683 depth/1311867190.371683.png +1311867190.399467 rgb/1311867190.399467.png 1311867190.410109 depth/1311867190.410109.png +1311867190.431374 rgb/1311867190.431374.png 1311867190.439496 depth/1311867190.439496.png +1311867190.463341 rgb/1311867190.463341.png 1311867190.470820 depth/1311867190.470820.png +1311867190.499357 rgb/1311867190.499357.png 1311867190.509753 depth/1311867190.509753.png +1311867190.531809 rgb/1311867190.531809.png 1311867190.540519 depth/1311867190.540519.png +1311867190.563353 rgb/1311867190.563353.png 1311867190.570844 depth/1311867190.570844.png +1311867190.599451 rgb/1311867190.599451.png 1311867190.606775 depth/1311867190.606775.png +1311867190.631421 rgb/1311867190.631421.png 1311867190.638994 depth/1311867190.638994.png +1311867190.663424 rgb/1311867190.663424.png 1311867190.672366 depth/1311867190.672366.png +1311867190.699639 rgb/1311867190.699639.png 1311867190.711498 depth/1311867190.711498.png +1311867190.731381 rgb/1311867190.731381.png 1311867190.739265 depth/1311867190.739265.png +1311867190.763475 rgb/1311867190.763475.png 1311867190.775180 depth/1311867190.775180.png +1311867190.799433 rgb/1311867190.799433.png 1311867190.807090 depth/1311867190.807090.png +1311867190.831710 rgb/1311867190.831710.png 1311867190.841428 depth/1311867190.841428.png +1311867190.863426 rgb/1311867190.863426.png 1311867190.873925 depth/1311867190.873925.png +1311867190.899432 rgb/1311867190.899432.png 1311867190.907614 depth/1311867190.907614.png +1311867190.931647 rgb/1311867190.931647.png 1311867190.939360 depth/1311867190.939360.png +1311867190.963532 rgb/1311867190.963532.png 1311867190.974161 depth/1311867190.974161.png +1311867190.999440 rgb/1311867190.999440.png 1311867191.008595 depth/1311867191.008595.png +1311867191.031327 rgb/1311867191.031327.png 1311867191.039692 depth/1311867191.039692.png +1311867191.063627 rgb/1311867191.063627.png 1311867191.076433 depth/1311867191.076433.png +1311867191.099432 rgb/1311867191.099432.png 1311867191.110304 depth/1311867191.110304.png +1311867191.131303 rgb/1311867191.131303.png 1311867191.138814 depth/1311867191.138814.png +1311867191.163395 rgb/1311867191.163395.png 1311867191.174282 depth/1311867191.174282.png +1311867191.199389 rgb/1311867191.199389.png 1311867191.207792 depth/1311867191.207792.png +1311867191.231395 rgb/1311867191.231395.png 1311867191.240842 depth/1311867191.240842.png +1311867191.263468 rgb/1311867191.263468.png 1311867191.276958 depth/1311867191.276958.png +1311867191.299713 rgb/1311867191.299713.png 1311867191.308503 depth/1311867191.308503.png +1311867191.331660 rgb/1311867191.331660.png 1311867191.340478 depth/1311867191.340478.png +1311867191.363436 rgb/1311867191.363436.png 1311867191.379463 depth/1311867191.379463.png +1311867191.399571 rgb/1311867191.399571.png 1311867191.409158 depth/1311867191.409158.png +1311867191.431588 rgb/1311867191.431588.png 1311867191.441597 depth/1311867191.441597.png +1311867191.463414 rgb/1311867191.463414.png 1311867191.477531 depth/1311867191.477531.png +1311867191.499653 rgb/1311867191.499653.png 1311867191.507559 depth/1311867191.507559.png +1311867191.531446 rgb/1311867191.531446.png 1311867191.539062 depth/1311867191.539062.png +1311867191.563639 rgb/1311867191.563639.png 1311867191.576470 depth/1311867191.576470.png +1311867191.599847 rgb/1311867191.599847.png 1311867191.611867 depth/1311867191.611867.png +1311867191.631469 rgb/1311867191.631469.png 1311867191.645188 depth/1311867191.645188.png +1311867191.663620 rgb/1311867191.663620.png 1311867191.682792 depth/1311867191.682792.png +1311867191.699573 rgb/1311867191.699573.png 1311867191.711940 depth/1311867191.711940.png +1311867191.731487 rgb/1311867191.731487.png 1311867191.745720 depth/1311867191.745720.png +1311867191.763579 rgb/1311867191.763579.png 1311867191.776380 depth/1311867191.776380.png +1311867191.799771 rgb/1311867191.799771.png 1311867191.809725 depth/1311867191.809725.png +1311867191.831511 rgb/1311867191.831511.png 1311867191.839578 depth/1311867191.839578.png +1311867191.863471 rgb/1311867191.863471.png 1311867191.874522 depth/1311867191.874522.png +1311867191.899623 rgb/1311867191.899623.png 1311867191.907712 depth/1311867191.907712.png +1311867191.931630 rgb/1311867191.931630.png 1311867191.939160 depth/1311867191.939160.png +1311867191.963470 rgb/1311867191.963470.png 1311867191.975524 depth/1311867191.975524.png +1311867191.999526 rgb/1311867191.999526.png 1311867192.007629 depth/1311867192.007629.png +1311867192.031527 rgb/1311867192.031527.png 1311867192.044795 depth/1311867192.044795.png +1311867192.063495 rgb/1311867192.063495.png 1311867192.075193 depth/1311867192.075193.png +1311867192.099806 rgb/1311867192.099806.png 1311867192.107392 depth/1311867192.107392.png +1311867192.131666 rgb/1311867192.131666.png 1311867192.143303 depth/1311867192.143303.png +1311867192.163516 rgb/1311867192.163516.png 1311867192.175467 depth/1311867192.175467.png +1311867192.199653 rgb/1311867192.199653.png 1311867192.207754 depth/1311867192.207754.png +1311867192.231699 rgb/1311867192.231699.png 1311867192.245125 depth/1311867192.245125.png +1311867192.263542 rgb/1311867192.263542.png 1311867192.274463 depth/1311867192.274463.png +1311867192.299473 rgb/1311867192.299473.png 1311867192.306772 depth/1311867192.306772.png +1311867192.331519 rgb/1311867192.331519.png 1311867192.342739 depth/1311867192.342739.png +1311867192.363620 rgb/1311867192.363620.png 1311867192.375591 depth/1311867192.375591.png +1311867192.399491 rgb/1311867192.399491.png 1311867192.405934 depth/1311867192.405934.png +1311867192.431620 rgb/1311867192.431620.png 1311867192.444710 depth/1311867192.444710.png +1311867192.463542 rgb/1311867192.463542.png 1311867192.474821 depth/1311867192.474821.png +1311867192.499590 rgb/1311867192.499590.png 1311867192.507719 depth/1311867192.507719.png +1311867192.531620 rgb/1311867192.531620.png 1311867192.542782 depth/1311867192.542782.png +1311867192.563632 rgb/1311867192.563632.png 1311867192.578717 depth/1311867192.578717.png +1311867192.599632 rgb/1311867192.599632.png 1311867192.610993 depth/1311867192.610993.png +1311867192.631521 rgb/1311867192.631521.png 1311867192.643521 depth/1311867192.643521.png +1311867192.663625 rgb/1311867192.663625.png 1311867192.679014 depth/1311867192.679014.png +1311867192.699607 rgb/1311867192.699607.png 1311867192.711329 depth/1311867192.711329.png +1311867192.731618 rgb/1311867192.731618.png 1311867192.743962 depth/1311867192.743962.png +1311867192.763642 rgb/1311867192.763642.png 1311867192.776063 depth/1311867192.776063.png +1311867192.799500 rgb/1311867192.799500.png 1311867192.809187 depth/1311867192.809187.png +1311867192.831693 rgb/1311867192.831693.png 1311867192.842229 depth/1311867192.842229.png +1311867192.863604 rgb/1311867192.863604.png 1311867192.879289 depth/1311867192.879289.png +1311867192.899654 rgb/1311867192.899654.png 1311867192.909219 depth/1311867192.909219.png +1311867192.931656 rgb/1311867192.931656.png 1311867192.943411 depth/1311867192.943411.png +1311867192.963825 rgb/1311867192.963825.png 1311867192.977629 depth/1311867192.977629.png +1311867192.999714 rgb/1311867192.999714.png 1311867193.008681 depth/1311867193.008681.png +1311867193.031653 rgb/1311867193.031653.png 1311867193.043060 depth/1311867193.043060.png +1311867193.063616 rgb/1311867193.063616.png 1311867193.076737 depth/1311867193.076737.png +1311867193.099627 rgb/1311867193.099627.png 1311867193.110585 depth/1311867193.110585.png +1311867193.131636 rgb/1311867193.131636.png 1311867193.142922 depth/1311867193.142922.png +1311867193.163809 rgb/1311867193.163809.png 1311867193.176737 depth/1311867193.176737.png +1311867193.199592 rgb/1311867193.199592.png 1311867193.212268 depth/1311867193.212268.png +1311867193.231634 rgb/1311867193.231634.png 1311867193.243243 depth/1311867193.243243.png +1311867193.263554 rgb/1311867193.263554.png 1311867193.277390 depth/1311867193.277390.png +1311867193.299517 rgb/1311867193.299517.png 1311867193.313938 depth/1311867193.313938.png +1311867193.331430 rgb/1311867193.331430.png 1311867193.342667 depth/1311867193.342667.png +1311867193.363678 rgb/1311867193.363678.png 1311867193.378823 depth/1311867193.378823.png +1311867193.399557 rgb/1311867193.399557.png 1311867193.412674 depth/1311867193.412674.png +1311867193.431817 rgb/1311867193.431817.png 1311867193.444081 depth/1311867193.444081.png +1311867193.463559 rgb/1311867193.463559.png 1311867193.478297 depth/1311867193.478297.png +1311867193.531619 rgb/1311867193.531619.png 1311867193.543112 depth/1311867193.543112.png +1311867193.563584 rgb/1311867193.563584.png 1311867193.576571 depth/1311867193.576571.png +1311867193.599533 rgb/1311867193.599533.png 1311867193.612780 depth/1311867193.612780.png +1311867193.631742 rgb/1311867193.631742.png 1311867193.646145 depth/1311867193.646145.png +1311867193.663591 rgb/1311867193.663591.png 1311867193.675786 depth/1311867193.675786.png +1311867193.699539 rgb/1311867193.699539.png 1311867193.712289 depth/1311867193.712289.png +1311867193.731568 rgb/1311867193.731568.png 1311867193.743019 depth/1311867193.743019.png +1311867193.763567 rgb/1311867193.763567.png 1311867193.776017 depth/1311867193.776017.png +1311867193.799691 rgb/1311867193.799691.png 1311867193.813971 depth/1311867193.813971.png +1311867193.831554 rgb/1311867193.831554.png 1311867193.843676 depth/1311867193.843676.png +1311867193.863523 rgb/1311867193.863523.png 1311867193.877118 depth/1311867193.877118.png +1311867193.899690 rgb/1311867193.899690.png 1311867193.915123 depth/1311867193.915123.png +1311867193.931567 rgb/1311867193.931567.png 1311867193.942531 depth/1311867193.942531.png +1311867193.963704 rgb/1311867193.963704.png 1311867193.978177 depth/1311867193.978177.png +1311867193.999703 rgb/1311867193.999703.png 1311867194.014857 depth/1311867194.014857.png +1311867194.031689 rgb/1311867194.031689.png 1311867194.043344 depth/1311867194.043344.png +1311867194.063653 rgb/1311867194.063653.png 1311867194.074612 depth/1311867194.074612.png +1311867194.099680 rgb/1311867194.099680.png 1311867194.113106 depth/1311867194.113106.png +1311867194.131720 rgb/1311867194.131720.png 1311867194.142856 depth/1311867194.142856.png +1311867194.163586 rgb/1311867194.163586.png 1311867194.175855 depth/1311867194.175855.png +1311867194.199685 rgb/1311867194.199685.png 1311867194.213845 depth/1311867194.213845.png +1311867194.231549 rgb/1311867194.231549.png 1311867194.245114 depth/1311867194.245114.png +1311867194.263619 rgb/1311867194.263619.png 1311867194.276024 depth/1311867194.276024.png +1311867194.299716 rgb/1311867194.299716.png 1311867194.313920 depth/1311867194.313920.png +1311867194.331761 rgb/1311867194.331761.png 1311867194.344782 depth/1311867194.344782.png +1311867194.363706 rgb/1311867194.363706.png 1311867194.380223 depth/1311867194.380223.png +1311867194.399611 rgb/1311867194.399611.png 1311867194.412452 depth/1311867194.412452.png +1311867194.431803 rgb/1311867194.431803.png 1311867194.444751 depth/1311867194.444751.png +1311867194.463875 rgb/1311867194.463875.png 1311867194.480584 depth/1311867194.480584.png +1311867194.499629 rgb/1311867194.499629.png 1311867194.517493 depth/1311867194.517493.png +1311867194.531606 rgb/1311867194.531606.png 1311867194.543950 depth/1311867194.543950.png +1311867194.563736 rgb/1311867194.563736.png 1311867194.579598 depth/1311867194.579598.png +1311867194.599622 rgb/1311867194.599622.png 1311867194.612948 depth/1311867194.612948.png +1311867194.663614 rgb/1311867194.663614.png 1311867194.649388 depth/1311867194.649388.png +1311867194.699671 rgb/1311867194.699671.png 1311867194.713331 depth/1311867194.713331.png +1311867194.731755 rgb/1311867194.731755.png 1311867194.747510 depth/1311867194.747510.png +1311867194.763586 rgb/1311867194.763586.png 1311867194.778445 depth/1311867194.778445.png +1311867194.799726 rgb/1311867194.799726.png 1311867194.813039 depth/1311867194.813039.png +1311867194.831891 rgb/1311867194.831891.png 1311867194.847672 depth/1311867194.847672.png +1311867194.863668 rgb/1311867194.863668.png 1311867194.881415 depth/1311867194.881415.png +1311867194.899588 rgb/1311867194.899588.png 1311867194.910409 depth/1311867194.910409.png +1311867194.931823 rgb/1311867194.931823.png 1311867194.945145 depth/1311867194.945145.png +1311867194.963864 rgb/1311867194.963864.png 1311867194.978740 depth/1311867194.978740.png +1311867194.999857 rgb/1311867194.999857.png 1311867195.013280 depth/1311867195.013280.png +1311867195.031823 rgb/1311867195.031823.png 1311867195.046494 depth/1311867195.046494.png +1311867195.063659 rgb/1311867195.063659.png 1311867195.078171 depth/1311867195.078171.png +1311867195.099839 rgb/1311867195.099839.png 1311867195.111531 depth/1311867195.111531.png +1311867195.131755 rgb/1311867195.131755.png 1311867195.145831 depth/1311867195.145831.png +1311867195.163739 rgb/1311867195.163739.png 1311867195.178032 depth/1311867195.178032.png +1311867195.199682 rgb/1311867195.199682.png 1311867195.211475 depth/1311867195.211475.png +1311867195.231953 rgb/1311867195.231953.png 1311867195.243680 depth/1311867195.243680.png +1311867195.263959 rgb/1311867195.263959.png 1311867195.278040 depth/1311867195.278040.png +1311867195.299843 rgb/1311867195.299843.png 1311867195.312318 depth/1311867195.312318.png +1311867195.331663 rgb/1311867195.331663.png 1311867195.342598 depth/1311867195.342598.png +1311867195.363660 rgb/1311867195.363660.png 1311867195.378271 depth/1311867195.378271.png +1311867195.399819 rgb/1311867195.399819.png 1311867195.411983 depth/1311867195.411983.png +1311867195.431775 rgb/1311867195.431775.png 1311867195.443552 depth/1311867195.443552.png +1311867195.463774 rgb/1311867195.463774.png 1311867195.478824 depth/1311867195.478824.png +1311867195.499861 rgb/1311867195.499861.png 1311867195.511318 depth/1311867195.511318.png +1311867195.531827 rgb/1311867195.531827.png 1311867195.543962 depth/1311867195.543962.png +1311867195.563721 rgb/1311867195.563721.png 1311867195.578216 depth/1311867195.578216.png +1311867195.599756 rgb/1311867195.599756.png 1311867195.611986 depth/1311867195.611986.png +1311867195.631794 rgb/1311867195.631794.png 1311867195.643091 depth/1311867195.643091.png +1311867195.663755 rgb/1311867195.663755.png 1311867195.677913 depth/1311867195.677913.png +1311867195.699923 rgb/1311867195.699923.png 1311867195.710730 depth/1311867195.710730.png +1311867195.732032 rgb/1311867195.732032.png 1311867195.745830 depth/1311867195.745830.png +1311867195.767662 rgb/1311867195.767662.png 1311867195.782188 depth/1311867195.782188.png +1311867195.799635 rgb/1311867195.799635.png 1311867195.810050 depth/1311867195.810050.png +1311867195.831755 rgb/1311867195.831755.png 1311867195.845855 depth/1311867195.845855.png +1311867195.867630 rgb/1311867195.867630.png 1311867195.877866 depth/1311867195.877866.png +1311867195.899840 rgb/1311867195.899840.png 1311867195.909827 depth/1311867195.909827.png +1311867195.931915 rgb/1311867195.931915.png 1311867195.945846 depth/1311867195.945846.png +1311867195.967737 rgb/1311867195.967737.png 1311867195.977843 depth/1311867195.977843.png +1311867195.999658 rgb/1311867195.999658.png 1311867196.010057 depth/1311867196.010057.png +1311867196.031886 rgb/1311867196.031886.png 1311867196.049879 depth/1311867196.049879.png +1311867196.067754 rgb/1311867196.067754.png 1311867196.079311 depth/1311867196.079311.png +1311867196.099654 rgb/1311867196.099654.png 1311867196.111398 depth/1311867196.111398.png +1311867196.131796 rgb/1311867196.131796.png 1311867196.147329 depth/1311867196.147329.png +1311867196.167747 rgb/1311867196.167747.png 1311867196.181177 depth/1311867196.181177.png +1311867196.199711 rgb/1311867196.199711.png 1311867196.211495 depth/1311867196.211495.png +1311867196.231920 rgb/1311867196.231920.png 1311867196.246260 depth/1311867196.246260.png +1311867196.267924 rgb/1311867196.267924.png 1311867196.280057 depth/1311867196.280057.png +1311867196.299732 rgb/1311867196.299732.png 1311867196.311160 depth/1311867196.311160.png +1311867196.331833 rgb/1311867196.331833.png 1311867196.348473 depth/1311867196.348473.png +1311867196.368729 rgb/1311867196.368729.png 1311867196.384267 depth/1311867196.384267.png +1311867196.399739 rgb/1311867196.399739.png 1311867196.410755 depth/1311867196.410755.png +1311867196.432020 rgb/1311867196.432020.png 1311867196.446315 depth/1311867196.446315.png +1311867196.467800 rgb/1311867196.467800.png 1311867196.479832 depth/1311867196.479832.png +1311867196.499768 rgb/1311867196.499768.png 1311867196.511347 depth/1311867196.511347.png +1311867196.531926 rgb/1311867196.531926.png 1311867196.546842 depth/1311867196.546842.png +1311867196.567767 rgb/1311867196.567767.png 1311867196.579555 depth/1311867196.579555.png +1311867196.599713 rgb/1311867196.599713.png 1311867196.610893 depth/1311867196.610893.png +1311867196.667737 rgb/1311867196.667737.png 1311867196.680510 depth/1311867196.680510.png +1311867196.699700 rgb/1311867196.699700.png 1311867196.711210 depth/1311867196.711210.png +1311867196.731760 rgb/1311867196.731760.png 1311867196.746490 depth/1311867196.746490.png +1311867196.767707 rgb/1311867196.767707.png 1311867196.778375 depth/1311867196.778375.png +1311867196.799736 rgb/1311867196.799736.png 1311867196.810918 depth/1311867196.810918.png +1311867196.831867 rgb/1311867196.831867.png 1311867196.848875 depth/1311867196.848875.png +1311867196.867749 rgb/1311867196.867749.png 1311867196.882175 depth/1311867196.882175.png +1311867196.899715 rgb/1311867196.899715.png 1311867196.911570 depth/1311867196.911570.png +1311867196.931975 rgb/1311867196.931975.png 1311867196.948244 depth/1311867196.948244.png +1311867196.967911 rgb/1311867196.967911.png 1311867196.980988 depth/1311867196.980988.png +1311867196.999866 rgb/1311867196.999866.png 1311867197.015489 depth/1311867197.015489.png +1311867197.031979 rgb/1311867197.031979.png 1311867197.049068 depth/1311867197.049068.png +1311867197.067817 rgb/1311867197.067817.png 1311867197.080648 depth/1311867197.080648.png +1311867197.099836 rgb/1311867197.099836.png 1311867197.114811 depth/1311867197.114811.png +1311867197.131870 rgb/1311867197.131870.png 1311867197.146843 depth/1311867197.146843.png +1311867197.167713 rgb/1311867197.167713.png 1311867197.179243 depth/1311867197.179243.png +1311867197.199776 rgb/1311867197.199776.png 1311867197.214362 depth/1311867197.214362.png +1311867197.231928 rgb/1311867197.231928.png 1311867197.245929 depth/1311867197.245929.png +1311867197.267919 rgb/1311867197.267919.png 1311867197.279996 depth/1311867197.279996.png +1311867197.299810 rgb/1311867197.299810.png 1311867197.315726 depth/1311867197.315726.png +1311867197.332018 rgb/1311867197.332018.png 1311867197.346871 depth/1311867197.346871.png +1311867197.367855 rgb/1311867197.367855.png 1311867197.378402 depth/1311867197.378402.png +1311867197.399882 rgb/1311867197.399882.png 1311867197.415510 depth/1311867197.415510.png +1311867197.431956 rgb/1311867197.431956.png 1311867197.447888 depth/1311867197.447888.png +1311867197.467991 rgb/1311867197.467991.png 1311867197.479318 depth/1311867197.479318.png +1311867197.499995 rgb/1311867197.499995.png 1311867197.515076 depth/1311867197.515076.png +1311867197.531882 rgb/1311867197.531882.png 1311867197.546926 depth/1311867197.546926.png +1311867197.567869 rgb/1311867197.567869.png 1311867197.580275 depth/1311867197.580275.png +1311867197.599910 rgb/1311867197.599910.png 1311867197.615275 depth/1311867197.615275.png +1311867197.631963 rgb/1311867197.631963.png 1311867197.647044 depth/1311867197.647044.png +1311867197.667929 rgb/1311867197.667929.png 1311867197.680085 depth/1311867197.680085.png +1311867197.699744 rgb/1311867197.699744.png 1311867197.714329 depth/1311867197.714329.png +1311867197.732004 rgb/1311867197.732004.png 1311867197.746342 depth/1311867197.746342.png +1311867197.767904 rgb/1311867197.767904.png 1311867197.779301 depth/1311867197.779301.png +1311867197.799835 rgb/1311867197.799835.png 1311867197.814675 depth/1311867197.814675.png +1311867197.831987 rgb/1311867197.831987.png 1311867197.846792 depth/1311867197.846792.png +1311867197.867941 rgb/1311867197.867941.png 1311867197.880298 depth/1311867197.880298.png +1311867197.899954 rgb/1311867197.899954.png 1311867197.914861 depth/1311867197.914861.png +1311867197.932046 rgb/1311867197.932046.png 1311867197.947014 depth/1311867197.947014.png +1311867197.967946 rgb/1311867197.967946.png 1311867197.981270 depth/1311867197.981270.png +1311867197.999775 rgb/1311867197.999775.png 1311867198.014547 depth/1311867198.014547.png +1311867198.031819 rgb/1311867198.031819.png 1311867198.046337 depth/1311867198.046337.png +1311867198.067816 rgb/1311867198.067816.png 1311867198.078707 depth/1311867198.078707.png +1311867198.099796 rgb/1311867198.099796.png 1311867198.114377 depth/1311867198.114377.png +1311867198.131829 rgb/1311867198.131829.png 1311867198.146361 depth/1311867198.146361.png +1311867198.167952 rgb/1311867198.167952.png 1311867198.182252 depth/1311867198.182252.png +1311867198.199814 rgb/1311867198.199814.png 1311867198.214499 depth/1311867198.214499.png +1311867198.232003 rgb/1311867198.232003.png 1311867198.246412 depth/1311867198.246412.png +1311867198.267962 rgb/1311867198.267962.png 1311867198.282158 depth/1311867198.282158.png +1311867198.331863 rgb/1311867198.331863.png 1311867198.315912 depth/1311867198.315912.png +1311867198.367970 rgb/1311867198.367970.png 1311867198.382832 depth/1311867198.382832.png +1311867198.431988 rgb/1311867198.431988.png 1311867198.424268 depth/1311867198.424268.png +1311867198.467921 rgb/1311867198.467921.png 1311867198.449786 depth/1311867198.449786.png +1311867198.500075 rgb/1311867198.500075.png 1311867198.485622 depth/1311867198.485622.png +1311867198.532125 rgb/1311867198.532125.png 1311867198.519034 depth/1311867198.519034.png +1311867198.567990 rgb/1311867198.567990.png 1311867198.582424 depth/1311867198.582424.png +1311867198.599951 rgb/1311867198.599951.png 1311867198.614749 depth/1311867198.614749.png +1311867198.631966 rgb/1311867198.631966.png 1311867198.648201 depth/1311867198.648201.png +1311867198.668073 rgb/1311867198.668073.png 1311867198.682754 depth/1311867198.682754.png +1311867198.699844 rgb/1311867198.699844.png 1311867198.714652 depth/1311867198.714652.png +1311867198.731874 rgb/1311867198.731874.png 1311867198.746770 depth/1311867198.746770.png +1311867198.767911 rgb/1311867198.767911.png 1311867198.784270 depth/1311867198.784270.png +1311867198.799839 rgb/1311867198.799839.png 1311867198.814942 depth/1311867198.814942.png +1311867198.831953 rgb/1311867198.831953.png 1311867198.846401 depth/1311867198.846401.png +1311867198.867891 rgb/1311867198.867891.png 1311867198.884537 depth/1311867198.884537.png +1311867198.899855 rgb/1311867198.899855.png 1311867198.914793 depth/1311867198.914793.png +1311867198.931881 rgb/1311867198.931881.png 1311867198.946518 depth/1311867198.946518.png +1311867198.968077 rgb/1311867198.968077.png 1311867198.983933 depth/1311867198.983933.png +1311867199.000050 rgb/1311867199.000050.png 1311867199.014873 depth/1311867199.014873.png +1311867199.031843 rgb/1311867199.031843.png 1311867199.046801 depth/1311867199.046801.png +1311867199.099860 rgb/1311867199.099860.png 1311867199.084932 depth/1311867199.084932.png +1311867199.132002 rgb/1311867199.132002.png 1311867199.146542 depth/1311867199.146542.png +1311867199.167891 rgb/1311867199.167891.png 1311867199.182366 depth/1311867199.182366.png +1311867199.200126 rgb/1311867199.200126.png 1311867199.214668 depth/1311867199.214668.png +1311867199.234099 rgb/1311867199.234099.png 1311867199.246775 depth/1311867199.246775.png +1311867199.267942 rgb/1311867199.267942.png 1311867199.283359 depth/1311867199.283359.png +1311867199.300030 rgb/1311867199.300030.png 1311867199.315913 depth/1311867199.315913.png +1311867199.331880 rgb/1311867199.331880.png 1311867199.346521 depth/1311867199.346521.png +1311867199.368141 rgb/1311867199.368141.png 1311867199.382905 depth/1311867199.382905.png +1311867199.399920 rgb/1311867199.399920.png 1311867199.414759 depth/1311867199.414759.png +1311867199.432048 rgb/1311867199.432048.png 1311867199.451291 depth/1311867199.451291.png +1311867199.467972 rgb/1311867199.467972.png 1311867199.483736 depth/1311867199.483736.png +1311867199.500181 rgb/1311867199.500181.png 1311867199.515020 depth/1311867199.515020.png +1311867199.568266 rgb/1311867199.568266.png 1311867199.554406 depth/1311867199.554406.png +1311867199.600399 rgb/1311867199.600399.png 1311867199.615831 depth/1311867199.615831.png +1311867199.668054 rgb/1311867199.668054.png 1311867199.653846 depth/1311867199.653846.png +1311867199.699941 rgb/1311867199.699941.png 1311867199.714676 depth/1311867199.714676.png +1311867199.732005 rgb/1311867199.732005.png 1311867199.751154 depth/1311867199.751154.png +1311867199.768069 rgb/1311867199.768069.png 1311867199.782602 depth/1311867199.782602.png +1311867199.800056 rgb/1311867199.800056.png 1311867199.815015 depth/1311867199.815015.png +1311867199.832480 rgb/1311867199.832480.png 1311867199.851905 depth/1311867199.851905.png +1311867199.867939 rgb/1311867199.867939.png 1311867199.883961 depth/1311867199.883961.png +1311867199.899922 rgb/1311867199.899922.png 1311867199.914816 depth/1311867199.914816.png +1311867199.932206 rgb/1311867199.932206.png 1311867199.952071 depth/1311867199.952071.png +1311867199.967970 rgb/1311867199.967970.png 1311867199.982841 depth/1311867199.982841.png +1311867200.000052 rgb/1311867200.000052.png 1311867200.014403 depth/1311867200.014403.png +1311867200.068006 rgb/1311867200.068006.png 1311867200.053964 depth/1311867200.053964.png +1311867200.100058 rgb/1311867200.100058.png 1311867200.083033 depth/1311867200.083033.png +1311867200.132173 rgb/1311867200.132173.png 1311867200.117447 depth/1311867200.117447.png +1311867200.168054 rgb/1311867200.168054.png 1311867200.151700 depth/1311867200.151700.png +1311867200.200062 rgb/1311867200.200062.png 1311867200.185322 depth/1311867200.185322.png +1311867200.232126 rgb/1311867200.232126.png 1311867200.217906 depth/1311867200.217906.png +1311867200.268192 rgb/1311867200.268192.png 1311867200.282543 depth/1311867200.282543.png +1311867200.300066 rgb/1311867200.300066.png 1311867200.314888 depth/1311867200.314888.png +1311867200.332117 rgb/1311867200.332117.png 1311867200.351499 depth/1311867200.351499.png +1311867200.368163 rgb/1311867200.368163.png 1311867200.383776 depth/1311867200.383776.png +1311867200.432114 rgb/1311867200.432114.png 1311867200.416280 depth/1311867200.416280.png +1311867200.468132 rgb/1311867200.468132.png 1311867200.452249 depth/1311867200.452249.png +1311867200.500090 rgb/1311867200.500090.png 1311867200.514392 depth/1311867200.514392.png +1311867200.532161 rgb/1311867200.532161.png 1311867200.550503 depth/1311867200.550503.png +1311867200.568212 rgb/1311867200.568212.png 1311867200.583222 depth/1311867200.583222.png +1311867200.600091 rgb/1311867200.600091.png 1311867200.614561 depth/1311867200.614561.png +1311867200.668204 rgb/1311867200.668204.png 1311867200.650478 depth/1311867200.650478.png +1311867200.700120 rgb/1311867200.700120.png 1311867200.685128 depth/1311867200.685128.png +1311867200.732170 rgb/1311867200.732170.png 1311867200.718972 depth/1311867200.718972.png +1311867200.768079 rgb/1311867200.768079.png 1311867200.783293 depth/1311867200.783293.png +1311867200.832137 rgb/1311867200.832137.png 1311867200.818107 depth/1311867200.818107.png +1311867200.868158 rgb/1311867200.868158.png 1311867200.850150 depth/1311867200.850150.png +1311867200.899995 rgb/1311867200.899995.png 1311867200.884537 depth/1311867200.884537.png +1311867200.932029 rgb/1311867200.932029.png 1311867200.919493 depth/1311867200.919493.png +1311867200.968154 rgb/1311867200.968154.png 1311867200.951268 depth/1311867200.951268.png +1311867201.000062 rgb/1311867201.000062.png 1311867200.985601 depth/1311867200.985601.png +1311867201.032193 rgb/1311867201.032193.png 1311867201.018440 depth/1311867201.018440.png +1311867201.067956 rgb/1311867201.067956.png 1311867201.055518 depth/1311867201.055518.png +1311867201.100217 rgb/1311867201.100217.png 1311867201.082543 depth/1311867201.082543.png +1311867201.132242 rgb/1311867201.132242.png 1311867201.119345 depth/1311867201.119345.png +1311867201.168191 rgb/1311867201.168191.png 1311867201.183016 depth/1311867201.183016.png +1311867201.232056 rgb/1311867201.232056.png 1311867201.219653 depth/1311867201.219653.png +1311867201.269490 rgb/1311867201.269490.png 1311867201.282410 depth/1311867201.282410.png +1311867201.332276 rgb/1311867201.332276.png 1311867201.318054 depth/1311867201.318054.png +1311867201.368233 rgb/1311867201.368233.png 1311867201.352220 depth/1311867201.352220.png +1311867201.400227 rgb/1311867201.400227.png 1311867201.384279 depth/1311867201.384279.png +1311867201.432761 rgb/1311867201.432761.png 1311867201.419876 depth/1311867201.419876.png +1311867201.468080 rgb/1311867201.468080.png 1311867201.455858 depth/1311867201.455858.png +1311867201.500087 rgb/1311867201.500087.png 1311867201.485311 depth/1311867201.485311.png +1311867201.532195 rgb/1311867201.532195.png 1311867201.519869 depth/1311867201.519869.png +1311867201.568143 rgb/1311867201.568143.png 1311867201.552774 depth/1311867201.552774.png +1311867201.600103 rgb/1311867201.600103.png 1311867201.584022 depth/1311867201.584022.png +1311867201.632068 rgb/1311867201.632068.png 1311867201.619705 depth/1311867201.619705.png +1311867201.668050 rgb/1311867201.668050.png 1311867201.683945 depth/1311867201.683945.png +1311867201.732200 rgb/1311867201.732200.png 1311867201.718901 depth/1311867201.718901.png +1311867201.768201 rgb/1311867201.768201.png 1311867201.750729 depth/1311867201.750729.png +1311867201.800210 rgb/1311867201.800210.png 1311867201.785805 depth/1311867201.785805.png +1311867201.832156 rgb/1311867201.832156.png 1311867201.819018 depth/1311867201.819018.png +1311867201.868219 rgb/1311867201.868219.png 1311867201.850574 depth/1311867201.850574.png +1311867201.900077 rgb/1311867201.900077.png 1311867201.886285 depth/1311867201.886285.png +1311867201.932262 rgb/1311867201.932262.png 1311867201.919573 depth/1311867201.919573.png +1311867201.968172 rgb/1311867201.968172.png 1311867201.951652 depth/1311867201.951652.png +1311867202.000190 rgb/1311867202.000190.png 1311867201.989460 depth/1311867201.989460.png +1311867202.032239 rgb/1311867202.032239.png 1311867202.018488 depth/1311867202.018488.png +1311867202.068152 rgb/1311867202.068152.png 1311867202.050736 depth/1311867202.050736.png +1311867202.100315 rgb/1311867202.100315.png 1311867202.086635 depth/1311867202.086635.png +1311867202.132409 rgb/1311867202.132409.png 1311867202.118592 depth/1311867202.118592.png +1311867202.168279 rgb/1311867202.168279.png 1311867202.151662 depth/1311867202.151662.png +1311867202.200125 rgb/1311867202.200125.png 1311867202.186626 depth/1311867202.186626.png +1311867202.232375 rgb/1311867202.232375.png 1311867202.219127 depth/1311867202.219127.png +1311867202.268101 rgb/1311867202.268101.png 1311867202.251322 depth/1311867202.251322.png +1311867202.300107 rgb/1311867202.300107.png 1311867202.286828 depth/1311867202.286828.png +1311867202.332365 rgb/1311867202.332365.png 1311867202.319988 depth/1311867202.319988.png +1311867202.368310 rgb/1311867202.368310.png 1311867202.352390 depth/1311867202.352390.png +1311867202.400292 rgb/1311867202.400292.png 1311867202.388363 depth/1311867202.388363.png +1311867202.432186 rgb/1311867202.432186.png 1311867202.419639 depth/1311867202.419639.png +1311867202.468118 rgb/1311867202.468118.png 1311867202.452943 depth/1311867202.452943.png +1311867202.500244 rgb/1311867202.500244.png 1311867202.487571 depth/1311867202.487571.png +1311867202.532280 rgb/1311867202.532280.png 1311867202.520645 depth/1311867202.520645.png +1311867202.568183 rgb/1311867202.568183.png 1311867202.550894 depth/1311867202.550894.png +1311867202.600241 rgb/1311867202.600241.png 1311867202.586495 depth/1311867202.586495.png +1311867202.632409 rgb/1311867202.632409.png 1311867202.618503 depth/1311867202.618503.png +1311867202.668254 rgb/1311867202.668254.png 1311867202.651445 depth/1311867202.651445.png +1311867202.700291 rgb/1311867202.700291.png 1311867202.686656 depth/1311867202.686656.png +1311867202.732284 rgb/1311867202.732284.png 1311867202.718536 depth/1311867202.718536.png +1311867202.768106 rgb/1311867202.768106.png 1311867202.750735 depth/1311867202.750735.png +1311867202.800215 rgb/1311867202.800215.png 1311867202.789717 depth/1311867202.789717.png +1311867202.832371 rgb/1311867202.832371.png 1311867202.819000 depth/1311867202.819000.png +1311867202.868186 rgb/1311867202.868186.png 1311867202.852758 depth/1311867202.852758.png +1311867202.900343 rgb/1311867202.900343.png 1311867202.887322 depth/1311867202.887322.png +1311867202.932160 rgb/1311867202.932160.png 1311867202.919988 depth/1311867202.919988.png +1311867202.968198 rgb/1311867202.968198.png 1311867202.952569 depth/1311867202.952569.png +1311867203.000234 rgb/1311867203.000234.png 1311867202.986871 depth/1311867202.986871.png +1311867203.032284 rgb/1311867203.032284.png 1311867203.020202 depth/1311867203.020202.png +1311867203.068187 rgb/1311867203.068187.png 1311867203.056085 depth/1311867203.056085.png +1311867203.100350 rgb/1311867203.100350.png 1311867203.086578 depth/1311867203.086578.png +1311867203.132443 rgb/1311867203.132443.png 1311867203.118993 depth/1311867203.118993.png +1311867203.168210 rgb/1311867203.168210.png 1311867203.154982 depth/1311867203.154982.png +1311867203.200286 rgb/1311867203.200286.png 1311867203.187794 depth/1311867203.187794.png +1311867203.232211 rgb/1311867203.232211.png 1311867203.218591 depth/1311867203.218591.png +1311867203.268183 rgb/1311867203.268183.png 1311867203.255203 depth/1311867203.255203.png +1311867203.300206 rgb/1311867203.300206.png 1311867203.286480 depth/1311867203.286480.png +1311867203.332226 rgb/1311867203.332226.png 1311867203.319467 depth/1311867203.319467.png +1311867203.368129 rgb/1311867203.368129.png 1311867203.354746 depth/1311867203.354746.png +1311867203.400200 rgb/1311867203.400200.png 1311867203.386560 depth/1311867203.386560.png +1311867203.432255 rgb/1311867203.432255.png 1311867203.418361 depth/1311867203.418361.png +1311867203.468205 rgb/1311867203.468205.png 1311867203.454512 depth/1311867203.454512.png +1311867203.500494 rgb/1311867203.500494.png 1311867203.486444 depth/1311867203.486444.png +1311867203.532247 rgb/1311867203.532247.png 1311867203.518554 depth/1311867203.518554.png +1311867203.568287 rgb/1311867203.568287.png 1311867203.556026 depth/1311867203.556026.png +1311867203.600247 rgb/1311867203.600247.png 1311867203.587655 depth/1311867203.587655.png +1311867203.632381 rgb/1311867203.632381.png 1311867203.619198 depth/1311867203.619198.png +1311867203.668366 rgb/1311867203.668366.png 1311867203.655772 depth/1311867203.655772.png +1311867203.700467 rgb/1311867203.700467.png 1311867203.686675 depth/1311867203.686675.png +1311867203.732263 rgb/1311867203.732263.png 1311867203.719526 depth/1311867203.719526.png +1311867203.768142 rgb/1311867203.768142.png 1311867203.756642 depth/1311867203.756642.png +1311867203.800188 rgb/1311867203.800188.png 1311867203.786723 depth/1311867203.786723.png +1311867203.832438 rgb/1311867203.832438.png 1311867203.819386 depth/1311867203.819386.png +1311867203.868154 rgb/1311867203.868154.png 1311867203.857286 depth/1311867203.857286.png +1311867203.900206 rgb/1311867203.900206.png 1311867203.889189 depth/1311867203.889189.png +1311867203.932460 rgb/1311867203.932460.png 1311867203.918802 depth/1311867203.918802.png +1311867203.968287 rgb/1311867203.968287.png 1311867203.955349 depth/1311867203.955349.png +1311867204.000337 rgb/1311867204.000337.png 1311867203.986637 depth/1311867203.986637.png +1311867204.032369 rgb/1311867204.032369.png 1311867204.019985 depth/1311867204.019985.png +1311867204.068206 rgb/1311867204.068206.png 1311867204.055151 depth/1311867204.055151.png +1311867204.100343 rgb/1311867204.100343.png 1311867204.086751 depth/1311867204.086751.png +1311867204.132295 rgb/1311867204.132295.png 1311867204.119153 depth/1311867204.119153.png +1311867204.168262 rgb/1311867204.168262.png 1311867204.155577 depth/1311867204.155577.png +1311867204.200305 rgb/1311867204.200305.png 1311867204.187653 depth/1311867204.187653.png +1311867204.232436 rgb/1311867204.232436.png 1311867204.218777 depth/1311867204.218777.png +1311867204.268181 rgb/1311867204.268181.png 1311867204.256644 depth/1311867204.256644.png +1311867204.300302 rgb/1311867204.300302.png 1311867204.286714 depth/1311867204.286714.png +1311867204.332519 rgb/1311867204.332519.png 1311867204.320454 depth/1311867204.320454.png +1311867204.368375 rgb/1311867204.368375.png 1311867204.362574 depth/1311867204.362574.png +1311867204.400282 rgb/1311867204.400282.png 1311867204.386960 depth/1311867204.386960.png +1311867204.432434 rgb/1311867204.432434.png 1311867204.424097 depth/1311867204.424097.png +1311867204.468296 rgb/1311867204.468296.png 1311867204.454995 depth/1311867204.454995.png +1311867204.500277 rgb/1311867204.500277.png 1311867204.487275 depth/1311867204.487275.png +1311867204.532479 rgb/1311867204.532479.png 1311867204.523722 depth/1311867204.523722.png +1311867204.568211 rgb/1311867204.568211.png 1311867204.558186 depth/1311867204.558186.png +1311867204.600264 rgb/1311867204.600264.png 1311867204.587847 depth/1311867204.587847.png +1311867204.632418 rgb/1311867204.632418.png 1311867204.624153 depth/1311867204.624153.png +1311867204.668452 rgb/1311867204.668452.png 1311867204.654182 depth/1311867204.654182.png +1311867204.700261 rgb/1311867204.700261.png 1311867204.687154 depth/1311867204.687154.png +1311867204.732293 rgb/1311867204.732293.png 1311867204.722569 depth/1311867204.722569.png +1311867204.768312 rgb/1311867204.768312.png 1311867204.753951 depth/1311867204.753951.png +1311867204.800434 rgb/1311867204.800434.png 1311867204.787872 depth/1311867204.787872.png +1311867204.832496 rgb/1311867204.832496.png 1311867204.822720 depth/1311867204.822720.png +1311867204.868246 rgb/1311867204.868246.png 1311867204.854267 depth/1311867204.854267.png +1311867204.900224 rgb/1311867204.900224.png 1311867204.886496 depth/1311867204.886496.png +1311867204.936363 rgb/1311867204.936363.png 1311867204.922022 depth/1311867204.922022.png +1311867204.968219 rgb/1311867204.968219.png 1311867204.954292 depth/1311867204.954292.png +1311867205.000335 rgb/1311867205.000335.png 1311867204.986600 depth/1311867204.986600.png +1311867205.036326 rgb/1311867205.036326.png 1311867205.022724 depth/1311867205.022724.png +1311867205.068637 rgb/1311867205.068637.png 1311867205.055081 depth/1311867205.055081.png +1311867205.100765 rgb/1311867205.100765.png 1311867205.088100 depth/1311867205.088100.png +1311867205.136301 rgb/1311867205.136301.png 1311867205.123245 depth/1311867205.123245.png +1311867205.168290 rgb/1311867205.168290.png 1311867205.154532 depth/1311867205.154532.png +1311867205.200371 rgb/1311867205.200371.png 1311867205.186351 depth/1311867205.186351.png +1311867205.236444 rgb/1311867205.236444.png 1311867205.222313 depth/1311867205.222313.png +1311867205.268392 rgb/1311867205.268392.png 1311867205.254185 depth/1311867205.254185.png +1311867205.300458 rgb/1311867205.300458.png 1311867205.288050 depth/1311867205.288050.png +1311867205.336288 rgb/1311867205.336288.png 1311867205.321888 depth/1311867205.321888.png +1311867205.368439 rgb/1311867205.368439.png 1311867205.354290 depth/1311867205.354290.png +1311867205.400476 rgb/1311867205.400476.png 1311867205.386278 depth/1311867205.386278.png +1311867205.436290 rgb/1311867205.436290.png 1311867205.422565 depth/1311867205.422565.png +1311867205.468361 rgb/1311867205.468361.png 1311867205.454042 depth/1311867205.454042.png +1311867205.500259 rgb/1311867205.500259.png 1311867205.486512 depth/1311867205.486512.png +1311867205.536285 rgb/1311867205.536285.png 1311867205.523034 depth/1311867205.523034.png +1311867205.568369 rgb/1311867205.568369.png 1311867205.554290 depth/1311867205.554290.png +1311867205.600318 rgb/1311867205.600318.png 1311867205.586684 depth/1311867205.586684.png +1311867205.636378 rgb/1311867205.636378.png 1311867205.622618 depth/1311867205.622618.png +1311867205.668640 rgb/1311867205.668640.png 1311867205.655598 depth/1311867205.655598.png +1311867205.700293 rgb/1311867205.700293.png 1311867205.690296 depth/1311867205.690296.png +1311867205.736482 rgb/1311867205.736482.png 1311867205.722206 depth/1311867205.722206.png +1311867205.768331 rgb/1311867205.768331.png 1311867205.754835 depth/1311867205.754835.png +1311867205.800294 rgb/1311867205.800294.png 1311867205.790638 depth/1311867205.790638.png +1311867205.836370 rgb/1311867205.836370.png 1311867205.823211 depth/1311867205.823211.png +1311867205.868513 rgb/1311867205.868513.png 1311867205.855476 depth/1311867205.855476.png +1311867205.900317 rgb/1311867205.900317.png 1311867205.890588 depth/1311867205.890588.png +1311867205.936313 rgb/1311867205.936313.png 1311867205.922302 depth/1311867205.922302.png +1311867205.968515 rgb/1311867205.968515.png 1311867205.954494 depth/1311867205.954494.png +1311867206.000654 rgb/1311867206.000654.png 1311867205.990585 depth/1311867205.990585.png +1311867206.036736 rgb/1311867206.036736.png 1311867206.025985 depth/1311867206.025985.png +1311867206.068413 rgb/1311867206.068413.png 1311867206.060425 depth/1311867206.060425.png +1311867206.100418 rgb/1311867206.100418.png 1311867206.090329 depth/1311867206.090329.png +1311867206.136422 rgb/1311867206.136422.png 1311867206.122754 depth/1311867206.122754.png +1311867206.168280 rgb/1311867206.168280.png 1311867206.154613 depth/1311867206.154613.png +1311867206.200431 rgb/1311867206.200431.png 1311867206.190380 depth/1311867206.190380.png +1311867206.236354 rgb/1311867206.236354.png 1311867206.223956 depth/1311867206.223956.png +1311867206.268562 rgb/1311867206.268562.png 1311867206.255358 depth/1311867206.255358.png +1311867206.300429 rgb/1311867206.300429.png 1311867206.290477 depth/1311867206.290477.png +1311867206.336618 rgb/1311867206.336618.png 1311867206.322204 depth/1311867206.322204.png +1311867206.368476 rgb/1311867206.368476.png 1311867206.354253 depth/1311867206.354253.png +1311867206.400411 rgb/1311867206.400411.png 1311867206.390007 depth/1311867206.390007.png +1311867206.436540 rgb/1311867206.436540.png 1311867206.422026 depth/1311867206.422026.png +1311867206.468475 rgb/1311867206.468475.png 1311867206.454231 depth/1311867206.454231.png +1311867206.500567 rgb/1311867206.500567.png 1311867206.490538 depth/1311867206.490538.png +1311867206.536578 rgb/1311867206.536578.png 1311867206.525033 depth/1311867206.525033.png +1311867206.568318 rgb/1311867206.568318.png 1311867206.553930 depth/1311867206.553930.png +1311867206.600453 rgb/1311867206.600453.png 1311867206.592113 depth/1311867206.592113.png +1311867206.636480 rgb/1311867206.636480.png 1311867206.622636 depth/1311867206.622636.png +1311867206.668513 rgb/1311867206.668513.png 1311867206.656675 depth/1311867206.656675.png +1311867206.700560 rgb/1311867206.700560.png 1311867206.694521 depth/1311867206.694521.png +1311867206.736376 rgb/1311867206.736376.png 1311867206.724848 depth/1311867206.724848.png +1311867206.768348 rgb/1311867206.768348.png 1311867206.758797 depth/1311867206.758797.png +1311867206.800520 rgb/1311867206.800520.png 1311867206.790284 depth/1311867206.790284.png +1311867206.836416 rgb/1311867206.836416.png 1311867206.822977 depth/1311867206.822977.png +1311867206.868563 rgb/1311867206.868563.png 1311867206.860545 depth/1311867206.860545.png +1311867206.900569 rgb/1311867206.900569.png 1311867206.890777 depth/1311867206.890777.png +1311867206.936441 rgb/1311867206.936441.png 1311867206.922502 depth/1311867206.922502.png +1311867206.968607 rgb/1311867206.968607.png 1311867206.959248 depth/1311867206.959248.png +1311867207.000644 rgb/1311867207.000644.png 1311867206.994868 depth/1311867206.994868.png +1311867207.036586 rgb/1311867207.036586.png 1311867207.024755 depth/1311867207.024755.png +1311867207.068407 rgb/1311867207.068407.png 1311867207.059726 depth/1311867207.059726.png +1311867207.100546 rgb/1311867207.100546.png 1311867207.094280 depth/1311867207.094280.png +1311867207.136473 rgb/1311867207.136473.png 1311867207.122914 depth/1311867207.122914.png +1311867207.168707 rgb/1311867207.168707.png 1311867207.158355 depth/1311867207.158355.png +1311867207.200654 rgb/1311867207.200654.png 1311867207.190492 depth/1311867207.190492.png +1311867207.236587 rgb/1311867207.236587.png 1311867207.222618 depth/1311867207.222618.png +1311867207.268617 rgb/1311867207.268617.png 1311867207.260483 depth/1311867207.260483.png +1311867207.300500 rgb/1311867207.300500.png 1311867207.292690 depth/1311867207.292690.png +1311867207.336652 rgb/1311867207.336652.png 1311867207.323524 depth/1311867207.323524.png +1311867207.368579 rgb/1311867207.368579.png 1311867207.359748 depth/1311867207.359748.png +1311867207.400698 rgb/1311867207.400698.png 1311867207.390131 depth/1311867207.390131.png +1311867207.436580 rgb/1311867207.436580.png 1311867207.422784 depth/1311867207.422784.png +1311867207.468647 rgb/1311867207.468647.png 1311867207.458679 depth/1311867207.458679.png +1311867207.500601 rgb/1311867207.500601.png 1311867207.492764 depth/1311867207.492764.png +1311867207.536508 rgb/1311867207.536508.png 1311867207.523730 depth/1311867207.523730.png +1311867207.568706 rgb/1311867207.568706.png 1311867207.559841 depth/1311867207.559841.png +1311867207.600587 rgb/1311867207.600587.png 1311867207.594480 depth/1311867207.594480.png +1311867207.636491 rgb/1311867207.636491.png 1311867207.625922 depth/1311867207.625922.png +1311867207.668773 rgb/1311867207.668773.png 1311867207.659294 depth/1311867207.659294.png +1311867207.700562 rgb/1311867207.700562.png 1311867207.692309 depth/1311867207.692309.png +1311867207.736501 rgb/1311867207.736501.png 1311867207.723864 depth/1311867207.723864.png +1311867207.768609 rgb/1311867207.768609.png 1311867207.758805 depth/1311867207.758805.png +1311867207.800991 rgb/1311867207.800991.png 1311867207.792192 depth/1311867207.792192.png +1311867207.836554 rgb/1311867207.836554.png 1311867207.823776 depth/1311867207.823776.png +1311867207.868773 rgb/1311867207.868773.png 1311867207.860848 depth/1311867207.860848.png +1311867207.900900 rgb/1311867207.900900.png 1311867207.893709 depth/1311867207.893709.png +1311867207.936534 rgb/1311867207.936534.png 1311867207.924414 depth/1311867207.924414.png +1311867207.968490 rgb/1311867207.968490.png 1311867207.961497 depth/1311867207.961497.png +1311867208.000665 rgb/1311867208.000665.png 1311867207.991413 depth/1311867207.991413.png +1311867208.036765 rgb/1311867208.036765.png 1311867208.024850 depth/1311867208.024850.png +1311867208.069925 rgb/1311867208.069925.png 1311867208.061850 depth/1311867208.061850.png +1311867208.101134 rgb/1311867208.101134.png 1311867208.092462 depth/1311867208.092462.png +1311867208.136633 rgb/1311867208.136633.png 1311867208.127656 depth/1311867208.127656.png +1311867208.168683 rgb/1311867208.168683.png 1311867208.159607 depth/1311867208.159607.png +1311867208.200521 rgb/1311867208.200521.png 1311867208.190501 depth/1311867208.190501.png +1311867208.236561 rgb/1311867208.236561.png 1311867208.228085 depth/1311867208.228085.png +1311867208.268440 rgb/1311867208.268440.png 1311867208.258179 depth/1311867208.258179.png +1311867208.300597 rgb/1311867208.300597.png 1311867208.290199 depth/1311867208.290199.png +1311867208.336528 rgb/1311867208.336528.png 1311867208.327021 depth/1311867208.327021.png +1311867208.368511 rgb/1311867208.368511.png 1311867208.358097 depth/1311867208.358097.png +1311867208.400592 rgb/1311867208.400592.png 1311867208.391056 depth/1311867208.391056.png +1311867208.436460 rgb/1311867208.436460.png 1311867208.426023 depth/1311867208.426023.png +1311867208.468664 rgb/1311867208.468664.png 1311867208.457742 depth/1311867208.457742.png +1311867208.500564 rgb/1311867208.500564.png 1311867208.490765 depth/1311867208.490765.png +1311867208.536522 rgb/1311867208.536522.png 1311867208.525741 depth/1311867208.525741.png +1311867208.568644 rgb/1311867208.568644.png 1311867208.558380 depth/1311867208.558380.png +1311867208.600595 rgb/1311867208.600595.png 1311867208.590450 depth/1311867208.590450.png +1311867208.636445 rgb/1311867208.636445.png 1311867208.625978 depth/1311867208.625978.png +1311867208.668488 rgb/1311867208.668488.png 1311867208.658208 depth/1311867208.658208.png +1311867208.700606 rgb/1311867208.700606.png 1311867208.691030 depth/1311867208.691030.png +1311867208.736710 rgb/1311867208.736710.png 1311867208.726226 depth/1311867208.726226.png +1311867208.768807 rgb/1311867208.768807.png 1311867208.759101 depth/1311867208.759101.png +1311867208.800641 rgb/1311867208.800641.png 1311867208.790975 depth/1311867208.790975.png +1311867208.836883 rgb/1311867208.836883.png 1311867208.825993 depth/1311867208.825993.png +1311867208.868491 rgb/1311867208.868491.png 1311867208.858819 depth/1311867208.858819.png +1311867208.900811 rgb/1311867208.900811.png 1311867208.891626 depth/1311867208.891626.png +1311867208.936516 rgb/1311867208.936516.png 1311867208.927512 depth/1311867208.927512.png +1311867208.968732 rgb/1311867208.968732.png 1311867208.957776 depth/1311867208.957776.png +1311867209.000767 rgb/1311867209.000767.png 1311867208.991164 depth/1311867208.991164.png +1311867209.036589 rgb/1311867209.036589.png 1311867209.027078 depth/1311867209.027078.png +1311867209.068848 rgb/1311867209.068848.png 1311867209.057957 depth/1311867209.057957.png +1311867209.100837 rgb/1311867209.100837.png 1311867209.090698 depth/1311867209.090698.png +1311867209.145248 rgb/1311867209.145248.png 1311867209.126078 depth/1311867209.126078.png +1311867209.168676 rgb/1311867209.168676.png 1311867209.160062 depth/1311867209.160062.png +1311867209.200608 rgb/1311867209.200608.png 1311867209.191784 depth/1311867209.191784.png +1311867209.236579 rgb/1311867209.236579.png 1311867209.225953 depth/1311867209.225953.png +1311867209.268677 rgb/1311867209.268677.png 1311867209.258006 depth/1311867209.258006.png +1311867209.300548 rgb/1311867209.300548.png 1311867209.290313 depth/1311867209.290313.png +1311867209.336608 rgb/1311867209.336608.png 1311867209.327422 depth/1311867209.327422.png +1311867209.368685 rgb/1311867209.368685.png 1311867209.358104 depth/1311867209.358104.png +1311867209.400674 rgb/1311867209.400674.png 1311867209.393797 depth/1311867209.393797.png +1311867209.436604 rgb/1311867209.436604.png 1311867209.425815 depth/1311867209.425815.png +1311867209.468504 rgb/1311867209.468504.png 1311867209.458133 depth/1311867209.458133.png +1311867209.501113 rgb/1311867209.501113.png 1311867209.494065 depth/1311867209.494065.png +1311867209.536902 rgb/1311867209.536902.png 1311867209.525873 depth/1311867209.525873.png +1311867209.568689 rgb/1311867209.568689.png 1311867209.558070 depth/1311867209.558070.png +1311867209.600759 rgb/1311867209.600759.png 1311867209.593954 depth/1311867209.593954.png +1311867209.636594 rgb/1311867209.636594.png 1311867209.626279 depth/1311867209.626279.png +1311867209.668570 rgb/1311867209.668570.png 1311867209.658202 depth/1311867209.658202.png +1311867209.701272 rgb/1311867209.701272.png 1311867209.696702 depth/1311867209.696702.png +1311867209.736573 rgb/1311867209.736573.png 1311867209.726264 depth/1311867209.726264.png +1311867209.768624 rgb/1311867209.768624.png 1311867209.758346 depth/1311867209.758346.png +1311867209.801498 rgb/1311867209.801498.png 1311867209.795932 depth/1311867209.795932.png +1311867209.836574 rgb/1311867209.836574.png 1311867209.826242 depth/1311867209.826242.png +1311867209.868553 rgb/1311867209.868553.png 1311867209.858896 depth/1311867209.858896.png +1311867209.900669 rgb/1311867209.900669.png 1311867209.894697 depth/1311867209.894697.png +1311867209.936544 rgb/1311867209.936544.png 1311867209.926845 depth/1311867209.926845.png +1311867209.968938 rgb/1311867209.968938.png 1311867209.958821 depth/1311867209.958821.png +1311867210.000704 rgb/1311867210.000704.png 1311867209.994254 depth/1311867209.994254.png +1311867210.036683 rgb/1311867210.036683.png 1311867210.026106 depth/1311867210.026106.png +1311867210.068816 rgb/1311867210.068816.png 1311867210.060359 depth/1311867210.060359.png +1311867210.100607 rgb/1311867210.100607.png 1311867210.094248 depth/1311867210.094248.png +1311867210.136711 rgb/1311867210.136711.png 1311867210.128034 depth/1311867210.128034.png +1311867210.168673 rgb/1311867210.168673.png 1311867210.157824 depth/1311867210.157824.png +1311867210.200662 rgb/1311867210.200662.png 1311867210.194321 depth/1311867210.194321.png +1311867210.236614 rgb/1311867210.236614.png 1311867210.225813 depth/1311867210.225813.png +1311867210.268764 rgb/1311867210.268764.png 1311867210.257977 depth/1311867210.257977.png +1311867210.300692 rgb/1311867210.300692.png 1311867210.295399 depth/1311867210.295399.png +1311867210.336672 rgb/1311867210.336672.png 1311867210.327137 depth/1311867210.327137.png +1311867210.368993 rgb/1311867210.368993.png 1311867210.358242 depth/1311867210.358242.png +1311867210.400741 rgb/1311867210.400741.png 1311867210.393792 depth/1311867210.393792.png +1311867210.436672 rgb/1311867210.436672.png 1311867210.426004 depth/1311867210.426004.png +1311867210.469063 rgb/1311867210.469063.png 1311867210.458171 depth/1311867210.458171.png +1311867210.500649 rgb/1311867210.500649.png 1311867210.494351 depth/1311867210.494351.png +1311867210.536682 rgb/1311867210.536682.png 1311867210.526130 depth/1311867210.526130.png +1311867210.569047 rgb/1311867210.569047.png 1311867210.563473 depth/1311867210.563473.png +1311867210.600859 rgb/1311867210.600859.png 1311867210.594387 depth/1311867210.594387.png +1311867210.636787 rgb/1311867210.636787.png 1311867210.626021 depth/1311867210.626021.png +1311867210.673847 rgb/1311867210.673847.png 1311867210.667571 depth/1311867210.667571.png +1311867210.700721 rgb/1311867210.700721.png 1311867210.695228 depth/1311867210.695228.png +1311867210.736657 rgb/1311867210.736657.png 1311867210.726090 depth/1311867210.726090.png +1311867210.769036 rgb/1311867210.769036.png 1311867210.762092 depth/1311867210.762092.png +1311867210.800700 rgb/1311867210.800700.png 1311867210.794349 depth/1311867210.794349.png +1311867210.836863 rgb/1311867210.836863.png 1311867210.826326 depth/1311867210.826326.png +1311867210.868831 rgb/1311867210.868831.png 1311867210.862398 depth/1311867210.862398.png +1311867210.900724 rgb/1311867210.900724.png 1311867210.894228 depth/1311867210.894228.png +1311867210.936751 rgb/1311867210.936751.png 1311867210.928831 depth/1311867210.928831.png +1311867210.969224 rgb/1311867210.969224.png 1311867210.965348 depth/1311867210.965348.png +1311867211.001198 rgb/1311867211.001198.png 1311867210.994558 depth/1311867210.994558.png +1311867211.036754 rgb/1311867211.036754.png 1311867211.026350 depth/1311867211.026350.png +1311867211.069171 rgb/1311867211.069171.png 1311867211.065157 depth/1311867211.065157.png +1311867211.101339 rgb/1311867211.101339.png 1311867211.094082 depth/1311867211.094082.png +1311867211.136879 rgb/1311867211.136879.png 1311867211.126688 depth/1311867211.126688.png +1311867211.169535 rgb/1311867211.169535.png 1311867211.164699 depth/1311867211.164699.png +1311867211.200759 rgb/1311867211.200759.png 1311867211.194663 depth/1311867211.194663.png +1311867211.236938 rgb/1311867211.236938.png 1311867211.227021 depth/1311867211.227021.png +1311867211.268944 rgb/1311867211.268944.png 1311867211.264560 depth/1311867211.264560.png +1311867211.301073 rgb/1311867211.301073.png 1311867211.295310 depth/1311867211.295310.png +1311867211.336815 rgb/1311867211.336815.png 1311867211.326295 depth/1311867211.326295.png +1311867211.368899 rgb/1311867211.368899.png 1311867211.365329 depth/1311867211.365329.png +1311867211.401155 rgb/1311867211.401155.png 1311867211.394902 depth/1311867211.394902.png +1311867211.436783 rgb/1311867211.436783.png 1311867211.429568 depth/1311867211.429568.png +1311867211.468760 rgb/1311867211.468760.png 1311867211.464506 depth/1311867211.464506.png +1311867211.500750 rgb/1311867211.500750.png 1311867211.494283 depth/1311867211.494283.png +1311867211.536921 rgb/1311867211.536921.png 1311867211.527957 depth/1311867211.527957.png +1311867211.569353 rgb/1311867211.569353.png 1311867211.564670 depth/1311867211.564670.png +1311867211.600936 rgb/1311867211.600936.png 1311867211.596759 depth/1311867211.596759.png +1311867211.636776 rgb/1311867211.636776.png 1311867211.626943 depth/1311867211.626943.png +1311867211.669417 rgb/1311867211.669417.png 1311867211.662028 depth/1311867211.662028.png +1311867211.700795 rgb/1311867211.700795.png 1311867211.694435 depth/1311867211.694435.png +1311867211.736761 rgb/1311867211.736761.png 1311867211.726757 depth/1311867211.726757.png +1311867211.769891 rgb/1311867211.769891.png 1311867211.764210 depth/1311867211.764210.png +1311867211.801052 rgb/1311867211.801052.png 1311867211.794816 depth/1311867211.794816.png +1311867211.838297 rgb/1311867211.838297.png 1311867211.833727 depth/1311867211.833727.png +1311867211.868798 rgb/1311867211.868798.png 1311867211.863093 depth/1311867211.863093.png +1311867211.901152 rgb/1311867211.901152.png 1311867211.896769 depth/1311867211.896769.png +1311867211.937348 rgb/1311867211.937348.png 1311867211.932430 depth/1311867211.932430.png +1311867211.971087 rgb/1311867211.971087.png 1311867211.965324 depth/1311867211.965324.png +1311867212.001054 rgb/1311867212.001054.png 1311867211.997286 depth/1311867211.997286.png +1311867212.037396 rgb/1311867212.037396.png 1311867212.031766 depth/1311867212.031766.png +1311867212.068925 rgb/1311867212.068925.png 1311867212.062152 depth/1311867212.062152.png +1311867212.100836 rgb/1311867212.100836.png 1311867212.095455 depth/1311867212.095455.png +1311867212.137104 rgb/1311867212.137104.png 1311867212.133103 depth/1311867212.133103.png +1311867212.168899 rgb/1311867212.168899.png 1311867212.166849 depth/1311867212.166849.png +1311867212.201292 rgb/1311867212.201292.png 1311867212.194507 depth/1311867212.194507.png +1311867212.236828 rgb/1311867212.236828.png 1311867212.230176 depth/1311867212.230176.png +1311867212.269660 rgb/1311867212.269660.png 1311867212.264719 depth/1311867212.264719.png +1311867212.300798 rgb/1311867212.300798.png 1311867212.294482 depth/1311867212.294482.png +1311867212.336980 rgb/1311867212.336980.png 1311867212.332643 depth/1311867212.332643.png +1311867212.369121 rgb/1311867212.369121.png 1311867212.365364 depth/1311867212.365364.png +1311867212.400874 rgb/1311867212.400874.png 1311867212.395551 depth/1311867212.395551.png +1311867212.437295 rgb/1311867212.437295.png 1311867212.432952 depth/1311867212.432952.png +1311867212.468814 rgb/1311867212.468814.png 1311867212.462264 depth/1311867212.462264.png +1311867212.500920 rgb/1311867212.500920.png 1311867212.494430 depth/1311867212.494430.png +1311867212.536991 rgb/1311867212.536991.png 1311867212.530027 depth/1311867212.530027.png +1311867212.568780 rgb/1311867212.568780.png 1311867212.562597 depth/1311867212.562597.png +1311867212.600775 rgb/1311867212.600775.png 1311867212.594836 depth/1311867212.594836.png +1311867212.636951 rgb/1311867212.636951.png 1311867212.632392 depth/1311867212.632392.png +1311867212.668874 rgb/1311867212.668874.png 1311867212.662983 depth/1311867212.662983.png +1311867212.701018 rgb/1311867212.701018.png 1311867212.694415 depth/1311867212.694415.png +1311867212.736989 rgb/1311867212.736989.png 1311867212.732322 depth/1311867212.732322.png +1311867212.768959 rgb/1311867212.768959.png 1311867212.761895 depth/1311867212.761895.png +1311867212.800808 rgb/1311867212.800808.png 1311867212.795161 depth/1311867212.795161.png +1311867212.837870 rgb/1311867212.837870.png 1311867212.830377 depth/1311867212.830377.png +1311867212.869033 rgb/1311867212.869033.png 1311867212.862524 depth/1311867212.862524.png +1311867212.900811 rgb/1311867212.900811.png 1311867212.894180 depth/1311867212.894180.png +1311867212.936948 rgb/1311867212.936948.png 1311867212.930659 depth/1311867212.930659.png +1311867212.969087 rgb/1311867212.969087.png 1311867212.962158 depth/1311867212.962158.png +1311867213.001064 rgb/1311867213.001064.png 1311867212.997198 depth/1311867212.997198.png +1311867213.036927 rgb/1311867213.036927.png 1311867213.030556 depth/1311867213.030556.png +1311867213.069051 rgb/1311867213.069051.png 1311867213.062233 depth/1311867213.062233.png +1311867213.101068 rgb/1311867213.101068.png 1311867213.098531 depth/1311867213.098531.png +1311867213.137000 rgb/1311867213.137000.png 1311867213.132167 depth/1311867213.132167.png +1311867213.169165 rgb/1311867213.169165.png 1311867213.164233 depth/1311867213.164233.png +1311867213.201431 rgb/1311867213.201431.png 1311867213.198165 depth/1311867213.198165.png +1311867213.236857 rgb/1311867213.236857.png 1311867213.230398 depth/1311867213.230398.png +1311867213.269223 rgb/1311867213.269223.png 1311867213.262134 depth/1311867213.262134.png +1311867213.301416 rgb/1311867213.301416.png 1311867213.298364 depth/1311867213.298364.png +1311867213.336896 rgb/1311867213.336896.png 1311867213.331297 depth/1311867213.331297.png +1311867213.369001 rgb/1311867213.369001.png 1311867213.362207 depth/1311867213.362207.png +1311867213.401378 rgb/1311867213.401378.png 1311867213.398062 depth/1311867213.398062.png +1311867213.437193 rgb/1311867213.437193.png 1311867213.430396 depth/1311867213.430396.png +1311867213.469040 rgb/1311867213.469040.png 1311867213.462063 depth/1311867213.462063.png +1311867213.500997 rgb/1311867213.500997.png 1311867213.498139 depth/1311867213.498139.png +1311867213.536881 rgb/1311867213.536881.png 1311867213.531834 depth/1311867213.531834.png +1311867213.569042 rgb/1311867213.569042.png 1311867213.562132 depth/1311867213.562132.png +1311867213.601011 rgb/1311867213.601011.png 1311867213.598958 depth/1311867213.598958.png +1311867213.636923 rgb/1311867213.636923.png 1311867213.632776 depth/1311867213.632776.png +1311867213.668995 rgb/1311867213.668995.png 1311867213.662325 depth/1311867213.662325.png +1311867213.701300 rgb/1311867213.701300.png 1311867213.698727 depth/1311867213.698727.png +1311867213.737146 rgb/1311867213.737146.png 1311867213.731280 depth/1311867213.731280.png +1311867213.769090 rgb/1311867213.769090.png 1311867213.762316 depth/1311867213.762316.png +1311867213.801664 rgb/1311867213.801664.png 1311867213.798497 depth/1311867213.798497.png +1311867213.837348 rgb/1311867213.837348.png 1311867213.830353 depth/1311867213.830353.png +1311867213.868914 rgb/1311867213.868914.png 1311867213.866938 depth/1311867213.866938.png +1311867213.900969 rgb/1311867213.900969.png 1311867213.898875 depth/1311867213.898875.png +1311867213.937067 rgb/1311867213.937067.png 1311867213.932459 depth/1311867213.932459.png +1311867213.968920 rgb/1311867213.968920.png 1311867213.962551 depth/1311867213.962551.png +1311867214.005161 rgb/1311867214.005161.png 1311867214.001499 depth/1311867214.001499.png +1311867214.037101 rgb/1311867214.037101.png 1311867214.031655 depth/1311867214.031655.png +1311867214.068910 rgb/1311867214.068910.png 1311867214.064003 depth/1311867214.064003.png +1311867214.104861 rgb/1311867214.104861.png 1311867214.098475 depth/1311867214.098475.png +1311867214.138206 rgb/1311867214.138206.png 1311867214.132699 depth/1311867214.132699.png +1311867214.169647 rgb/1311867214.169647.png 1311867214.164380 depth/1311867214.164380.png +1311867214.205217 rgb/1311867214.205217.png 1311867214.201302 depth/1311867214.201302.png +1311867214.239878 rgb/1311867214.239878.png 1311867214.233843 depth/1311867214.233843.png +1311867214.270552 rgb/1311867214.270552.png 1311867214.267490 depth/1311867214.267490.png +1311867214.305762 rgb/1311867214.305762.png 1311867214.300472 depth/1311867214.300472.png +1311867214.337669 rgb/1311867214.337669.png 1311867214.331055 depth/1311867214.331055.png +1311867214.369049 rgb/1311867214.369049.png 1311867214.366367 depth/1311867214.366367.png +1311867214.405033 rgb/1311867214.405033.png 1311867214.398003 depth/1311867214.398003.png +1311867214.437364 rgb/1311867214.437364.png 1311867214.433221 depth/1311867214.433221.png +1311867214.469778 rgb/1311867214.469778.png 1311867214.469818 depth/1311867214.469818.png +1311867214.505939 rgb/1311867214.505939.png 1311867214.500862 depth/1311867214.500862.png +1311867214.537369 rgb/1311867214.537369.png 1311867214.532909 depth/1311867214.532909.png +1311867214.569142 rgb/1311867214.569142.png 1311867214.566238 depth/1311867214.566238.png +1311867214.604864 rgb/1311867214.604864.png 1311867214.598216 depth/1311867214.598216.png +1311867214.636989 rgb/1311867214.636989.png 1311867214.630473 depth/1311867214.630473.png +1311867214.669101 rgb/1311867214.669101.png 1311867214.666559 depth/1311867214.666559.png +1311867214.704890 rgb/1311867214.704890.png 1311867214.698562 depth/1311867214.698562.png +1311867214.736964 rgb/1311867214.736964.png 1311867214.731080 depth/1311867214.731080.png +1311867214.769506 rgb/1311867214.769506.png 1311867214.768292 depth/1311867214.768292.png +1311867214.804993 rgb/1311867214.804993.png 1311867214.798063 depth/1311867214.798063.png +1311867214.836918 rgb/1311867214.836918.png 1311867214.830227 depth/1311867214.830227.png +1311867214.869998 rgb/1311867214.869998.png 1311867214.866509 depth/1311867214.866509.png +1311867214.904984 rgb/1311867214.904984.png 1311867214.898785 depth/1311867214.898785.png +1311867214.937253 rgb/1311867214.937253.png 1311867214.930825 depth/1311867214.930825.png +1311867214.969304 rgb/1311867214.969304.png 1311867214.966350 depth/1311867214.966350.png +1311867215.005064 rgb/1311867215.005064.png 1311867214.998091 depth/1311867214.998091.png +1311867215.037107 rgb/1311867215.037107.png 1311867215.030535 depth/1311867215.030535.png +1311867215.069291 rgb/1311867215.069291.png 1311867215.066838 depth/1311867215.066838.png +1311867215.105004 rgb/1311867215.105004.png 1311867215.098625 depth/1311867215.098625.png +1311867215.136914 rgb/1311867215.136914.png 1311867215.130449 depth/1311867215.130449.png +1311867215.169446 rgb/1311867215.169446.png 1311867215.166475 depth/1311867215.166475.png +1311867215.204946 rgb/1311867215.204946.png 1311867215.198166 depth/1311867215.198166.png +1311867215.236951 rgb/1311867215.236951.png 1311867215.230539 depth/1311867215.230539.png +1311867215.269082 rgb/1311867215.269082.png 1311867215.267247 depth/1311867215.267247.png +1311867215.304957 rgb/1311867215.304957.png 1311867215.298450 depth/1311867215.298450.png +1311867215.336962 rgb/1311867215.336962.png 1311867215.330815 depth/1311867215.330815.png +1311867215.369184 rgb/1311867215.369184.png 1311867215.366868 depth/1311867215.366868.png +1311867215.404952 rgb/1311867215.404952.png 1311867215.398538 depth/1311867215.398538.png +1311867215.437035 rgb/1311867215.437035.png 1311867215.430540 depth/1311867215.430540.png +1311867215.469090 rgb/1311867215.469090.png 1311867215.466565 depth/1311867215.466565.png +1311867215.504980 rgb/1311867215.504980.png 1311867215.498574 depth/1311867215.498574.png +1311867215.537123 rgb/1311867215.537123.png 1311867215.534556 depth/1311867215.534556.png +1311867215.569034 rgb/1311867215.569034.png 1311867215.566537 depth/1311867215.566537.png +1311867215.605085 rgb/1311867215.605085.png 1311867215.599212 depth/1311867215.599212.png +1311867215.637055 rgb/1311867215.637055.png 1311867215.634636 depth/1311867215.634636.png +1311867215.668922 rgb/1311867215.668922.png 1311867215.667807 depth/1311867215.667807.png +1311867215.704951 rgb/1311867215.704951.png 1311867215.698918 depth/1311867215.698918.png +1311867215.738883 rgb/1311867215.738883.png 1311867215.736307 depth/1311867215.736307.png +1311867215.769199 rgb/1311867215.769199.png 1311867215.767234 depth/1311867215.767234.png +1311867215.804883 rgb/1311867215.804883.png 1311867215.798475 depth/1311867215.798475.png +1311867215.837335 rgb/1311867215.837335.png 1311867215.834626 depth/1311867215.834626.png +1311867215.869167 rgb/1311867215.869167.png 1311867215.867785 depth/1311867215.867785.png +1311867215.905276 rgb/1311867215.905276.png 1311867215.901509 depth/1311867215.901509.png +1311867215.937088 rgb/1311867215.937088.png 1311867215.936341 depth/1311867215.936341.png +1311867215.970287 rgb/1311867215.970287.png 1311867215.967170 depth/1311867215.967170.png +1311867216.005079 rgb/1311867216.005079.png 1311867215.998861 depth/1311867215.998861.png +1311867216.036968 rgb/1311867216.036968.png 1311867216.036000 depth/1311867216.036000.png +1311867216.069483 rgb/1311867216.069483.png 1311867216.066615 depth/1311867216.066615.png +1311867216.105043 rgb/1311867216.105043.png 1311867216.098439 depth/1311867216.098439.png +1311867216.139295 rgb/1311867216.139295.png 1311867216.135610 depth/1311867216.135610.png +1311867216.169209 rgb/1311867216.169209.png 1311867216.169219 depth/1311867216.169219.png +1311867216.204961 rgb/1311867216.204961.png 1311867216.198337 depth/1311867216.198337.png +1311867216.237023 rgb/1311867216.237023.png 1311867216.235626 depth/1311867216.235626.png +1311867216.270663 rgb/1311867216.270663.png 1311867216.266688 depth/1311867216.266688.png +1311867216.305048 rgb/1311867216.305048.png 1311867216.298872 depth/1311867216.298872.png +1311867216.339542 rgb/1311867216.339542.png 1311867216.337480 depth/1311867216.337480.png +1311867216.369469 rgb/1311867216.369469.png 1311867216.366949 depth/1311867216.366949.png +1311867216.405512 rgb/1311867216.405512.png 1311867216.398915 depth/1311867216.398915.png +1311867216.437341 rgb/1311867216.437341.png 1311867216.435030 depth/1311867216.435030.png +1311867216.469753 rgb/1311867216.469753.png 1311867216.467146 depth/1311867216.467146.png +1311867216.504980 rgb/1311867216.504980.png 1311867216.499518 depth/1311867216.499518.png +1311867216.537226 rgb/1311867216.537226.png 1311867216.537110 depth/1311867216.537110.png +1311867216.569333 rgb/1311867216.569333.png 1311867216.566721 depth/1311867216.566721.png +1311867216.605032 rgb/1311867216.605032.png 1311867216.599049 depth/1311867216.599049.png +1311867216.637314 rgb/1311867216.637314.png 1311867216.637349 depth/1311867216.637349.png +1311867216.669119 rgb/1311867216.669119.png 1311867216.666770 depth/1311867216.666770.png +1311867216.705236 rgb/1311867216.705236.png 1311867216.698460 depth/1311867216.698460.png +1311867216.737208 rgb/1311867216.737208.png 1311867216.735234 depth/1311867216.735234.png +1311867216.769195 rgb/1311867216.769195.png 1311867216.766676 depth/1311867216.766676.png +1311867216.805002 rgb/1311867216.805002.png 1311867216.804141 depth/1311867216.804141.png +1311867216.837963 rgb/1311867216.837963.png 1311867216.834647 depth/1311867216.834647.png +1311867216.870340 rgb/1311867216.870340.png 1311867216.866658 depth/1311867216.866658.png +1311867216.904959 rgb/1311867216.904959.png 1311867216.904330 depth/1311867216.904330.png +1311867216.937407 rgb/1311867216.937407.png 1311867216.934638 depth/1311867216.934638.png +1311867216.969173 rgb/1311867216.969173.png 1311867216.967064 depth/1311867216.967064.png +1311867217.005327 rgb/1311867217.005327.png 1311867217.003467 depth/1311867217.003467.png +1311867217.037311 rgb/1311867217.037311.png 1311867217.034613 depth/1311867217.034613.png +1311867217.069129 rgb/1311867217.069129.png 1311867217.066936 depth/1311867217.066936.png +1311867217.105258 rgb/1311867217.105258.png 1311867217.104641 depth/1311867217.104641.png +1311867217.137085 rgb/1311867217.137085.png 1311867217.136313 depth/1311867217.136313.png +1311867217.169189 rgb/1311867217.169189.png 1311867217.166641 depth/1311867217.166641.png +1311867217.205792 rgb/1311867217.205792.png 1311867217.202562 depth/1311867217.202562.png +1311867217.237168 rgb/1311867217.237168.png 1311867217.234561 depth/1311867217.234561.png +1311867217.269228 rgb/1311867217.269228.png 1311867217.266687 depth/1311867217.266687.png +1311867217.305164 rgb/1311867217.305164.png 1311867217.303071 depth/1311867217.303071.png +1311867217.337405 rgb/1311867217.337405.png 1311867217.335057 depth/1311867217.335057.png +1311867217.369597 rgb/1311867217.369597.png 1311867217.367254 depth/1311867217.367254.png +1311867217.412045 rgb/1311867217.412045.png 1311867217.405199 depth/1311867217.405199.png +1311867217.437282 rgb/1311867217.437282.png 1311867217.435256 depth/1311867217.435256.png +1311867217.469419 rgb/1311867217.469419.png 1311867217.469430 depth/1311867217.469430.png +1311867217.505032 rgb/1311867217.505032.png 1311867217.505043 depth/1311867217.505043.png +1311867217.537068 rgb/1311867217.537068.png 1311867217.534680 depth/1311867217.534680.png +1311867217.569154 rgb/1311867217.569154.png 1311867217.566950 depth/1311867217.566950.png +1311867217.605054 rgb/1311867217.605054.png 1311867217.602982 depth/1311867217.602982.png +1311867217.637099 rgb/1311867217.637099.png 1311867217.634689 depth/1311867217.634689.png +1311867217.669100 rgb/1311867217.669100.png 1311867217.666971 depth/1311867217.666971.png +1311867217.705063 rgb/1311867217.705063.png 1311867217.704535 depth/1311867217.704535.png +1311867217.737154 rgb/1311867217.737154.png 1311867217.735349 depth/1311867217.735349.png +1311867217.769488 rgb/1311867217.769488.png 1311867217.767069 depth/1311867217.767069.png +1311867217.805184 rgb/1311867217.805184.png 1311867217.802824 depth/1311867217.802824.png +1311867217.837227 rgb/1311867217.837227.png 1311867217.835056 depth/1311867217.835056.png +1311867217.869085 rgb/1311867217.869085.png 1311867217.867660 depth/1311867217.867660.png +1311867217.905635 rgb/1311867217.905635.png 1311867217.903143 depth/1311867217.903143.png +1311867217.937258 rgb/1311867217.937258.png 1311867217.935124 depth/1311867217.935124.png +1311867217.971093 rgb/1311867217.971093.png 1311867217.971100 depth/1311867217.971100.png +1311867218.005224 rgb/1311867218.005224.png 1311867218.003978 depth/1311867218.003978.png +1311867218.037144 rgb/1311867218.037144.png 1311867218.034727 depth/1311867218.034727.png +1311867218.071085 rgb/1311867218.071085.png 1311867218.071095 depth/1311867218.071095.png +1311867218.105098 rgb/1311867218.105098.png 1311867218.102904 depth/1311867218.102904.png +1311867218.137118 rgb/1311867218.137118.png 1311867218.135394 depth/1311867218.135394.png +1311867218.171201 rgb/1311867218.171201.png 1311867218.171209 depth/1311867218.171209.png +1311867218.205035 rgb/1311867218.205035.png 1311867218.204112 depth/1311867218.204112.png +1311867218.237244 rgb/1311867218.237244.png 1311867218.235236 depth/1311867218.235236.png +1311867218.271553 rgb/1311867218.271553.png 1311867218.271564 depth/1311867218.271564.png +1311867218.305133 rgb/1311867218.305133.png 1311867218.303010 depth/1311867218.303010.png +1311867218.337365 rgb/1311867218.337365.png 1311867218.335330 depth/1311867218.335330.png +1311867218.373471 rgb/1311867218.373471.png 1311867218.373477 depth/1311867218.373477.png +1311867218.405269 rgb/1311867218.405269.png 1311867218.403041 depth/1311867218.403041.png +1311867218.437232 rgb/1311867218.437232.png 1311867218.435479 depth/1311867218.435479.png +1311867218.472952 rgb/1311867218.472952.png 1311867218.472975 depth/1311867218.472975.png +1311867218.505117 rgb/1311867218.505117.png 1311867218.503413 depth/1311867218.503413.png +1311867218.537273 rgb/1311867218.537273.png 1311867218.535025 depth/1311867218.535025.png +1311867218.571458 rgb/1311867218.571458.png 1311867218.571476 depth/1311867218.571476.png +1311867218.605932 rgb/1311867218.605932.png 1311867218.602762 depth/1311867218.602762.png +1311867218.637202 rgb/1311867218.637202.png 1311867218.636531 depth/1311867218.636531.png +1311867218.671051 rgb/1311867218.671051.png 1311867218.671082 depth/1311867218.671082.png +1311867218.705900 rgb/1311867218.705900.png 1311867218.702733 depth/1311867218.702733.png +1311867218.737849 rgb/1311867218.737849.png 1311867218.735286 depth/1311867218.735286.png +1311867218.771585 rgb/1311867218.771585.png 1311867218.771590 depth/1311867218.771590.png +1311867218.805242 rgb/1311867218.805242.png 1311867218.802779 depth/1311867218.802779.png +1311867218.837996 rgb/1311867218.837996.png 1311867218.834796 depth/1311867218.834796.png +1311867218.872727 rgb/1311867218.872727.png 1311867218.872734 depth/1311867218.872734.png +1311867218.905486 rgb/1311867218.905486.png 1311867218.902682 depth/1311867218.902682.png +1311867218.937220 rgb/1311867218.937220.png 1311867218.935555 depth/1311867218.935555.png +1311867218.973161 rgb/1311867218.973161.png 1311867218.973168 depth/1311867218.973168.png +1311867219.005183 rgb/1311867219.005183.png 1311867219.003058 depth/1311867219.003058.png +1311867219.037124 rgb/1311867219.037124.png 1311867219.035078 depth/1311867219.035078.png +1311867219.073837 rgb/1311867219.073837.png 1311867219.073843 depth/1311867219.073843.png +1311867219.105080 rgb/1311867219.105080.png 1311867219.102872 depth/1311867219.102872.png +1311867219.138326 rgb/1311867219.138326.png 1311867219.135339 depth/1311867219.135339.png +1311867219.170841 rgb/1311867219.170841.png 1311867219.170846 depth/1311867219.170846.png +1311867219.205245 rgb/1311867219.205245.png 1311867219.202940 depth/1311867219.202940.png +1311867219.239134 rgb/1311867219.239134.png 1311867219.239013 depth/1311867219.239013.png +1311867219.270902 rgb/1311867219.270902.png 1311867219.270906 depth/1311867219.270906.png +1311867219.305243 rgb/1311867219.305243.png 1311867219.303487 depth/1311867219.303487.png +1311867219.340155 rgb/1311867219.340155.png 1311867219.340160 depth/1311867219.340160.png +1311867219.371495 rgb/1311867219.371495.png 1311867219.371505 depth/1311867219.371505.png +1311867219.405197 rgb/1311867219.405197.png 1311867219.403433 depth/1311867219.403433.png +1311867219.439479 rgb/1311867219.439479.png 1311867219.439486 depth/1311867219.439486.png +1311867219.471709 rgb/1311867219.471709.png 1311867219.471730 depth/1311867219.471730.png +1311867219.505156 rgb/1311867219.505156.png 1311867219.503311 depth/1311867219.503311.png +1311867219.539180 rgb/1311867219.539180.png 1311867219.539195 depth/1311867219.539195.png +1311867219.574333 rgb/1311867219.574333.png 1311867219.574347 depth/1311867219.574347.png +1311867219.608604 rgb/1311867219.608604.png 1311867219.608626 depth/1311867219.608626.png +1311867219.642360 rgb/1311867219.642360.png 1311867219.642502 depth/1311867219.642502.png +1311867219.671103 rgb/1311867219.671103.png 1311867219.671117 depth/1311867219.671117.png +1311867219.705287 rgb/1311867219.705287.png 1311867219.702987 depth/1311867219.702987.png +1311867219.739499 rgb/1311867219.739499.png 1311867219.739518 depth/1311867219.739518.png +1311867219.773963 rgb/1311867219.773963.png 1311867219.777211 depth/1311867219.777211.png +1311867219.805177 rgb/1311867219.805177.png 1311867219.803964 depth/1311867219.803964.png +1311867219.839721 rgb/1311867219.839721.png 1311867219.839734 depth/1311867219.839734.png +1311867219.875308 rgb/1311867219.875308.png 1311867219.875322 depth/1311867219.875322.png +1311867219.910839 rgb/1311867219.910839.png 1311867219.907134 depth/1311867219.907134.png +1311867219.941763 rgb/1311867219.941763.png 1311867219.941782 depth/1311867219.941782.png +1311867219.973219 rgb/1311867219.973219.png 1311867219.973230 depth/1311867219.973230.png +1311867220.006868 rgb/1311867220.006868.png 1311867220.006463 depth/1311867220.006463.png +1311867220.042194 rgb/1311867220.042194.png 1311867220.042243 depth/1311867220.042243.png +1311867220.074365 rgb/1311867220.074365.png 1311867220.074382 depth/1311867220.074382.png +1311867220.105276 rgb/1311867220.105276.png 1311867220.103671 depth/1311867220.103671.png +1311867220.142093 rgb/1311867220.142093.png 1311867220.142123 depth/1311867220.142123.png +1311867220.171409 rgb/1311867220.171409.png 1311867220.171473 depth/1311867220.171473.png +1311867220.206177 rgb/1311867220.206177.png 1311867220.206199 depth/1311867220.206199.png +1311867220.242193 rgb/1311867220.242193.png 1311867220.242225 depth/1311867220.242225.png +1311867220.274111 rgb/1311867220.274111.png 1311867220.274128 depth/1311867220.274128.png +1311867220.306449 rgb/1311867220.306449.png 1311867220.306458 depth/1311867220.306458.png +1311867220.342053 rgb/1311867220.342053.png 1311867220.342100 depth/1311867220.342100.png +1311867220.371471 rgb/1311867220.371471.png 1311867220.371487 depth/1311867220.371487.png +1311867220.406370 rgb/1311867220.406370.png 1311867220.406380 depth/1311867220.406380.png +1311867220.440877 rgb/1311867220.440877.png 1311867220.440884 depth/1311867220.440884.png +1311867220.472868 rgb/1311867220.472868.png 1311867220.472875 depth/1311867220.472875.png +1311867220.509080 rgb/1311867220.509080.png 1311867220.509106 depth/1311867220.509106.png +1311867220.541975 rgb/1311867220.541975.png 1311867220.541985 depth/1311867220.541985.png +1311867220.571621 rgb/1311867220.571621.png 1311867220.571640 depth/1311867220.571640.png +1311867220.610419 rgb/1311867220.610419.png 1311867220.610425 depth/1311867220.610425.png +1311867220.639667 rgb/1311867220.639667.png 1311867220.641550 depth/1311867220.641550.png +1311867220.671279 rgb/1311867220.671279.png 1311867220.671309 depth/1311867220.671309.png +1311867220.707327 rgb/1311867220.707327.png 1311867220.707336 depth/1311867220.707336.png +1311867220.739338 rgb/1311867220.739338.png 1311867220.739344 depth/1311867220.739344.png +1311867220.771914 rgb/1311867220.771914.png 1311867220.771985 depth/1311867220.771985.png +1311867220.809727 rgb/1311867220.809727.png 1311867220.809753 depth/1311867220.809753.png +1311867220.841417 rgb/1311867220.841417.png 1311867220.841502 depth/1311867220.841502.png +1311867220.871240 rgb/1311867220.871240.png 1311867220.871248 depth/1311867220.871248.png +1311867220.907590 rgb/1311867220.907590.png 1311867220.907596 depth/1311867220.907596.png +1311867220.939280 rgb/1311867220.939280.png 1311867220.939297 depth/1311867220.939297.png +1311867220.971313 rgb/1311867220.971313.png 1311867220.971319 depth/1311867220.971319.png +1311867221.008955 rgb/1311867221.008955.png 1311867221.009018 depth/1311867221.009018.png +1311867221.039288 rgb/1311867221.039288.png 1311867221.039294 depth/1311867221.039294.png +1311867221.072099 rgb/1311867221.072099.png 1311867221.071571 depth/1311867221.071571.png +1311867221.107750 rgb/1311867221.107750.png 1311867221.107758 depth/1311867221.107758.png +1311867221.139766 rgb/1311867221.139766.png 1311867221.139779 depth/1311867221.139779.png +1311867221.171684 rgb/1311867221.171684.png 1311867221.171691 depth/1311867221.171691.png +1311867221.208397 rgb/1311867221.208397.png 1311867221.208183 depth/1311867221.208183.png +1311867221.239750 rgb/1311867221.239750.png 1311867221.239813 depth/1311867221.239813.png +1311867221.271980 rgb/1311867221.271980.png 1311867221.272124 depth/1311867221.272124.png +1311867221.307576 rgb/1311867221.307576.png 1311867221.307593 depth/1311867221.307593.png +1311867221.339333 rgb/1311867221.339333.png 1311867221.339345 depth/1311867221.339345.png +1311867221.371416 rgb/1311867221.371416.png 1311867221.371422 depth/1311867221.371422.png +1311867221.407147 rgb/1311867221.407147.png 1311867221.407388 depth/1311867221.407388.png +1311867221.440006 rgb/1311867221.440006.png 1311867221.440068 depth/1311867221.440068.png +1311867221.471228 rgb/1311867221.471228.png 1311867221.471241 depth/1311867221.471241.png +1311867221.508153 rgb/1311867221.508153.png 1311867221.508172 depth/1311867221.508172.png +1311867221.539675 rgb/1311867221.539675.png 1311867221.539691 depth/1311867221.539691.png +1311867221.571272 rgb/1311867221.571272.png 1311867221.571279 depth/1311867221.571279.png +1311867221.607168 rgb/1311867221.607168.png 1311867221.607311 depth/1311867221.607311.png +1311867221.640370 rgb/1311867221.640370.png 1311867221.640377 depth/1311867221.640377.png +1311867221.669453 rgb/1311867221.669453.png 1311867221.677148 depth/1311867221.677148.png +1311867221.707171 rgb/1311867221.707171.png 1311867221.707202 depth/1311867221.707202.png +1311867221.742382 rgb/1311867221.742382.png 1311867221.742393 depth/1311867221.742393.png +1311867221.769386 rgb/1311867221.769386.png 1311867221.777350 depth/1311867221.777350.png +1311867221.807422 rgb/1311867221.807422.png 1311867221.807454 depth/1311867221.807454.png +1311867221.839645 rgb/1311867221.839645.png 1311867221.839652 depth/1311867221.839652.png +1311867221.869580 rgb/1311867221.869580.png 1311867221.877733 depth/1311867221.877733.png +1311867221.907739 rgb/1311867221.907739.png 1311867221.907749 depth/1311867221.907749.png +1311867221.942361 rgb/1311867221.942361.png 1311867221.942463 depth/1311867221.942463.png +1311867221.969578 rgb/1311867221.969578.png 1311867221.977536 depth/1311867221.977536.png +1311867222.009006 rgb/1311867222.009006.png 1311867222.008677 depth/1311867222.008677.png +1311867222.042876 rgb/1311867222.042876.png 1311867222.039534 depth/1311867222.039534.png +1311867222.069362 rgb/1311867222.069362.png 1311867222.078253 depth/1311867222.078253.png +1311867222.111094 rgb/1311867222.111094.png 1311867222.107797 depth/1311867222.107797.png +1311867222.140683 rgb/1311867222.140683.png 1311867222.140690 depth/1311867222.140690.png +1311867222.169399 rgb/1311867222.169399.png 1311867222.179799 depth/1311867222.179799.png +1311867222.208160 rgb/1311867222.208160.png 1311867222.208173 depth/1311867222.208173.png +1311867222.240073 rgb/1311867222.240073.png 1311867222.240084 depth/1311867222.240084.png +1311867222.269681 rgb/1311867222.269681.png 1311867222.276030 depth/1311867222.276030.png +1311867222.307736 rgb/1311867222.307736.png 1311867222.307742 depth/1311867222.307742.png +1311867222.339630 rgb/1311867222.339630.png 1311867222.339639 depth/1311867222.339639.png +1311867222.369496 rgb/1311867222.369496.png 1311867222.379236 depth/1311867222.379236.png +1311867222.410190 rgb/1311867222.410190.png 1311867222.410200 depth/1311867222.410200.png +1311867222.443636 rgb/1311867222.443636.png 1311867222.443643 depth/1311867222.443643.png +1311867222.469409 rgb/1311867222.469409.png 1311867222.478112 depth/1311867222.478112.png +1311867222.508688 rgb/1311867222.508688.png 1311867222.508709 depth/1311867222.508709.png +1311867222.540167 rgb/1311867222.540167.png 1311867222.540179 depth/1311867222.540179.png +1311867222.569671 rgb/1311867222.569671.png 1311867222.577404 depth/1311867222.577404.png +1311867222.608424 rgb/1311867222.608424.png 1311867222.608439 depth/1311867222.608439.png +1311867222.643296 rgb/1311867222.643296.png 1311867222.643312 depth/1311867222.643312.png +1311867222.669574 rgb/1311867222.669574.png 1311867222.679649 depth/1311867222.679649.png +1311867222.708011 rgb/1311867222.708011.png 1311867222.708025 depth/1311867222.708025.png +1311867222.739992 rgb/1311867222.739992.png 1311867222.740008 depth/1311867222.740008.png +1311867222.769457 rgb/1311867222.769457.png 1311867222.779394 depth/1311867222.779394.png +1311867222.809321 rgb/1311867222.809321.png 1311867222.809157 depth/1311867222.809157.png +1311867222.840258 rgb/1311867222.840258.png 1311867222.840276 depth/1311867222.840276.png +1311867222.869499 rgb/1311867222.869499.png 1311867222.881298 depth/1311867222.881298.png +1311867222.908232 rgb/1311867222.908232.png 1311867222.908236 depth/1311867222.908236.png +1311867222.937591 rgb/1311867222.937591.png 1311867222.947082 depth/1311867222.947082.png +1311867222.969488 rgb/1311867222.969488.png 1311867222.983102 depth/1311867222.983102.png +1311867223.007824 rgb/1311867223.007824.png 1311867223.007831 depth/1311867223.007831.png +1311867223.037495 rgb/1311867223.037495.png 1311867223.045406 depth/1311867223.045406.png +1311867223.069417 rgb/1311867223.069417.png 1311867223.080825 depth/1311867223.080825.png +1311867223.109412 rgb/1311867223.109412.png 1311867223.109423 depth/1311867223.109423.png +1311867223.138136 rgb/1311867223.138136.png 1311867223.147377 depth/1311867223.147377.png +1311867223.175852 rgb/1311867223.175852.png 1311867223.175858 depth/1311867223.175858.png +1311867223.208002 rgb/1311867223.208002.png 1311867223.207819 depth/1311867223.207819.png +1311867223.237463 rgb/1311867223.237463.png 1311867223.245008 depth/1311867223.245008.png +1311867223.277936 rgb/1311867223.277936.png 1311867223.276362 depth/1311867223.276362.png +1311867223.308589 rgb/1311867223.308589.png 1311867223.308600 depth/1311867223.308600.png +1311867223.337625 rgb/1311867223.337625.png 1311867223.345242 depth/1311867223.345242.png +1311867223.375432 rgb/1311867223.375432.png 1311867223.379469 depth/1311867223.379469.png +1311867223.407361 rgb/1311867223.407361.png 1311867223.407424 depth/1311867223.407424.png +1311867223.437562 rgb/1311867223.437562.png 1311867223.445800 depth/1311867223.445800.png +1311867223.475825 rgb/1311867223.475825.png 1311867223.475833 depth/1311867223.475833.png +1311867223.507732 rgb/1311867223.507732.png 1311867223.507743 depth/1311867223.507743.png +1311867223.537550 rgb/1311867223.537550.png 1311867223.546653 depth/1311867223.546653.png +1311867223.575919 rgb/1311867223.575919.png 1311867223.575954 depth/1311867223.575954.png +1311867223.607790 rgb/1311867223.607790.png 1311867223.607807 depth/1311867223.607807.png +1311867223.637449 rgb/1311867223.637449.png 1311867223.650204 depth/1311867223.650204.png +1311867223.675382 rgb/1311867223.675382.png 1311867223.675388 depth/1311867223.675388.png +1311867223.708839 rgb/1311867223.708839.png 1311867223.708858 depth/1311867223.708858.png +1311867223.737594 rgb/1311867223.737594.png 1311867223.745281 depth/1311867223.745281.png +1311867223.776066 rgb/1311867223.776066.png 1311867223.776072 depth/1311867223.776072.png +1311867223.807750 rgb/1311867223.807750.png 1311867223.807756 depth/1311867223.807756.png +1311867223.837481 rgb/1311867223.837481.png 1311867223.843852 depth/1311867223.843852.png +1311867223.876077 rgb/1311867223.876077.png 1311867223.876092 depth/1311867223.876092.png +1311867223.907813 rgb/1311867223.907813.png 1311867223.907828 depth/1311867223.907828.png +1311867223.938926 rgb/1311867223.938926.png 1311867223.949167 depth/1311867223.949167.png +1311867223.976047 rgb/1311867223.976047.png 1311867223.976074 depth/1311867223.976074.png +1311867224.009213 rgb/1311867224.009213.png 1311867224.009344 depth/1311867224.009344.png +1311867224.037596 rgb/1311867224.037596.png 1311867224.047044 depth/1311867224.047044.png +1311867224.076133 rgb/1311867224.076133.png 1311867224.076141 depth/1311867224.076141.png +1311867224.108128 rgb/1311867224.108128.png 1311867224.108135 depth/1311867224.108135.png +1311867224.137526 rgb/1311867224.137526.png 1311867224.145899 depth/1311867224.145899.png +1311867224.176888 rgb/1311867224.176888.png 1311867224.176893 depth/1311867224.176893.png +1311867224.205512 rgb/1311867224.205512.png 1311867224.214377 depth/1311867224.214377.png +1311867224.237792 rgb/1311867224.237792.png 1311867224.247043 depth/1311867224.247043.png +1311867224.276855 rgb/1311867224.276855.png 1311867224.276863 depth/1311867224.276863.png +1311867224.305465 rgb/1311867224.305465.png 1311867224.314617 depth/1311867224.314617.png +1311867224.337546 rgb/1311867224.337546.png 1311867224.345673 depth/1311867224.345673.png +1311867224.376913 rgb/1311867224.376913.png 1311867224.376921 depth/1311867224.376921.png +1311867224.405603 rgb/1311867224.405603.png 1311867224.414102 depth/1311867224.414102.png +1311867224.437516 rgb/1311867224.437516.png 1311867224.446427 depth/1311867224.446427.png +1311867224.477686 rgb/1311867224.477686.png 1311867224.477419 depth/1311867224.477419.png +1311867224.505660 rgb/1311867224.505660.png 1311867224.518122 depth/1311867224.518122.png +1311867224.537809 rgb/1311867224.537809.png 1311867224.547057 depth/1311867224.547057.png +1311867224.585912 rgb/1311867224.585912.png 1311867224.580686 depth/1311867224.580686.png +1311867224.605597 rgb/1311867224.605597.png 1311867224.618112 depth/1311867224.618112.png +1311867224.637806 rgb/1311867224.637806.png 1311867224.650216 depth/1311867224.650216.png +1311867224.678501 rgb/1311867224.678501.png 1311867224.678519 depth/1311867224.678519.png +1311867224.705493 rgb/1311867224.705493.png 1311867224.717365 depth/1311867224.717365.png +1311867224.737612 rgb/1311867224.737612.png 1311867224.752092 depth/1311867224.752092.png +1311867224.786626 rgb/1311867224.786626.png 1311867224.781324 depth/1311867224.781324.png +1311867224.805654 rgb/1311867224.805654.png 1311867224.812346 depth/1311867224.812346.png +1311867224.837824 rgb/1311867224.837824.png 1311867224.845819 depth/1311867224.845819.png +1311867224.877943 rgb/1311867224.877943.png 1311867224.877666 depth/1311867224.877666.png +1311867224.905651 rgb/1311867224.905651.png 1311867224.914245 depth/1311867224.914245.png +1311867224.937570 rgb/1311867224.937570.png 1311867224.947145 depth/1311867224.947145.png +1311867224.979735 rgb/1311867224.979735.png 1311867224.980049 depth/1311867224.980049.png +1311867225.006618 rgb/1311867225.006618.png 1311867225.014292 depth/1311867225.014292.png +1311867225.037681 rgb/1311867225.037681.png 1311867225.049388 depth/1311867225.049388.png +1311867225.079869 rgb/1311867225.079869.png 1311867225.079540 depth/1311867225.079540.png +1311867225.105549 rgb/1311867225.105549.png 1311867225.113819 depth/1311867225.113819.png +1311867225.137763 rgb/1311867225.137763.png 1311867225.147238 depth/1311867225.147238.png +1311867225.180820 rgb/1311867225.180820.png 1311867225.181094 depth/1311867225.181094.png +1311867225.205557 rgb/1311867225.205557.png 1311867225.215322 depth/1311867225.215322.png +1311867225.237668 rgb/1311867225.237668.png 1311867225.248347 depth/1311867225.248347.png +1311867225.279255 rgb/1311867225.279255.png 1311867225.279291 depth/1311867225.279291.png +1311867225.305777 rgb/1311867225.305777.png 1311867225.320754 depth/1311867225.320754.png +1311867225.337676 rgb/1311867225.337676.png 1311867225.346235 depth/1311867225.346235.png +1311867225.373693 rgb/1311867225.373693.png 1311867225.385207 depth/1311867225.385207.png +1311867225.405582 rgb/1311867225.405582.png 1311867225.413013 depth/1311867225.413013.png +1311867225.437602 rgb/1311867225.437602.png 1311867225.450427 depth/1311867225.450427.png +1311867225.473714 rgb/1311867225.473714.png 1311867225.484295 depth/1311867225.484295.png +1311867225.505610 rgb/1311867225.505610.png 1311867225.516392 depth/1311867225.516392.png +1311867225.537795 rgb/1311867225.537795.png 1311867225.549375 depth/1311867225.549375.png +1311867225.573788 rgb/1311867225.573788.png 1311867225.588235 depth/1311867225.588235.png +1311867225.605520 rgb/1311867225.605520.png 1311867225.617901 depth/1311867225.617901.png +1311867225.637625 rgb/1311867225.637625.png 1311867225.646129 depth/1311867225.646129.png +1311867225.673806 rgb/1311867225.673806.png 1311867225.684712 depth/1311867225.684712.png +1311867225.705642 rgb/1311867225.705642.png 1311867225.716077 depth/1311867225.716077.png +1311867225.737747 rgb/1311867225.737747.png 1311867225.750630 depth/1311867225.750630.png +1311867225.773659 rgb/1311867225.773659.png 1311867225.787290 depth/1311867225.787290.png +1311867225.805618 rgb/1311867225.805618.png 1311867225.817078 depth/1311867225.817078.png +1311867225.837804 rgb/1311867225.837804.png 1311867225.852002 depth/1311867225.852002.png +1311867225.873778 rgb/1311867225.873778.png 1311867225.886291 depth/1311867225.886291.png +1311867225.905632 rgb/1311867225.905632.png 1311867225.917793 depth/1311867225.917793.png +1311867225.937904 rgb/1311867225.937904.png 1311867225.950491 depth/1311867225.950491.png +1311867225.973591 rgb/1311867225.973591.png 1311867225.985248 depth/1311867225.985248.png +1311867226.005870 rgb/1311867226.005870.png 1311867226.017372 depth/1311867226.017372.png +1311867226.037807 rgb/1311867226.037807.png 1311867226.051148 depth/1311867226.051148.png +1311867226.073737 rgb/1311867226.073737.png 1311867226.087782 depth/1311867226.087782.png +1311867226.105587 rgb/1311867226.105587.png 1311867226.118227 depth/1311867226.118227.png +1311867226.137702 rgb/1311867226.137702.png 1311867226.147749 depth/1311867226.147749.png +1311867226.173782 rgb/1311867226.173782.png 1311867226.183314 depth/1311867226.183314.png +1311867226.205652 rgb/1311867226.205652.png 1311867226.216681 depth/1311867226.216681.png +1311867226.237839 rgb/1311867226.237839.png 1311867226.248711 depth/1311867226.248711.png +1311867226.273639 rgb/1311867226.273639.png 1311867226.282993 depth/1311867226.282993.png +1311867226.305637 rgb/1311867226.305637.png 1311867226.321131 depth/1311867226.321131.png +1311867226.337609 rgb/1311867226.337609.png 1311867226.345582 depth/1311867226.345582.png +1311867226.373734 rgb/1311867226.373734.png 1311867226.387308 depth/1311867226.387308.png +1311867226.405602 rgb/1311867226.405602.png 1311867226.418875 depth/1311867226.418875.png +1311867226.437644 rgb/1311867226.437644.png 1311867226.447274 depth/1311867226.447274.png +1311867226.473717 rgb/1311867226.473717.png 1311867226.484957 depth/1311867226.484957.png +1311867226.505750 rgb/1311867226.505750.png 1311867226.516784 depth/1311867226.516784.png +1311867226.537741 rgb/1311867226.537741.png 1311867226.546219 depth/1311867226.546219.png +1311867226.573767 rgb/1311867226.573767.png 1311867226.584229 depth/1311867226.584229.png +1311867226.605613 rgb/1311867226.605613.png 1311867226.614960 depth/1311867226.614960.png +1311867226.637797 rgb/1311867226.637797.png 1311867226.654529 depth/1311867226.654529.png +1311867226.673676 rgb/1311867226.673676.png 1311867226.680215 depth/1311867226.680215.png +1311867226.705658 rgb/1311867226.705658.png 1311867226.714235 depth/1311867226.714235.png +1311867226.737728 rgb/1311867226.737728.png 1311867226.750659 depth/1311867226.750659.png +1311867226.773860 rgb/1311867226.773860.png 1311867226.781808 depth/1311867226.781808.png +1311867226.805637 rgb/1311867226.805637.png 1311867226.813308 depth/1311867226.813308.png +1311867226.837753 rgb/1311867226.837753.png 1311867226.851361 depth/1311867226.851361.png +1311867226.873821 rgb/1311867226.873821.png 1311867226.883868 depth/1311867226.883868.png +1311867226.905774 rgb/1311867226.905774.png 1311867226.918156 depth/1311867226.918156.png +1311867226.937813 rgb/1311867226.937813.png 1311867226.951490 depth/1311867226.951490.png +1311867226.973631 rgb/1311867226.973631.png 1311867226.981015 depth/1311867226.981015.png +1311867227.005676 rgb/1311867227.005676.png 1311867227.012562 depth/1311867227.012562.png +1311867227.037802 rgb/1311867227.037802.png 1311867227.048067 depth/1311867227.048067.png +1311867227.073659 rgb/1311867227.073659.png 1311867227.086193 depth/1311867227.086193.png +1311867227.105662 rgb/1311867227.105662.png 1311867227.115819 depth/1311867227.115819.png +1311867227.137793 rgb/1311867227.137793.png 1311867227.150400 depth/1311867227.150400.png +1311867227.173840 rgb/1311867227.173840.png 1311867227.184159 depth/1311867227.184159.png +1311867227.205749 rgb/1311867227.205749.png 1311867227.214845 depth/1311867227.214845.png +1311867227.237947 rgb/1311867227.237947.png 1311867227.248026 depth/1311867227.248026.png +1311867227.273709 rgb/1311867227.273709.png 1311867227.281980 depth/1311867227.281980.png +1311867227.305822 rgb/1311867227.305822.png 1311867227.315250 depth/1311867227.315250.png +1311867227.337747 rgb/1311867227.337747.png 1311867227.347984 depth/1311867227.347984.png +1311867227.373776 rgb/1311867227.373776.png 1311867227.384107 depth/1311867227.384107.png +1311867227.405700 rgb/1311867227.405700.png 1311867227.414144 depth/1311867227.414144.png +1311867227.437755 rgb/1311867227.437755.png 1311867227.447920 depth/1311867227.447920.png +1311867227.473739 rgb/1311867227.473739.png 1311867227.481876 depth/1311867227.481876.png +1311867227.505780 rgb/1311867227.505780.png 1311867227.516933 depth/1311867227.516933.png +1311867227.537934 rgb/1311867227.537934.png 1311867227.550122 depth/1311867227.550122.png +1311867227.573742 rgb/1311867227.573742.png 1311867227.581954 depth/1311867227.581954.png +1311867227.605850 rgb/1311867227.605850.png 1311867227.616275 depth/1311867227.616275.png +1311867227.637919 rgb/1311867227.637919.png 1311867227.650308 depth/1311867227.650308.png +1311867227.673930 rgb/1311867227.673930.png 1311867227.682398 depth/1311867227.682398.png +1311867227.705960 rgb/1311867227.705960.png 1311867227.713593 depth/1311867227.713593.png +1311867227.737825 rgb/1311867227.737825.png 1311867227.749637 depth/1311867227.749637.png +1311867227.773732 rgb/1311867227.773732.png 1311867227.782762 depth/1311867227.782762.png +1311867227.805861 rgb/1311867227.805861.png 1311867227.814155 depth/1311867227.814155.png +1311867227.837774 rgb/1311867227.837774.png 1311867227.849769 depth/1311867227.849769.png +1311867227.873834 rgb/1311867227.873834.png 1311867227.883287 depth/1311867227.883287.png +1311867227.905791 rgb/1311867227.905791.png 1311867227.919694 depth/1311867227.919694.png +1311867227.937974 rgb/1311867227.937974.png 1311867227.951678 depth/1311867227.951678.png +1311867227.973753 rgb/1311867227.973753.png 1311867227.982859 depth/1311867227.982859.png +1311867228.005723 rgb/1311867228.005723.png 1311867228.018191 depth/1311867228.018191.png +1311867228.037953 rgb/1311867228.037953.png 1311867228.051633 depth/1311867228.051633.png +1311867228.073892 rgb/1311867228.073892.png 1311867228.082533 depth/1311867228.082533.png +1311867228.105804 rgb/1311867228.105804.png 1311867228.117984 depth/1311867228.117984.png +1311867228.137844 rgb/1311867228.137844.png 1311867228.151139 depth/1311867228.151139.png +1311867228.173814 rgb/1311867228.173814.png 1311867228.182861 depth/1311867228.182861.png +1311867228.205739 rgb/1311867228.205739.png 1311867228.217942 depth/1311867228.217942.png +1311867228.237933 rgb/1311867228.237933.png 1311867228.254125 depth/1311867228.254125.png +1311867228.273761 rgb/1311867228.273761.png 1311867228.282652 depth/1311867228.282652.png +1311867228.305921 rgb/1311867228.305921.png 1311867228.318174 depth/1311867228.318174.png +1311867228.337798 rgb/1311867228.337798.png 1311867228.350452 depth/1311867228.350452.png +1311867228.373868 rgb/1311867228.373868.png 1311867228.382478 depth/1311867228.382478.png +1311867228.405817 rgb/1311867228.405817.png 1311867228.417676 depth/1311867228.417676.png +1311867228.437784 rgb/1311867228.437784.png 1311867228.448304 depth/1311867228.448304.png +1311867228.473891 rgb/1311867228.473891.png 1311867228.483532 depth/1311867228.483532.png +1311867228.505808 rgb/1311867228.505808.png 1311867228.517790 depth/1311867228.517790.png +1311867228.537902 rgb/1311867228.537902.png 1311867228.552964 depth/1311867228.552964.png +1311867228.573967 rgb/1311867228.573967.png 1311867228.583412 depth/1311867228.583412.png +1311867228.605785 rgb/1311867228.605785.png 1311867228.616884 depth/1311867228.616884.png +1311867228.638238 rgb/1311867228.638238.png 1311867228.651354 depth/1311867228.651354.png +1311867228.705963 rgb/1311867228.705963.png 1311867228.696091 depth/1311867228.696091.png +1311867228.738100 rgb/1311867228.738100.png 1311867228.725113 depth/1311867228.725113.png +1311867228.773802 rgb/1311867228.773802.png 1311867228.787273 depth/1311867228.787273.png +1311867228.805984 rgb/1311867228.805984.png 1311867228.818499 depth/1311867228.818499.png +1311867228.838559 rgb/1311867228.838559.png 1311867228.851219 depth/1311867228.851219.png +1311867228.873961 rgb/1311867228.873961.png 1311867228.883505 depth/1311867228.883505.png +1311867228.906015 rgb/1311867228.906015.png 1311867228.918145 depth/1311867228.918145.png +1311867228.937917 rgb/1311867228.937917.png 1311867228.949649 depth/1311867228.949649.png +1311867228.974031 rgb/1311867228.974031.png 1311867228.984476 depth/1311867228.984476.png +1311867229.006218 rgb/1311867229.006218.png 1311867229.023845 depth/1311867229.023845.png +1311867229.037895 rgb/1311867229.037895.png 1311867229.050928 depth/1311867229.050928.png +1311867229.073863 rgb/1311867229.073863.png 1311867229.087432 depth/1311867229.087432.png +1311867229.106048 rgb/1311867229.106048.png 1311867229.121808 depth/1311867229.121808.png +1311867229.138415 rgb/1311867229.138415.png 1311867229.151714 depth/1311867229.151714.png +1311867229.173882 rgb/1311867229.173882.png 1311867229.189054 depth/1311867229.189054.png +1311867229.205881 rgb/1311867229.205881.png 1311867229.221434 depth/1311867229.221434.png +1311867229.237989 rgb/1311867229.237989.png 1311867229.253298 depth/1311867229.253298.png +1311867229.273846 rgb/1311867229.273846.png 1311867229.284135 depth/1311867229.284135.png +1311867229.305876 rgb/1311867229.305876.png 1311867229.319302 depth/1311867229.319302.png +1311867229.338430 rgb/1311867229.338430.png 1311867229.350224 depth/1311867229.350224.png +1311867229.373891 rgb/1311867229.373891.png 1311867229.385071 depth/1311867229.385071.png +1311867229.405824 rgb/1311867229.405824.png 1311867229.418047 depth/1311867229.418047.png +1311867229.438754 rgb/1311867229.438754.png 1311867229.448374 depth/1311867229.448374.png +1311867229.473780 rgb/1311867229.473780.png 1311867229.484336 depth/1311867229.484336.png +1311867229.505914 rgb/1311867229.505914.png 1311867229.518993 depth/1311867229.518993.png +1311867229.538044 rgb/1311867229.538044.png 1311867229.550458 depth/1311867229.550458.png +1311867229.573925 rgb/1311867229.573925.png 1311867229.585338 depth/1311867229.585338.png +1311867229.605773 rgb/1311867229.605773.png 1311867229.618280 depth/1311867229.618280.png +1311867229.637979 rgb/1311867229.637979.png 1311867229.650316 depth/1311867229.650316.png +1311867229.673818 rgb/1311867229.673818.png 1311867229.687698 depth/1311867229.687698.png +1311867229.705799 rgb/1311867229.705799.png 1311867229.718422 depth/1311867229.718422.png +1311867229.737926 rgb/1311867229.737926.png 1311867229.750000 depth/1311867229.750000.png +1311867229.773985 rgb/1311867229.773985.png 1311867229.785433 depth/1311867229.785433.png +1311867229.805829 rgb/1311867229.805829.png 1311867229.818483 depth/1311867229.818483.png +1311867229.837864 rgb/1311867229.837864.png 1311867229.849428 depth/1311867229.849428.png +1311867229.874033 rgb/1311867229.874033.png 1311867229.885334 depth/1311867229.885334.png +1311867229.905852 rgb/1311867229.905852.png 1311867229.918314 depth/1311867229.918314.png +1311867229.938195 rgb/1311867229.938195.png 1311867229.953416 depth/1311867229.953416.png +1311867229.973952 rgb/1311867229.973952.png 1311867229.987775 depth/1311867229.987775.png +1311867230.005885 rgb/1311867230.005885.png 1311867230.019488 depth/1311867230.019488.png +1311867230.037850 rgb/1311867230.037850.png 1311867230.051261 depth/1311867230.051261.png +1311867230.074069 rgb/1311867230.074069.png 1311867230.087604 depth/1311867230.087604.png +1311867230.105927 rgb/1311867230.105927.png 1311867230.121203 depth/1311867230.121203.png +1311867230.138081 rgb/1311867230.138081.png 1311867230.150813 depth/1311867230.150813.png +1311867230.173877 rgb/1311867230.173877.png 1311867230.187230 depth/1311867230.187230.png +1311867230.206050 rgb/1311867230.206050.png 1311867230.219479 depth/1311867230.219479.png +1311867230.238178 rgb/1311867230.238178.png 1311867230.249421 depth/1311867230.249421.png +1311867230.274102 rgb/1311867230.274102.png 1311867230.289479 depth/1311867230.289479.png +1311867230.305950 rgb/1311867230.305950.png 1311867230.318943 depth/1311867230.318943.png +1311867230.337872 rgb/1311867230.337872.png 1311867230.355201 depth/1311867230.355201.png +1311867230.374067 rgb/1311867230.374067.png 1311867230.391314 depth/1311867230.391314.png +1311867230.406184 rgb/1311867230.406184.png 1311867230.416993 depth/1311867230.416993.png +1311867230.437986 rgb/1311867230.437986.png 1311867230.453894 depth/1311867230.453894.png +1311867230.474028 rgb/1311867230.474028.png 1311867230.489211 depth/1311867230.489211.png +1311867230.506080 rgb/1311867230.506080.png 1311867230.521643 depth/1311867230.521643.png +1311867230.574088 rgb/1311867230.574088.png 1311867230.556415 depth/1311867230.556415.png +1311867230.605959 rgb/1311867230.605959.png 1311867230.618415 depth/1311867230.618415.png +1311867230.638052 rgb/1311867230.638052.png 1311867230.653440 depth/1311867230.653440.png +1311867230.674058 rgb/1311867230.674058.png 1311867230.692078 depth/1311867230.692078.png +1311867230.705904 rgb/1311867230.705904.png 1311867230.718519 depth/1311867230.718519.png +1311867230.737957 rgb/1311867230.737957.png 1311867230.752912 depth/1311867230.752912.png +1311867230.774137 rgb/1311867230.774137.png 1311867230.787161 depth/1311867230.787161.png +1311867230.805901 rgb/1311867230.805901.png 1311867230.819574 depth/1311867230.819574.png +1311867230.838169 rgb/1311867230.838169.png 1311867230.853418 depth/1311867230.853418.png +1311867230.874133 rgb/1311867230.874133.png 1311867230.889016 depth/1311867230.889016.png +1311867230.905947 rgb/1311867230.905947.png 1311867230.917651 depth/1311867230.917651.png +1311867230.938299 rgb/1311867230.938299.png 1311867230.955917 depth/1311867230.955917.png +1311867230.973924 rgb/1311867230.973924.png 1311867230.988101 depth/1311867230.988101.png +1311867231.006219 rgb/1311867231.006219.png 1311867231.016628 depth/1311867231.016628.png +1311867231.074099 rgb/1311867231.074099.png 1311867231.086862 depth/1311867231.086862.png +1311867231.105954 rgb/1311867231.105954.png 1311867231.122102 depth/1311867231.122102.png +1311867231.138242 rgb/1311867231.138242.png 1311867231.152380 depth/1311867231.152380.png +1311867231.174250 rgb/1311867231.174250.png 1311867231.186007 depth/1311867231.186007.png +1311867231.205918 rgb/1311867231.205918.png 1311867231.218827 depth/1311867231.218827.png +1311867231.238184 rgb/1311867231.238184.png 1311867231.252262 depth/1311867231.252262.png +1311867231.274090 rgb/1311867231.274090.png 1311867231.286411 depth/1311867231.286411.png +1311867231.306019 rgb/1311867231.306019.png 1311867231.321594 depth/1311867231.321594.png +1311867231.338149 rgb/1311867231.338149.png 1311867231.352551 depth/1311867231.352551.png +1311867231.374183 rgb/1311867231.374183.png 1311867231.387465 depth/1311867231.387465.png +1311867231.405990 rgb/1311867231.405990.png 1311867231.418704 depth/1311867231.418704.png +1311867231.438072 rgb/1311867231.438072.png 1311867231.454240 depth/1311867231.454240.png +1311867231.474140 rgb/1311867231.474140.png 1311867231.486799 depth/1311867231.486799.png +1311867231.505980 rgb/1311867231.505980.png 1311867231.519303 depth/1311867231.519303.png +1311867231.538096 rgb/1311867231.538096.png 1311867231.552415 depth/1311867231.552415.png +1311867231.574153 rgb/1311867231.574153.png 1311867231.585585 depth/1311867231.585585.png +1311867231.605955 rgb/1311867231.605955.png 1311867231.621082 depth/1311867231.621082.png +1311867231.638125 rgb/1311867231.638125.png 1311867231.652217 depth/1311867231.652217.png +1311867231.674142 rgb/1311867231.674142.png 1311867231.688050 depth/1311867231.688050.png +1311867231.705921 rgb/1311867231.705921.png 1311867231.720809 depth/1311867231.720809.png +1311867231.738011 rgb/1311867231.738011.png 1311867231.752308 depth/1311867231.752308.png +1311867231.774173 rgb/1311867231.774173.png 1311867231.786059 depth/1311867231.786059.png +1311867231.805931 rgb/1311867231.805931.png 1311867231.820213 depth/1311867231.820213.png +1311867231.838039 rgb/1311867231.838039.png 1311867231.852184 depth/1311867231.852184.png +1311867231.873920 rgb/1311867231.873920.png 1311867231.885750 depth/1311867231.885750.png +1311867231.905983 rgb/1311867231.905983.png 1311867231.920856 depth/1311867231.920856.png +1311867231.938028 rgb/1311867231.938028.png 1311867231.953318 depth/1311867231.953318.png +1311867231.974086 rgb/1311867231.974086.png 1311867231.987049 depth/1311867231.987049.png +1311867232.006124 rgb/1311867232.006124.png 1311867232.020286 depth/1311867232.020286.png +1311867232.038052 rgb/1311867232.038052.png 1311867232.052242 depth/1311867232.052242.png +1311867232.074075 rgb/1311867232.074075.png 1311867232.087849 depth/1311867232.087849.png +1311867232.106162 rgb/1311867232.106162.png 1311867232.120324 depth/1311867232.120324.png +1311867232.138161 rgb/1311867232.138161.png 1311867232.154551 depth/1311867232.154551.png +1311867232.173947 rgb/1311867232.173947.png 1311867232.184618 depth/1311867232.184618.png +1311867232.206061 rgb/1311867232.206061.png 1311867232.220978 depth/1311867232.220978.png +1311867232.241970 rgb/1311867232.241970.png 1311867232.253112 depth/1311867232.253112.png +1311867232.273986 rgb/1311867232.273986.png 1311867232.284448 depth/1311867232.284448.png +1311867232.305979 rgb/1311867232.305979.png 1311867232.320979 depth/1311867232.320979.png +1311867232.342085 rgb/1311867232.342085.png 1311867232.354466 depth/1311867232.354466.png +1311867232.374074 rgb/1311867232.374074.png 1311867232.385891 depth/1311867232.385891.png +1311867232.405964 rgb/1311867232.405964.png 1311867232.420391 depth/1311867232.420391.png +1311867232.442125 rgb/1311867232.442125.png 1311867232.454456 depth/1311867232.454456.png +1311867232.473958 rgb/1311867232.473958.png 1311867232.484601 depth/1311867232.484601.png +1311867232.505952 rgb/1311867232.505952.png 1311867232.520303 depth/1311867232.520303.png +1311867232.542122 rgb/1311867232.542122.png 1311867232.555005 depth/1311867232.555005.png +1311867232.573937 rgb/1311867232.573937.png 1311867232.584432 depth/1311867232.584432.png +1311867232.606133 rgb/1311867232.606133.png 1311867232.620160 depth/1311867232.620160.png +1311867232.642128 rgb/1311867232.642128.png 1311867232.655486 depth/1311867232.655486.png +1311867232.674004 rgb/1311867232.674004.png 1311867232.685049 depth/1311867232.685049.png +1311867232.706009 rgb/1311867232.706009.png 1311867232.721032 depth/1311867232.721032.png +1311867232.742111 rgb/1311867232.742111.png 1311867232.753952 depth/1311867232.753952.png +1311867232.774049 rgb/1311867232.774049.png 1311867232.788581 depth/1311867232.788581.png +1311867232.805985 rgb/1311867232.805985.png 1311867232.820617 depth/1311867232.820617.png +1311867232.842129 rgb/1311867232.842129.png 1311867232.853937 depth/1311867232.853937.png +1311867232.874052 rgb/1311867232.874052.png 1311867232.888271 depth/1311867232.888271.png +1311867232.906135 rgb/1311867232.906135.png 1311867232.920377 depth/1311867232.920377.png +1311867232.942097 rgb/1311867232.942097.png 1311867232.955990 depth/1311867232.955990.png +1311867232.974275 rgb/1311867232.974275.png 1311867232.989004 depth/1311867232.989004.png +1311867233.006058 rgb/1311867233.006058.png 1311867233.021226 depth/1311867233.021226.png +1311867233.042232 rgb/1311867233.042232.png 1311867233.056929 depth/1311867233.056929.png +1311867233.108859 rgb/1311867233.108859.png 1311867233.094320 depth/1311867233.094320.png +1311867233.142135 rgb/1311867233.142135.png 1311867233.153080 depth/1311867233.153080.png +1311867233.174057 rgb/1311867233.174057.png 1311867233.188768 depth/1311867233.188768.png +1311867233.206774 rgb/1311867233.206774.png 1311867233.221048 depth/1311867233.221048.png +1311867233.274216 rgb/1311867233.274216.png 1311867233.259018 depth/1311867233.259018.png +1311867233.306062 rgb/1311867233.306062.png 1311867233.321221 depth/1311867233.321221.png +1311867233.342453 rgb/1311867233.342453.png 1311867233.353385 depth/1311867233.353385.png +1311867233.374066 rgb/1311867233.374066.png 1311867233.388456 depth/1311867233.388456.png +1311867233.406026 rgb/1311867233.406026.png 1311867233.423667 depth/1311867233.423667.png +1311867233.442194 rgb/1311867233.442194.png 1311867233.452270 depth/1311867233.452270.png +1311867233.474076 rgb/1311867233.474076.png 1311867233.488161 depth/1311867233.488161.png +1311867233.506601 rgb/1311867233.506601.png 1311867233.520120 depth/1311867233.520120.png +1311867233.542082 rgb/1311867233.542082.png 1311867233.552627 depth/1311867233.552627.png +1311867233.574217 rgb/1311867233.574217.png 1311867233.589085 depth/1311867233.589085.png +1311867233.606173 rgb/1311867233.606173.png 1311867233.620262 depth/1311867233.620262.png +1311867233.642267 rgb/1311867233.642267.png 1311867233.653908 depth/1311867233.653908.png +1311867233.674202 rgb/1311867233.674202.png 1311867233.687929 depth/1311867233.687929.png +1311867233.706461 rgb/1311867233.706461.png 1311867233.719779 depth/1311867233.719779.png +1311867233.742420 rgb/1311867233.742420.png 1311867233.757754 depth/1311867233.757754.png +1311867233.774073 rgb/1311867233.774073.png 1311867233.789609 depth/1311867233.789609.png +1311867233.806227 rgb/1311867233.806227.png 1311867233.822119 depth/1311867233.822119.png +1311867233.842183 rgb/1311867233.842183.png 1311867233.856245 depth/1311867233.856245.png +1311867233.874229 rgb/1311867233.874229.png 1311867233.888569 depth/1311867233.888569.png +1311867233.906084 rgb/1311867233.906084.png 1311867233.920345 depth/1311867233.920345.png +1311867233.942192 rgb/1311867233.942192.png 1311867233.955291 depth/1311867233.955291.png +1311867233.974249 rgb/1311867233.974249.png 1311867233.988590 depth/1311867233.988590.png +1311867234.006205 rgb/1311867234.006205.png 1311867234.020583 depth/1311867234.020583.png +1311867234.042205 rgb/1311867234.042205.png 1311867234.056624 depth/1311867234.056624.png +1311867234.074349 rgb/1311867234.074349.png 1311867234.090717 depth/1311867234.090717.png +1311867234.106175 rgb/1311867234.106175.png 1311867234.121452 depth/1311867234.121452.png +1311867234.142473 rgb/1311867234.142473.png 1311867234.156169 depth/1311867234.156169.png +1311867234.174383 rgb/1311867234.174383.png 1311867234.189256 depth/1311867234.189256.png +1311867234.206312 rgb/1311867234.206312.png 1311867234.220360 depth/1311867234.220360.png +1311867234.242292 rgb/1311867234.242292.png 1311867234.258893 depth/1311867234.258893.png +1311867234.274294 rgb/1311867234.274294.png 1311867234.289532 depth/1311867234.289532.png +1311867234.306469 rgb/1311867234.306469.png 1311867234.321320 depth/1311867234.321320.png +1311867234.342355 rgb/1311867234.342355.png 1311867234.357013 depth/1311867234.357013.png +1311867234.374159 rgb/1311867234.374159.png 1311867234.388577 depth/1311867234.388577.png +1311867234.406260 rgb/1311867234.406260.png 1311867234.420491 depth/1311867234.420491.png +1311867234.442238 rgb/1311867234.442238.png 1311867234.457992 depth/1311867234.457992.png +1311867234.474248 rgb/1311867234.474248.png 1311867234.487896 depth/1311867234.487896.png +1311867234.506308 rgb/1311867234.506308.png 1311867234.520124 depth/1311867234.520124.png +1311867234.542293 rgb/1311867234.542293.png 1311867234.559428 depth/1311867234.559428.png +1311867234.574192 rgb/1311867234.574192.png 1311867234.588238 depth/1311867234.588238.png +1311867234.606098 rgb/1311867234.606098.png 1311867234.620420 depth/1311867234.620420.png +1311867234.642267 rgb/1311867234.642267.png 1311867234.659091 depth/1311867234.659091.png +1311867234.674096 rgb/1311867234.674096.png 1311867234.688046 depth/1311867234.688046.png +1311867234.706095 rgb/1311867234.706095.png 1311867234.719878 depth/1311867234.719878.png +1311867234.742287 rgb/1311867234.742287.png 1311867234.758618 depth/1311867234.758618.png +1311867234.774140 rgb/1311867234.774140.png 1311867234.788261 depth/1311867234.788261.png +1311867234.806072 rgb/1311867234.806072.png 1311867234.820656 depth/1311867234.820656.png +1311867234.842326 rgb/1311867234.842326.png 1311867234.859025 depth/1311867234.859025.png +1311867234.874157 rgb/1311867234.874157.png 1311867234.888123 depth/1311867234.888123.png +1311867234.906187 rgb/1311867234.906187.png 1311867234.920493 depth/1311867234.920493.png +1311867234.942270 rgb/1311867234.942270.png 1311867234.956609 depth/1311867234.956609.png +1311867234.974155 rgb/1311867234.974155.png 1311867234.990409 depth/1311867234.990409.png +1311867235.006175 rgb/1311867235.006175.png 1311867235.020599 depth/1311867235.020599.png +1311867235.042326 rgb/1311867235.042326.png 1311867235.056381 depth/1311867235.056381.png +1311867235.074182 rgb/1311867235.074182.png 1311867235.091115 depth/1311867235.091115.png +1311867235.106252 rgb/1311867235.106252.png 1311867235.120814 depth/1311867235.120814.png +1311867235.142245 rgb/1311867235.142245.png 1311867235.156407 depth/1311867235.156407.png +1311867235.174301 rgb/1311867235.174301.png 1311867235.188568 depth/1311867235.188568.png +1311867235.206197 rgb/1311867235.206197.png 1311867235.220209 depth/1311867235.220209.png +1311867235.242257 rgb/1311867235.242257.png 1311867235.257626 depth/1311867235.257626.png +1311867235.274183 rgb/1311867235.274183.png 1311867235.289966 depth/1311867235.289966.png +1311867235.306202 rgb/1311867235.306202.png 1311867235.324783 depth/1311867235.324783.png +1311867235.342289 rgb/1311867235.342289.png 1311867235.356780 depth/1311867235.356780.png +1311867235.374391 rgb/1311867235.374391.png 1311867235.388628 depth/1311867235.388628.png +1311867235.406214 rgb/1311867235.406214.png 1311867235.424619 depth/1311867235.424619.png +1311867235.442222 rgb/1311867235.442222.png 1311867235.456485 depth/1311867235.456485.png +1311867235.474167 rgb/1311867235.474167.png 1311867235.489793 depth/1311867235.489793.png +1311867235.506159 rgb/1311867235.506159.png 1311867235.524072 depth/1311867235.524072.png +1311867235.542321 rgb/1311867235.542321.png 1311867235.557729 depth/1311867235.557729.png +1311867235.574193 rgb/1311867235.574193.png 1311867235.588064 depth/1311867235.588064.png +1311867235.606195 rgb/1311867235.606195.png 1311867235.624994 depth/1311867235.624994.png +1311867235.642444 rgb/1311867235.642444.png 1311867235.656327 depth/1311867235.656327.png +1311867235.674238 rgb/1311867235.674238.png 1311867235.688562 depth/1311867235.688562.png +1311867235.706367 rgb/1311867235.706367.png 1311867235.724195 depth/1311867235.724195.png +1311867235.742311 rgb/1311867235.742311.png 1311867235.756172 depth/1311867235.756172.png +1311867235.806313 rgb/1311867235.806313.png 1311867235.790328 depth/1311867235.790328.png +1311867235.842280 rgb/1311867235.842280.png 1311867235.856217 depth/1311867235.856217.png +1311867235.874209 rgb/1311867235.874209.png 1311867235.888105 depth/1311867235.888105.png +1311867235.906374 rgb/1311867235.906374.png 1311867235.923990 depth/1311867235.923990.png +1311867235.942343 rgb/1311867235.942343.png 1311867235.956376 depth/1311867235.956376.png +1311867235.974196 rgb/1311867235.974196.png 1311867235.989095 depth/1311867235.989095.png +1311867236.042378 rgb/1311867236.042378.png 1311867236.025045 depth/1311867236.025045.png +1311867236.074226 rgb/1311867236.074226.png 1311867236.088486 depth/1311867236.088486.png +1311867236.106358 rgb/1311867236.106358.png 1311867236.124704 depth/1311867236.124704.png +1311867236.142358 rgb/1311867236.142358.png 1311867236.158129 depth/1311867236.158129.png +1311867236.174242 rgb/1311867236.174242.png 1311867236.190153 depth/1311867236.190153.png +1311867236.206222 rgb/1311867236.206222.png 1311867236.224233 depth/1311867236.224233.png +1311867236.274266 rgb/1311867236.274266.png 1311867236.259949 depth/1311867236.259949.png +1311867236.306429 rgb/1311867236.306429.png 1311867236.289042 depth/1311867236.289042.png +1311867236.342291 rgb/1311867236.342291.png 1311867236.356881 depth/1311867236.356881.png +1311867236.374298 rgb/1311867236.374298.png 1311867236.389742 depth/1311867236.389742.png +1311867236.406251 rgb/1311867236.406251.png 1311867236.424339 depth/1311867236.424339.png +1311867236.442391 rgb/1311867236.442391.png 1311867236.456604 depth/1311867236.456604.png +1311867236.506314 rgb/1311867236.506314.png 1311867236.493613 depth/1311867236.493613.png +1311867236.542354 rgb/1311867236.542354.png 1311867236.524700 depth/1311867236.524700.png +1311867236.574217 rgb/1311867236.574217.png 1311867236.560210 depth/1311867236.560210.png +1311867236.606288 rgb/1311867236.606288.png 1311867236.597291 depth/1311867236.597291.png +1311867236.642388 rgb/1311867236.642388.png 1311867236.624658 depth/1311867236.624658.png +1311867236.674478 rgb/1311867236.674478.png 1311867236.660048 depth/1311867236.660048.png +1311867236.706587 rgb/1311867236.706587.png 1311867236.695666 depth/1311867236.695666.png +1311867236.742471 rgb/1311867236.742471.png 1311867236.727637 depth/1311867236.727637.png +1311867236.774407 rgb/1311867236.774407.png 1311867236.761927 depth/1311867236.761927.png +1311867236.806389 rgb/1311867236.806389.png 1311867236.792347 depth/1311867236.792347.png +1311867236.842397 rgb/1311867236.842397.png 1311867236.858344 depth/1311867236.858344.png +1311867236.906286 rgb/1311867236.906286.png 1311867236.892848 depth/1311867236.892848.png +1311867236.942486 rgb/1311867236.942486.png 1311867236.958196 depth/1311867236.958196.png +1311867237.006457 rgb/1311867237.006457.png 1311867236.993729 depth/1311867236.993729.png +1311867237.042352 rgb/1311867237.042352.png 1311867237.024420 depth/1311867237.024420.png +1311867237.074287 rgb/1311867237.074287.png 1311867237.060306 depth/1311867237.060306.png +1311867237.106376 rgb/1311867237.106376.png 1311867237.092759 depth/1311867237.092759.png +1311867237.142401 rgb/1311867237.142401.png 1311867237.156658 depth/1311867237.156658.png +1311867237.206351 rgb/1311867237.206351.png 1311867237.192595 depth/1311867237.192595.png +1311867237.242389 rgb/1311867237.242389.png 1311867237.256958 depth/1311867237.256958.png +1311867237.306833 rgb/1311867237.306833.png 1311867237.294428 depth/1311867237.294428.png +1311867237.342478 rgb/1311867237.342478.png 1311867237.356531 depth/1311867237.356531.png +1311867237.406529 rgb/1311867237.406529.png 1311867237.393498 depth/1311867237.393498.png +1311867237.442502 rgb/1311867237.442502.png 1311867237.457951 depth/1311867237.457951.png +1311867237.506364 rgb/1311867237.506364.png 1311867237.493356 depth/1311867237.493356.png +1311867237.542505 rgb/1311867237.542505.png 1311867237.558123 depth/1311867237.558123.png +1311867237.606410 rgb/1311867237.606410.png 1311867237.592535 depth/1311867237.592535.png +1311867237.642379 rgb/1311867237.642379.png 1311867237.656929 depth/1311867237.656929.png +1311867237.706366 rgb/1311867237.706366.png 1311867237.692501 depth/1311867237.692501.png +1311867237.742584 rgb/1311867237.742584.png 1311867237.724361 depth/1311867237.724361.png +1311867237.774590 rgb/1311867237.774590.png 1311867237.761794 depth/1311867237.761794.png +1311867237.806458 rgb/1311867237.806458.png 1311867237.792681 depth/1311867237.792681.png +1311867237.842501 rgb/1311867237.842501.png 1311867237.825582 depth/1311867237.825582.png +1311867237.874551 rgb/1311867237.874551.png 1311867237.861270 depth/1311867237.861270.png +1311867237.906433 rgb/1311867237.906433.png 1311867237.892606 depth/1311867237.892606.png +1311867237.942660 rgb/1311867237.942660.png 1311867237.925359 depth/1311867237.925359.png +1311867237.974431 rgb/1311867237.974431.png 1311867237.961351 depth/1311867237.961351.png +1311867238.006500 rgb/1311867238.006500.png 1311867237.992891 depth/1311867237.992891.png +1311867238.042572 rgb/1311867238.042572.png 1311867238.024592 depth/1311867238.024592.png +1311867238.074515 rgb/1311867238.074515.png 1311867238.060795 depth/1311867238.060795.png +1311867238.106429 rgb/1311867238.106429.png 1311867238.093263 depth/1311867238.093263.png +1311867238.142402 rgb/1311867238.142402.png 1311867238.125193 depth/1311867238.125193.png +1311867238.174577 rgb/1311867238.174577.png 1311867238.160847 depth/1311867238.160847.png +1311867238.206467 rgb/1311867238.206467.png 1311867238.192851 depth/1311867238.192851.png +1311867238.242454 rgb/1311867238.242454.png 1311867238.224677 depth/1311867238.224677.png +1311867238.274552 rgb/1311867238.274552.png 1311867238.260594 depth/1311867238.260594.png +1311867238.306377 rgb/1311867238.306377.png 1311867238.292679 depth/1311867238.292679.png +1311867238.342532 rgb/1311867238.342532.png 1311867238.325781 depth/1311867238.325781.png +1311867238.374439 rgb/1311867238.374439.png 1311867238.360439 depth/1311867238.360439.png +1311867238.406474 rgb/1311867238.406474.png 1311867238.393638 depth/1311867238.393638.png +1311867238.442421 rgb/1311867238.442421.png 1311867238.426405 depth/1311867238.426405.png +1311867238.474426 rgb/1311867238.474426.png 1311867238.461621 depth/1311867238.461621.png +1311867238.506473 rgb/1311867238.506473.png 1311867238.493255 depth/1311867238.493255.png +1311867238.542703 rgb/1311867238.542703.png 1311867238.524866 depth/1311867238.524866.png +1311867238.574615 rgb/1311867238.574615.png 1311867238.560593 depth/1311867238.560593.png +1311867238.606413 rgb/1311867238.606413.png 1311867238.592912 depth/1311867238.592912.png +1311867238.642378 rgb/1311867238.642378.png 1311867238.624987 depth/1311867238.624987.png +1311867238.674405 rgb/1311867238.674405.png 1311867238.660848 depth/1311867238.660848.png +1311867238.706486 rgb/1311867238.706486.png 1311867238.692936 depth/1311867238.692936.png +1311867238.742522 rgb/1311867238.742522.png 1311867238.724636 depth/1311867238.724636.png +1311867238.774397 rgb/1311867238.774397.png 1311867238.762797 depth/1311867238.762797.png +1311867238.806422 rgb/1311867238.806422.png 1311867238.794992 depth/1311867238.794992.png +1311867238.842541 rgb/1311867238.842541.png 1311867238.824682 depth/1311867238.824682.png +1311867238.874418 rgb/1311867238.874418.png 1311867238.863058 depth/1311867238.863058.png +1311867238.906451 rgb/1311867238.906451.png 1311867238.893389 depth/1311867238.893389.png +1311867238.942510 rgb/1311867238.942510.png 1311867238.927898 depth/1311867238.927898.png +1311867238.974527 rgb/1311867238.974527.png 1311867238.962805 depth/1311867238.962805.png +1311867239.006405 rgb/1311867239.006405.png 1311867238.993782 depth/1311867238.993782.png +1311867239.042587 rgb/1311867239.042587.png 1311867239.028730 depth/1311867239.028730.png +1311867239.074592 rgb/1311867239.074592.png 1311867239.061998 depth/1311867239.061998.png +1311867239.106416 rgb/1311867239.106416.png 1311867239.093924 depth/1311867239.093924.png +1311867239.143039 rgb/1311867239.143039.png 1311867239.135811 depth/1311867239.135811.png +1311867239.174559 rgb/1311867239.174559.png 1311867239.162055 depth/1311867239.162055.png +1311867239.206507 rgb/1311867239.206507.png 1311867239.193657 depth/1311867239.193657.png +1311867239.242615 rgb/1311867239.242615.png 1311867239.229495 depth/1311867239.229495.png +1311867239.274466 rgb/1311867239.274466.png 1311867239.260915 depth/1311867239.260915.png +1311867239.306409 rgb/1311867239.306409.png 1311867239.292879 depth/1311867239.292879.png +1311867239.342486 rgb/1311867239.342486.png 1311867239.329529 depth/1311867239.329529.png +1311867239.374562 rgb/1311867239.374562.png 1311867239.361500 depth/1311867239.361500.png +1311867239.406592 rgb/1311867239.406592.png 1311867239.392841 depth/1311867239.392841.png +1311867239.442634 rgb/1311867239.442634.png 1311867239.429329 depth/1311867239.429329.png +1311867239.474517 rgb/1311867239.474517.png 1311867239.461906 depth/1311867239.461906.png +1311867239.506556 rgb/1311867239.506556.png 1311867239.493825 depth/1311867239.493825.png +1311867239.542637 rgb/1311867239.542637.png 1311867239.529502 depth/1311867239.529502.png +1311867239.574603 rgb/1311867239.574603.png 1311867239.561707 depth/1311867239.561707.png +1311867239.606412 rgb/1311867239.606412.png 1311867239.594491 depth/1311867239.594491.png +1311867239.642581 rgb/1311867239.642581.png 1311867239.628443 depth/1311867239.628443.png +1311867239.674585 rgb/1311867239.674585.png 1311867239.662309 depth/1311867239.662309.png +1311867239.706420 rgb/1311867239.706420.png 1311867239.693124 depth/1311867239.693124.png +1311867239.742532 rgb/1311867239.742532.png 1311867239.728495 depth/1311867239.728495.png +1311867239.774489 rgb/1311867239.774489.png 1311867239.761461 depth/1311867239.761461.png +1311867239.806512 rgb/1311867239.806512.png 1311867239.792615 depth/1311867239.792615.png +1311867239.842582 rgb/1311867239.842582.png 1311867239.830832 depth/1311867239.830832.png +1311867239.874576 rgb/1311867239.874576.png 1311867239.860844 depth/1311867239.860844.png +1311867239.906569 rgb/1311867239.906569.png 1311867239.892907 depth/1311867239.892907.png +1311867239.942408 rgb/1311867239.942408.png 1311867239.930660 depth/1311867239.930660.png +1311867239.976213 rgb/1311867239.976213.png 1311867239.961370 depth/1311867239.961370.png +1311867240.006746 rgb/1311867240.006746.png 1311867239.994822 depth/1311867239.994822.png +1311867240.042506 rgb/1311867240.042506.png 1311867240.029229 depth/1311867240.029229.png +1311867240.074598 rgb/1311867240.074598.png 1311867240.061881 depth/1311867240.061881.png +1311867240.106559 rgb/1311867240.106559.png 1311867240.094551 depth/1311867240.094551.png +1311867240.142844 rgb/1311867240.142844.png 1311867240.129751 depth/1311867240.129751.png +1311867240.174466 rgb/1311867240.174466.png 1311867240.161724 depth/1311867240.161724.png +1311867240.206552 rgb/1311867240.206552.png 1311867240.196313 depth/1311867240.196313.png +1311867240.242433 rgb/1311867240.242433.png 1311867240.229103 depth/1311867240.229103.png +1311867240.274677 rgb/1311867240.274677.png 1311867240.261276 depth/1311867240.261276.png +1311867240.306544 rgb/1311867240.306544.png 1311867240.298125 depth/1311867240.298125.png +1311867240.342481 rgb/1311867240.342481.png 1311867240.328916 depth/1311867240.328916.png +1311867240.374466 rgb/1311867240.374466.png 1311867240.360940 depth/1311867240.360940.png +1311867240.406662 rgb/1311867240.406662.png 1311867240.396789 depth/1311867240.396789.png +1311867240.442598 rgb/1311867240.442598.png 1311867240.428689 depth/1311867240.428689.png +1311867240.474536 rgb/1311867240.474536.png 1311867240.465085 depth/1311867240.465085.png +1311867240.506469 rgb/1311867240.506469.png 1311867240.497290 depth/1311867240.497290.png +1311867240.542590 rgb/1311867240.542590.png 1311867240.530998 depth/1311867240.530998.png +1311867240.574511 rgb/1311867240.574511.png 1311867240.560821 depth/1311867240.560821.png +1311867240.606557 rgb/1311867240.606557.png 1311867240.596599 depth/1311867240.596599.png +1311867240.642795 rgb/1311867240.642795.png 1311867240.629079 depth/1311867240.629079.png +1311867240.674613 rgb/1311867240.674613.png 1311867240.662256 depth/1311867240.662256.png +1311867240.706562 rgb/1311867240.706562.png 1311867240.696880 depth/1311867240.696880.png +1311867240.742631 rgb/1311867240.742631.png 1311867240.729198 depth/1311867240.729198.png +1311867240.774678 rgb/1311867240.774678.png 1311867240.762563 depth/1311867240.762563.png +1311867240.806605 rgb/1311867240.806605.png 1311867240.796572 depth/1311867240.796572.png +1311867240.842940 rgb/1311867240.842940.png 1311867240.829331 depth/1311867240.829331.png +1311867240.874843 rgb/1311867240.874843.png 1311867240.862110 depth/1311867240.862110.png +1311867240.906548 rgb/1311867240.906548.png 1311867240.897350 depth/1311867240.897350.png +1311867240.942559 rgb/1311867240.942559.png 1311867240.929027 depth/1311867240.929027.png +1311867240.974622 rgb/1311867240.974622.png 1311867240.961437 depth/1311867240.961437.png +1311867241.006716 rgb/1311867241.006716.png 1311867240.996845 depth/1311867240.996845.png +1311867241.042623 rgb/1311867241.042623.png 1311867241.031562 depth/1311867241.031562.png +1311867241.074792 rgb/1311867241.074792.png 1311867241.063367 depth/1311867241.063367.png +1311867241.106779 rgb/1311867241.106779.png 1311867241.099010 depth/1311867241.099010.png +1311867241.142854 rgb/1311867241.142854.png 1311867241.128529 depth/1311867241.128529.png +1311867241.174730 rgb/1311867241.174730.png 1311867241.164150 depth/1311867241.164150.png +1311867241.206721 rgb/1311867241.206721.png 1311867241.198012 depth/1311867241.198012.png +1311867241.242631 rgb/1311867241.242631.png 1311867241.231333 depth/1311867241.231333.png +1311867241.275069 rgb/1311867241.275069.png 1311867241.264070 depth/1311867241.264070.png +1311867241.310769 rgb/1311867241.310769.png 1311867241.300061 depth/1311867241.300061.png +1311867241.342582 rgb/1311867241.342582.png 1311867241.329485 depth/1311867241.329485.png +1311867241.374677 rgb/1311867241.374677.png 1311867241.361255 depth/1311867241.361255.png +1311867241.410635 rgb/1311867241.410635.png 1311867241.398114 depth/1311867241.398114.png +1311867241.442620 rgb/1311867241.442620.png 1311867241.430059 depth/1311867241.430059.png +1311867241.474896 rgb/1311867241.474896.png 1311867241.465201 depth/1311867241.465201.png +1311867241.510751 rgb/1311867241.510751.png 1311867241.496979 depth/1311867241.496979.png +1311867241.542602 rgb/1311867241.542602.png 1311867241.533172 depth/1311867241.533172.png +1311867241.574823 rgb/1311867241.574823.png 1311867241.565696 depth/1311867241.565696.png +1311867241.610604 rgb/1311867241.610604.png 1311867241.600248 depth/1311867241.600248.png +1311867241.642627 rgb/1311867241.642627.png 1311867241.629120 depth/1311867241.629120.png +1311867241.674668 rgb/1311867241.674668.png 1311867241.664679 depth/1311867241.664679.png +1311867241.710757 rgb/1311867241.710757.png 1311867241.699926 depth/1311867241.699926.png +1311867241.742749 rgb/1311867241.742749.png 1311867241.729765 depth/1311867241.729765.png +1311867241.774620 rgb/1311867241.774620.png 1311867241.767664 depth/1311867241.767664.png +1311867241.810714 rgb/1311867241.810714.png 1311867241.797485 depth/1311867241.797485.png +1311867241.842840 rgb/1311867241.842840.png 1311867241.829655 depth/1311867241.829655.png +1311867241.874966 rgb/1311867241.874966.png 1311867241.866892 depth/1311867241.866892.png +1311867241.910597 rgb/1311867241.910597.png 1311867241.897969 depth/1311867241.897969.png +1311867241.942934 rgb/1311867241.942934.png 1311867241.929262 depth/1311867241.929262.png +1311867241.974655 rgb/1311867241.974655.png 1311867241.965404 depth/1311867241.965404.png +1311867242.010806 rgb/1311867242.010806.png 1311867241.997403 depth/1311867241.997403.png +1311867242.042670 rgb/1311867242.042670.png 1311867242.029634 depth/1311867242.029634.png +1311867242.074787 rgb/1311867242.074787.png 1311867242.067006 depth/1311867242.067006.png +1311867242.110732 rgb/1311867242.110732.png 1311867242.097251 depth/1311867242.097251.png +1311867242.142880 rgb/1311867242.142880.png 1311867242.130804 depth/1311867242.130804.png +1311867242.174884 rgb/1311867242.174884.png 1311867242.167018 depth/1311867242.167018.png +1311867242.210643 rgb/1311867242.210643.png 1311867242.198241 depth/1311867242.198241.png +1311867242.242719 rgb/1311867242.242719.png 1311867242.233437 depth/1311867242.233437.png +1311867242.275028 rgb/1311867242.275028.png 1311867242.269660 depth/1311867242.269660.png +1311867242.310756 rgb/1311867242.310756.png 1311867242.298243 depth/1311867242.298243.png +1311867242.342625 rgb/1311867242.342625.png 1311867242.329349 depth/1311867242.329349.png +1311867242.374628 rgb/1311867242.374628.png 1311867242.365946 depth/1311867242.365946.png +1311867242.410601 rgb/1311867242.410601.png 1311867242.397480 depth/1311867242.397480.png +1311867242.442670 rgb/1311867242.442670.png 1311867242.432277 depth/1311867242.432277.png +1311867242.474794 rgb/1311867242.474794.png 1311867242.464899 depth/1311867242.464899.png +1311867242.510745 rgb/1311867242.510745.png 1311867242.497561 depth/1311867242.497561.png +1311867242.542677 rgb/1311867242.542677.png 1311867242.529257 depth/1311867242.529257.png +1311867242.574755 rgb/1311867242.574755.png 1311867242.565094 depth/1311867242.565094.png +1311867242.610840 rgb/1311867242.610840.png 1311867242.598503 depth/1311867242.598503.png +1311867242.642862 rgb/1311867242.642862.png 1311867242.630559 depth/1311867242.630559.png +1311867242.674755 rgb/1311867242.674755.png 1311867242.669274 depth/1311867242.669274.png +1311867242.710770 rgb/1311867242.710770.png 1311867242.698104 depth/1311867242.698104.png +1311867242.742836 rgb/1311867242.742836.png 1311867242.737283 depth/1311867242.737283.png +1311867242.774742 rgb/1311867242.774742.png 1311867242.765690 depth/1311867242.765690.png +1311867242.810922 rgb/1311867242.810922.png 1311867242.799409 depth/1311867242.799409.png +1311867242.842725 rgb/1311867242.842725.png 1311867242.835554 depth/1311867242.835554.png +1311867242.874716 rgb/1311867242.874716.png 1311867242.866672 depth/1311867242.866672.png +1311867242.910777 rgb/1311867242.910777.png 1311867242.898093 depth/1311867242.898093.png +1311867242.942636 rgb/1311867242.942636.png 1311867242.933550 depth/1311867242.933550.png +1311867242.974656 rgb/1311867242.974656.png 1311867242.965000 depth/1311867242.965000.png +1311867243.010665 rgb/1311867243.010665.png 1311867242.997082 depth/1311867242.997082.png +1311867243.042682 rgb/1311867243.042682.png 1311867243.033253 depth/1311867243.033253.png +1311867243.074944 rgb/1311867243.074944.png 1311867243.064869 depth/1311867243.064869.png +1311867243.110760 rgb/1311867243.110760.png 1311867243.097216 depth/1311867243.097216.png +1311867243.142942 rgb/1311867243.142942.png 1311867243.135710 depth/1311867243.135710.png +1311867243.174792 rgb/1311867243.174792.png 1311867243.165596 depth/1311867243.165596.png +1311867243.210671 rgb/1311867243.210671.png 1311867243.197717 depth/1311867243.197717.png +1311867243.242923 rgb/1311867243.242923.png 1311867243.235886 depth/1311867243.235886.png +1311867243.274872 rgb/1311867243.274872.png 1311867243.264924 depth/1311867243.264924.png +1311867243.310909 rgb/1311867243.310909.png 1311867243.297022 depth/1311867243.297022.png +1311867243.342681 rgb/1311867243.342681.png 1311867243.332754 depth/1311867243.332754.png +1311867243.375787 rgb/1311867243.375787.png 1311867243.368156 depth/1311867243.368156.png +1311867243.412082 rgb/1311867243.412082.png 1311867243.402182 depth/1311867243.402182.png +1311867243.442886 rgb/1311867243.442886.png 1311867243.434433 depth/1311867243.434433.png +1311867243.474884 rgb/1311867243.474884.png 1311867243.466551 depth/1311867243.466551.png +1311867243.510986 rgb/1311867243.510986.png 1311867243.498214 depth/1311867243.498214.png +1311867243.543026 rgb/1311867243.543026.png 1311867243.533978 depth/1311867243.533978.png +1311867243.574697 rgb/1311867243.574697.png 1311867243.566972 depth/1311867243.566972.png +1311867243.610776 rgb/1311867243.610776.png 1311867243.597834 depth/1311867243.597834.png +1311867243.642685 rgb/1311867243.642685.png 1311867243.633372 depth/1311867243.633372.png +1311867243.674867 rgb/1311867243.674867.png 1311867243.666153 depth/1311867243.666153.png +1311867243.710902 rgb/1311867243.710902.png 1311867243.698185 depth/1311867243.698185.png +1311867243.742761 rgb/1311867243.742761.png 1311867243.734471 depth/1311867243.734471.png +1311867243.774837 rgb/1311867243.774837.png 1311867243.766630 depth/1311867243.766630.png +1311867243.810755 rgb/1311867243.810755.png 1311867243.797977 depth/1311867243.797977.png +1311867243.842825 rgb/1311867243.842825.png 1311867243.833024 depth/1311867243.833024.png +1311867243.874795 rgb/1311867243.874795.png 1311867243.864769 depth/1311867243.864769.png +1311867243.911010 rgb/1311867243.911010.png 1311867243.896874 depth/1311867243.896874.png +1311867243.942765 rgb/1311867243.942765.png 1311867243.932996 depth/1311867243.932996.png +1311867243.974939 rgb/1311867243.974939.png 1311867243.966059 depth/1311867243.966059.png +1311867244.010938 rgb/1311867244.010938.png 1311867244.001674 depth/1311867244.001674.png +1311867244.042874 rgb/1311867244.042874.png 1311867244.034138 depth/1311867244.034138.png +1311867244.074729 rgb/1311867244.074729.png 1311867244.065579 depth/1311867244.065579.png +1311867244.110737 rgb/1311867244.110737.png 1311867244.101093 depth/1311867244.101093.png +1311867244.142752 rgb/1311867244.142752.png 1311867244.135309 depth/1311867244.135309.png +1311867244.174960 rgb/1311867244.174960.png 1311867244.164842 depth/1311867244.164842.png +1311867244.210998 rgb/1311867244.210998.png 1311867244.202474 depth/1311867244.202474.png +1311867244.242837 rgb/1311867244.242837.png 1311867244.233028 depth/1311867244.233028.png +1311867244.274849 rgb/1311867244.274849.png 1311867244.264902 depth/1311867244.264902.png +1311867244.311019 rgb/1311867244.311019.png 1311867244.301031 depth/1311867244.301031.png +1311867244.342945 rgb/1311867244.342945.png 1311867244.335519 depth/1311867244.335519.png +1311867244.374807 rgb/1311867244.374807.png 1311867244.364908 depth/1311867244.364908.png +1311867244.410917 rgb/1311867244.410917.png 1311867244.400876 depth/1311867244.400876.png +1311867244.442939 rgb/1311867244.442939.png 1311867244.432994 depth/1311867244.432994.png +1311867244.474845 rgb/1311867244.474845.png 1311867244.465451 depth/1311867244.465451.png +1311867244.510909 rgb/1311867244.510909.png 1311867244.505249 depth/1311867244.505249.png +1311867244.543087 rgb/1311867244.543087.png 1311867244.533099 depth/1311867244.533099.png +1311867244.574880 rgb/1311867244.574880.png 1311867244.566940 depth/1311867244.566940.png +1311867244.610794 rgb/1311867244.610794.png 1311867244.602703 depth/1311867244.602703.png +1311867244.642828 rgb/1311867244.642828.png 1311867244.632802 depth/1311867244.632802.png +1311867244.674838 rgb/1311867244.674838.png 1311867244.667245 depth/1311867244.667245.png +1311867244.710970 rgb/1311867244.710970.png 1311867244.701260 depth/1311867244.701260.png +1311867244.742796 rgb/1311867244.742796.png 1311867244.734632 depth/1311867244.734632.png +1311867244.774974 rgb/1311867244.774974.png 1311867244.765000 depth/1311867244.765000.png +1311867244.810910 rgb/1311867244.810910.png 1311867244.801532 depth/1311867244.801532.png +1311867244.842820 rgb/1311867244.842820.png 1311867244.833191 depth/1311867244.833191.png +1311867244.874902 rgb/1311867244.874902.png 1311867244.865157 depth/1311867244.865157.png +1311867244.910805 rgb/1311867244.910805.png 1311867244.901355 depth/1311867244.901355.png +1311867244.942839 rgb/1311867244.942839.png 1311867244.932874 depth/1311867244.932874.png +1311867244.974988 rgb/1311867244.974988.png 1311867244.965251 depth/1311867244.965251.png +1311867245.010872 rgb/1311867245.010872.png 1311867245.002272 depth/1311867245.002272.png +1311867245.042993 rgb/1311867245.042993.png 1311867245.034998 depth/1311867245.034998.png +1311867245.074920 rgb/1311867245.074920.png 1311867245.066473 depth/1311867245.066473.png +1311867245.111116 rgb/1311867245.111116.png 1311867245.104164 depth/1311867245.104164.png +1311867245.142920 rgb/1311867245.142920.png 1311867245.133805 depth/1311867245.133805.png +1311867245.174913 rgb/1311867245.174913.png 1311867245.174925 depth/1311867245.174925.png +1311867245.210898 rgb/1311867245.210898.png 1311867245.201638 depth/1311867245.201638.png +1311867245.242901 rgb/1311867245.242901.png 1311867245.234384 depth/1311867245.234384.png +1311867245.275567 rgb/1311867245.275567.png 1311867245.269269 depth/1311867245.269269.png +1311867245.312009 rgb/1311867245.312009.png 1311867245.302958 depth/1311867245.302958.png +1311867245.343010 rgb/1311867245.343010.png 1311867245.334163 depth/1311867245.334163.png +1311867245.374937 rgb/1311867245.374937.png 1311867245.372930 depth/1311867245.372930.png +1311867245.412235 rgb/1311867245.412235.png 1311867245.404540 depth/1311867245.404540.png +1311867245.442883 rgb/1311867245.442883.png 1311867245.434105 depth/1311867245.434105.png +1311867245.475145 rgb/1311867245.475145.png 1311867245.472801 depth/1311867245.472801.png +1311867245.510882 rgb/1311867245.510882.png 1311867245.500876 depth/1311867245.500876.png +1311867245.542961 rgb/1311867245.542961.png 1311867245.534361 depth/1311867245.534361.png +1311867245.574941 rgb/1311867245.574941.png 1311867245.570021 depth/1311867245.570021.png +1311867245.610913 rgb/1311867245.610913.png 1311867245.600959 depth/1311867245.600959.png +1311867245.642819 rgb/1311867245.642819.png 1311867245.633731 depth/1311867245.633731.png +1311867245.675175 rgb/1311867245.675175.png 1311867245.670091 depth/1311867245.670091.png +1311867245.710917 rgb/1311867245.710917.png 1311867245.702934 depth/1311867245.702934.png +1311867245.742982 rgb/1311867245.742982.png 1311867245.734221 depth/1311867245.734221.png +1311867245.775252 rgb/1311867245.775252.png 1311867245.772283 depth/1311867245.772283.png +1311867245.811035 rgb/1311867245.811035.png 1311867245.802066 depth/1311867245.802066.png +1311867245.842823 rgb/1311867245.842823.png 1311867245.833304 depth/1311867245.833304.png +1311867245.875777 rgb/1311867245.875777.png 1311867245.871926 depth/1311867245.871926.png +1311867245.911075 rgb/1311867245.911075.png 1311867245.900988 depth/1311867245.900988.png +1311867245.942887 rgb/1311867245.942887.png 1311867245.933643 depth/1311867245.933643.png +1311867245.975135 rgb/1311867245.975135.png 1311867245.971155 depth/1311867245.971155.png +1311867246.011242 rgb/1311867246.011242.png 1311867246.001374 depth/1311867246.001374.png +1311867246.042923 rgb/1311867246.042923.png 1311867246.033146 depth/1311867246.033146.png +1311867246.075233 rgb/1311867246.075233.png 1311867246.069018 depth/1311867246.069018.png +1311867246.110925 rgb/1311867246.110925.png 1311867246.101828 depth/1311867246.101828.png +1311867246.143089 rgb/1311867246.143089.png 1311867246.135545 depth/1311867246.135545.png +1311867246.174981 rgb/1311867246.174981.png 1311867246.169198 depth/1311867246.169198.png +1311867246.210964 rgb/1311867246.210964.png 1311867246.205140 depth/1311867246.205140.png +1311867246.242940 rgb/1311867246.242940.png 1311867246.234735 depth/1311867246.234735.png +1311867246.275065 rgb/1311867246.275065.png 1311867246.270863 depth/1311867246.270863.png +1311867246.310872 rgb/1311867246.310872.png 1311867246.303325 depth/1311867246.303325.png +1311867246.342932 rgb/1311867246.342932.png 1311867246.334051 depth/1311867246.334051.png +1311867246.375297 rgb/1311867246.375297.png 1311867246.373419 depth/1311867246.373419.png +1311867246.410931 rgb/1311867246.410931.png 1311867246.401213 depth/1311867246.401213.png +1311867246.443077 rgb/1311867246.443077.png 1311867246.437207 depth/1311867246.437207.png +1311867246.475133 rgb/1311867246.475133.png 1311867246.471314 depth/1311867246.471314.png +1311867246.510968 rgb/1311867246.510968.png 1311867246.502035 depth/1311867246.502035.png +1311867246.543113 rgb/1311867246.543113.png 1311867246.537040 depth/1311867246.537040.png +1311867246.575204 rgb/1311867246.575204.png 1311867246.571977 depth/1311867246.571977.png +1311867246.611125 rgb/1311867246.611125.png 1311867246.603266 depth/1311867246.603266.png +1311867246.643187 rgb/1311867246.643187.png 1311867246.638693 depth/1311867246.638693.png +1311867246.675169 rgb/1311867246.675169.png 1311867246.669333 depth/1311867246.669333.png +1311867246.711056 rgb/1311867246.711056.png 1311867246.704390 depth/1311867246.704390.png +1311867246.743305 rgb/1311867246.743305.png 1311867246.737272 depth/1311867246.737272.png +1311867246.774986 rgb/1311867246.774986.png 1311867246.769448 depth/1311867246.769448.png +1311867246.811193 rgb/1311867246.811193.png 1311867246.803849 depth/1311867246.803849.png +1311867246.843092 rgb/1311867246.843092.png 1311867246.838322 depth/1311867246.838322.png +1311867246.875078 rgb/1311867246.875078.png 1311867246.871268 depth/1311867246.871268.png +1311867246.911155 rgb/1311867246.911155.png 1311867246.904146 depth/1311867246.904146.png +1311867246.943061 rgb/1311867246.943061.png 1311867246.937355 depth/1311867246.937355.png +1311867246.975124 rgb/1311867246.975124.png 1311867246.972553 depth/1311867246.972553.png +1311867247.010909 rgb/1311867247.010909.png 1311867247.002134 depth/1311867247.002134.png +1311867247.044073 rgb/1311867247.044073.png 1311867247.041778 depth/1311867247.041778.png +1311867247.075192 rgb/1311867247.075192.png 1311867247.069851 depth/1311867247.069851.png +1311867247.111215 rgb/1311867247.111215.png 1311867247.101177 depth/1311867247.101177.png +1311867247.143044 rgb/1311867247.143044.png 1311867247.137342 depth/1311867247.137342.png +1311867247.175163 rgb/1311867247.175163.png 1311867247.169484 depth/1311867247.169484.png +1311867247.211319 rgb/1311867247.211319.png 1311867247.202060 depth/1311867247.202060.png +1311867247.243728 rgb/1311867247.243728.png 1311867247.239668 depth/1311867247.239668.png +1311867247.277719 rgb/1311867247.277719.png 1311867247.272079 depth/1311867247.272079.png +1311867247.310969 rgb/1311867247.310969.png 1311867247.301275 depth/1311867247.301275.png +1311867247.343205 rgb/1311867247.343205.png 1311867247.337565 depth/1311867247.337565.png +1311867247.375307 rgb/1311867247.375307.png 1311867247.369517 depth/1311867247.369517.png +1311867247.411675 rgb/1311867247.411675.png 1311867247.405433 depth/1311867247.405433.png +1311867247.444093 rgb/1311867247.444093.png 1311867247.438549 depth/1311867247.438549.png +1311867247.475103 rgb/1311867247.475103.png 1311867247.474843 depth/1311867247.474843.png +1311867247.511045 rgb/1311867247.511045.png 1311867247.501403 depth/1311867247.501403.png +1311867247.543085 rgb/1311867247.543085.png 1311867247.539732 depth/1311867247.539732.png +1311867247.575121 rgb/1311867247.575121.png 1311867247.569156 depth/1311867247.569156.png +1311867247.611460 rgb/1311867247.611460.png 1311867247.602480 depth/1311867247.602480.png +1311867247.643111 rgb/1311867247.643111.png 1311867247.638073 depth/1311867247.638073.png +1311867247.675076 rgb/1311867247.675076.png 1311867247.670014 depth/1311867247.670014.png +1311867247.711237 rgb/1311867247.711237.png 1311867247.706162 depth/1311867247.706162.png +1311867247.743122 rgb/1311867247.743122.png 1311867247.738313 depth/1311867247.738313.png +1311867247.775041 rgb/1311867247.775041.png 1311867247.773083 depth/1311867247.773083.png +1311867247.811163 rgb/1311867247.811163.png 1311867247.805402 depth/1311867247.805402.png +1311867247.843889 rgb/1311867247.843889.png 1311867247.837557 depth/1311867247.837557.png +1311867247.875244 rgb/1311867247.875244.png 1311867247.869021 depth/1311867247.869021.png +1311867247.911329 rgb/1311867247.911329.png 1311867247.907491 depth/1311867247.907491.png +1311867247.943062 rgb/1311867247.943062.png 1311867247.937547 depth/1311867247.937547.png +1311867247.976983 rgb/1311867247.976983.png 1311867247.970753 depth/1311867247.970753.png +1311867248.010991 rgb/1311867248.010991.png 1311867248.005384 depth/1311867248.005384.png +1311867248.043197 rgb/1311867248.043197.png 1311867248.037825 depth/1311867248.037825.png +1311867248.075142 rgb/1311867248.075142.png 1311867248.069890 depth/1311867248.069890.png +1311867248.112183 rgb/1311867248.112183.png 1311867248.108154 depth/1311867248.108154.png +1311867248.143172 rgb/1311867248.143172.png 1311867248.138760 depth/1311867248.138760.png +1311867248.175750 rgb/1311867248.175750.png 1311867248.169866 depth/1311867248.169866.png +1311867248.211186 rgb/1311867248.211186.png 1311867248.206824 depth/1311867248.206824.png +1311867248.243143 rgb/1311867248.243143.png 1311867248.238348 depth/1311867248.238348.png +1311867248.275529 rgb/1311867248.275529.png 1311867248.270402 depth/1311867248.270402.png +1311867248.311223 rgb/1311867248.311223.png 1311867248.308733 depth/1311867248.308733.png +1311867248.343459 rgb/1311867248.343459.png 1311867248.340448 depth/1311867248.340448.png +1311867248.375222 rgb/1311867248.375222.png 1311867248.369871 depth/1311867248.369871.png +1311867248.411556 rgb/1311867248.411556.png 1311867248.409835 depth/1311867248.409835.png +1311867248.443137 rgb/1311867248.443137.png 1311867248.438581 depth/1311867248.438581.png +1311867248.475923 rgb/1311867248.475923.png 1311867248.470199 depth/1311867248.470199.png +1311867248.511151 rgb/1311867248.511151.png 1311867248.508337 depth/1311867248.508337.png +1311867248.543189 rgb/1311867248.543189.png 1311867248.537785 depth/1311867248.537785.png +1311867248.575187 rgb/1311867248.575187.png 1311867248.572499 depth/1311867248.572499.png +1311867248.611439 rgb/1311867248.611439.png 1311867248.607009 depth/1311867248.607009.png +1311867248.643245 rgb/1311867248.643245.png 1311867248.638469 depth/1311867248.638469.png +1311867248.675309 rgb/1311867248.675309.png 1311867248.670252 depth/1311867248.670252.png +1311867248.711283 rgb/1311867248.711283.png 1311867248.706536 depth/1311867248.706536.png +1311867248.743299 rgb/1311867248.743299.png 1311867248.743305 depth/1311867248.743305.png +1311867248.776222 rgb/1311867248.776222.png 1311867248.769433 depth/1311867248.769433.png +1311867248.811190 rgb/1311867248.811190.png 1311867248.805206 depth/1311867248.805206.png +1311867248.843319 rgb/1311867248.843319.png 1311867248.838326 depth/1311867248.838326.png +1311867248.875531 rgb/1311867248.875531.png 1311867248.875524 depth/1311867248.875524.png +1311867248.911170 rgb/1311867248.911170.png 1311867248.909044 depth/1311867248.909044.png +1311867248.943097 rgb/1311867248.943097.png 1311867248.940181 depth/1311867248.940181.png +1311867248.976589 rgb/1311867248.976589.png 1311867248.976607 depth/1311867248.976607.png +1311867249.011260 rgb/1311867249.011260.png 1311867249.005328 depth/1311867249.005328.png +1311867249.043231 rgb/1311867249.043231.png 1311867249.037121 depth/1311867249.037121.png +1311867249.079906 rgb/1311867249.079906.png 1311867249.079925 depth/1311867249.079925.png +1311867249.112055 rgb/1311867249.112055.png 1311867249.106357 depth/1311867249.106357.png +1311867249.143598 rgb/1311867249.143598.png 1311867249.140147 depth/1311867249.140147.png +1311867249.178513 rgb/1311867249.178513.png 1311867249.174028 depth/1311867249.174028.png +1311867249.211358 rgb/1311867249.211358.png 1311867249.207514 depth/1311867249.207514.png +1311867249.243278 rgb/1311867249.243278.png 1311867249.239832 depth/1311867249.239832.png +1311867249.277340 rgb/1311867249.277340.png 1311867249.277356 depth/1311867249.277356.png +1311867249.311292 rgb/1311867249.311292.png 1311867249.306356 depth/1311867249.306356.png +1311867249.343725 rgb/1311867249.343725.png 1311867249.341224 depth/1311867249.341224.png +1311867249.376845 rgb/1311867249.376845.png 1311867249.376858 depth/1311867249.376858.png +1311867249.411217 rgb/1311867249.411217.png 1311867249.405473 depth/1311867249.405473.png +1311867249.443221 rgb/1311867249.443221.png 1311867249.438211 depth/1311867249.438211.png +1311867249.476410 rgb/1311867249.476410.png 1311867249.476444 depth/1311867249.476444.png +1311867249.511134 rgb/1311867249.511134.png 1311867249.505517 depth/1311867249.505517.png +1311867249.543230 rgb/1311867249.543230.png 1311867249.537314 depth/1311867249.537314.png +1311867249.575910 rgb/1311867249.575910.png 1311867249.575982 depth/1311867249.575982.png +1311867249.611223 rgb/1311867249.611223.png 1311867249.608851 depth/1311867249.608851.png +1311867249.643378 rgb/1311867249.643378.png 1311867249.638062 depth/1311867249.638062.png +1311867249.675103 rgb/1311867249.675103.png 1311867249.673702 depth/1311867249.673702.png +1311867249.711139 rgb/1311867249.711139.png 1311867249.707998 depth/1311867249.707998.png +1311867249.743247 rgb/1311867249.743247.png 1311867249.740043 depth/1311867249.740043.png +1311867249.775158 rgb/1311867249.775158.png 1311867249.773386 depth/1311867249.773386.png +1311867249.811149 rgb/1311867249.811149.png 1311867249.808523 depth/1311867249.808523.png +1311867249.843325 rgb/1311867249.843325.png 1311867249.837680 depth/1311867249.837680.png +1311867249.878395 rgb/1311867249.878395.png 1311867249.878409 depth/1311867249.878409.png +1311867249.911240 rgb/1311867249.911240.png 1311867249.907597 depth/1311867249.907597.png +1311867249.943277 rgb/1311867249.943277.png 1311867249.939728 depth/1311867249.939728.png +1311867249.975170 rgb/1311867249.975170.png 1311867249.974895 depth/1311867249.974895.png +1311867250.011711 rgb/1311867250.011711.png 1311867250.005565 depth/1311867250.005565.png +1311867250.043427 rgb/1311867250.043427.png 1311867250.037222 depth/1311867250.037222.png +1311867250.076673 rgb/1311867250.076673.png 1311867250.076719 depth/1311867250.076719.png +1311867250.111610 rgb/1311867250.111610.png 1311867250.106894 depth/1311867250.106894.png +1311867250.143222 rgb/1311867250.143222.png 1311867250.141178 depth/1311867250.141178.png +1311867250.175891 rgb/1311867250.175891.png 1311867250.175898 depth/1311867250.175898.png +1311867250.213337 rgb/1311867250.213337.png 1311867250.205522 depth/1311867250.205522.png +1311867250.245669 rgb/1311867250.245669.png 1311867250.245713 depth/1311867250.245713.png +1311867250.275168 rgb/1311867250.275168.png 1311867250.273671 depth/1311867250.273671.png +1311867250.311441 rgb/1311867250.311441.png 1311867250.305683 depth/1311867250.305683.png +1311867250.343197 rgb/1311867250.343197.png 1311867250.341283 depth/1311867250.341283.png +1311867250.378064 rgb/1311867250.378064.png 1311867250.377626 depth/1311867250.377626.png +1311867250.411649 rgb/1311867250.411649.png 1311867250.405413 depth/1311867250.405413.png +1311867250.444170 rgb/1311867250.444170.png 1311867250.444178 depth/1311867250.444178.png +1311867250.479325 rgb/1311867250.479325.png 1311867250.476408 depth/1311867250.476408.png +1311867250.511322 rgb/1311867250.511322.png 1311867250.506725 depth/1311867250.506725.png +1311867250.544330 rgb/1311867250.544330.png 1311867250.544340 depth/1311867250.544340.png +1311867250.579349 rgb/1311867250.579349.png 1311867250.573296 depth/1311867250.573296.png +1311867250.611488 rgb/1311867250.611488.png 1311867250.605223 depth/1311867250.605223.png +1311867250.643376 rgb/1311867250.643376.png 1311867250.642715 depth/1311867250.642715.png +1311867250.679554 rgb/1311867250.679554.png 1311867250.673238 depth/1311867250.673238.png +1311867250.711292 rgb/1311867250.711292.png 1311867250.707638 depth/1311867250.707638.png +1311867250.744545 rgb/1311867250.744545.png 1311867250.744589 depth/1311867250.744589.png +1311867250.779283 rgb/1311867250.779283.png 1311867250.777367 depth/1311867250.777367.png +1311867250.814558 rgb/1311867250.814558.png 1311867250.806271 depth/1311867250.806271.png +1311867250.843347 rgb/1311867250.843347.png 1311867250.843360 depth/1311867250.843360.png +1311867250.879276 rgb/1311867250.879276.png 1311867250.873642 depth/1311867250.873642.png +1311867250.911636 rgb/1311867250.911636.png 1311867250.905565 depth/1311867250.905565.png +1311867250.943372 rgb/1311867250.943372.png 1311867250.941647 depth/1311867250.941647.png +1311867250.979305 rgb/1311867250.979305.png 1311867250.976372 depth/1311867250.976372.png +1311867251.011246 rgb/1311867251.011246.png 1311867251.005419 depth/1311867251.005419.png +1311867251.043774 rgb/1311867251.043774.png 1311867251.043791 depth/1311867251.043791.png +1311867251.079316 rgb/1311867251.079316.png 1311867251.073693 depth/1311867251.073693.png +1311867251.111584 rgb/1311867251.111584.png 1311867251.105746 depth/1311867251.105746.png +1311867251.143281 rgb/1311867251.143281.png 1311867251.141746 depth/1311867251.141746.png +1311867251.179425 rgb/1311867251.179425.png 1311867251.173562 depth/1311867251.173562.png +1311867251.211383 rgb/1311867251.211383.png 1311867251.205968 depth/1311867251.205968.png +1311867251.247232 rgb/1311867251.247232.png 1311867251.246582 depth/1311867251.246582.png +1311867251.279370 rgb/1311867251.279370.png 1311867251.275047 depth/1311867251.275047.png +1311867251.313387 rgb/1311867251.313387.png 1311867251.310926 depth/1311867251.310926.png +1311867251.343242 rgb/1311867251.343242.png 1311867251.341515 depth/1311867251.341515.png +1311867251.380182 rgb/1311867251.380182.png 1311867251.376153 depth/1311867251.376153.png +1311867251.411345 rgb/1311867251.411345.png 1311867251.411355 depth/1311867251.411355.png +1311867251.443379 rgb/1311867251.443379.png 1311867251.443396 depth/1311867251.443396.png +1311867251.479338 rgb/1311867251.479338.png 1311867251.476359 depth/1311867251.476359.png +1311867251.513641 rgb/1311867251.513641.png 1311867251.517510 depth/1311867251.517510.png +1311867251.543175 rgb/1311867251.543175.png 1311867251.542053 depth/1311867251.542053.png +1311867251.579534 rgb/1311867251.579534.png 1311867251.573838 depth/1311867251.573838.png +1311867251.611953 rgb/1311867251.611953.png 1311867251.611968 depth/1311867251.611968.png +1311867251.643296 rgb/1311867251.643296.png 1311867251.641726 depth/1311867251.641726.png +1311867251.679728 rgb/1311867251.679728.png 1311867251.675240 depth/1311867251.675240.png +1311867251.712294 rgb/1311867251.712294.png 1311867251.712338 depth/1311867251.712338.png +1311867251.743499 rgb/1311867251.743499.png 1311867251.741376 depth/1311867251.741376.png +1311867251.779744 rgb/1311867251.779744.png 1311867251.773506 depth/1311867251.773506.png +1311867251.811253 rgb/1311867251.811253.png 1311867251.809288 depth/1311867251.809288.png +1311867251.843328 rgb/1311867251.843328.png 1311867251.841161 depth/1311867251.841161.png +1311867251.880542 rgb/1311867251.880542.png 1311867251.873150 depth/1311867251.873150.png +1311867251.911249 rgb/1311867251.911249.png 1311867251.909214 depth/1311867251.909214.png +1311867251.943218 rgb/1311867251.943218.png 1311867251.941809 depth/1311867251.941809.png +1311867251.980011 rgb/1311867251.980011.png 1311867251.974636 depth/1311867251.974636.png +1311867252.011886 rgb/1311867252.011886.png 1311867252.011904 depth/1311867252.011904.png +1311867252.044103 rgb/1311867252.044103.png 1311867252.041228 depth/1311867252.041228.png +1311867252.079454 rgb/1311867252.079454.png 1311867252.073278 depth/1311867252.073278.png +1311867252.112225 rgb/1311867252.112225.png 1311867252.112246 depth/1311867252.112246.png +1311867252.143295 rgb/1311867252.143295.png 1311867252.141274 depth/1311867252.141274.png +1311867252.179436 rgb/1311867252.179436.png 1311867252.173384 depth/1311867252.173384.png +1311867252.211346 rgb/1311867252.211346.png 1311867252.210777 depth/1311867252.210777.png +1311867252.243281 rgb/1311867252.243281.png 1311867252.241230 depth/1311867252.241230.png +1311867252.279411 rgb/1311867252.279411.png 1311867252.273848 depth/1311867252.273848.png +1311867252.311267 rgb/1311867252.311267.png 1311867252.311029 depth/1311867252.311029.png +1311867252.345029 rgb/1311867252.345029.png 1311867252.341880 depth/1311867252.341880.png +1311867252.379459 rgb/1311867252.379459.png 1311867252.374830 depth/1311867252.374830.png +1311867252.411197 rgb/1311867252.411197.png 1311867252.410210 depth/1311867252.410210.png +1311867252.445597 rgb/1311867252.445597.png 1311867252.445605 depth/1311867252.445605.png +1311867252.479290 rgb/1311867252.479290.png 1311867252.473786 depth/1311867252.473786.png +1311867252.511225 rgb/1311867252.511225.png 1311867252.509912 depth/1311867252.509912.png +1311867252.543282 rgb/1311867252.543282.png 1311867252.541490 depth/1311867252.541490.png +1311867252.579180 rgb/1311867252.579180.png 1311867252.578390 depth/1311867252.578390.png +1311867252.611280 rgb/1311867252.611280.png 1311867252.609663 depth/1311867252.609663.png +1311867252.643277 rgb/1311867252.643277.png 1311867252.641820 depth/1311867252.641820.png +1311867252.679249 rgb/1311867252.679249.png 1311867252.677772 depth/1311867252.677772.png +1311867252.711249 rgb/1311867252.711249.png 1311867252.710032 depth/1311867252.710032.png +1311867252.743241 rgb/1311867252.743241.png 1311867252.742726 depth/1311867252.742726.png +1311867252.779273 rgb/1311867252.779273.png 1311867252.777754 depth/1311867252.777754.png +1311867252.811278 rgb/1311867252.811278.png 1311867252.809777 depth/1311867252.809777.png +1311867252.843319 rgb/1311867252.843319.png 1311867252.841481 depth/1311867252.841481.png +1311867252.879266 rgb/1311867252.879266.png 1311867252.877640 depth/1311867252.877640.png +1311867252.911219 rgb/1311867252.911219.png 1311867252.910265 depth/1311867252.910265.png +1311867252.944692 rgb/1311867252.944692.png 1311867252.941823 depth/1311867252.941823.png +1311867252.980602 rgb/1311867252.980602.png 1311867252.977263 depth/1311867252.977263.png +1311867253.011381 rgb/1311867253.011381.png 1311867253.010849 depth/1311867253.010849.png +1311867253.043431 rgb/1311867253.043431.png 1311867253.042352 depth/1311867253.042352.png +1311867253.079921 rgb/1311867253.079921.png 1311867253.079930 depth/1311867253.079930.png +1311867253.111303 rgb/1311867253.111303.png 1311867253.109702 depth/1311867253.109702.png +1311867253.144056 rgb/1311867253.144056.png 1311867253.144076 depth/1311867253.144076.png +1311867253.179405 rgb/1311867253.179405.png 1311867253.177662 depth/1311867253.177662.png +1311867253.211216 rgb/1311867253.211216.png 1311867253.209393 depth/1311867253.209393.png +1311867253.245841 rgb/1311867253.245841.png 1311867253.242864 depth/1311867253.242864.png +1311867253.279395 rgb/1311867253.279395.png 1311867253.278709 depth/1311867253.278709.png +1311867253.311408 rgb/1311867253.311408.png 1311867253.309589 depth/1311867253.309589.png +1311867253.344521 rgb/1311867253.344521.png 1311867253.344561 depth/1311867253.344561.png +1311867253.379408 rgb/1311867253.379408.png 1311867253.377918 depth/1311867253.377918.png +1311867253.412926 rgb/1311867253.412926.png 1311867253.412953 depth/1311867253.412953.png +1311867253.444491 rgb/1311867253.444491.png 1311867253.444499 depth/1311867253.444499.png +1311867253.480478 rgb/1311867253.480478.png 1311867253.480486 depth/1311867253.480486.png +1311867253.511374 rgb/1311867253.511374.png 1311867253.509709 depth/1311867253.509709.png +1311867253.544163 rgb/1311867253.544163.png 1311867253.541739 depth/1311867253.541739.png +1311867253.579407 rgb/1311867253.579407.png 1311867253.577655 depth/1311867253.577655.png +1311867253.611802 rgb/1311867253.611802.png 1311867253.609458 depth/1311867253.609458.png +1311867253.644463 rgb/1311867253.644463.png 1311867253.644765 depth/1311867253.644765.png +1311867253.679979 rgb/1311867253.679979.png 1311867253.677508 depth/1311867253.677508.png +1311867253.711529 rgb/1311867253.711529.png 1311867253.711577 depth/1311867253.711577.png +1311867253.743537 rgb/1311867253.743537.png 1311867253.741691 depth/1311867253.741691.png +1311867253.780402 rgb/1311867253.780402.png 1311867253.780615 depth/1311867253.780615.png +1311867253.811301 rgb/1311867253.811301.png 1311867253.810444 depth/1311867253.810444.png +1311867253.846601 rgb/1311867253.846601.png 1311867253.846956 depth/1311867253.846956.png +1311867253.879206 rgb/1311867253.879206.png 1311867253.878390 depth/1311867253.878390.png +1311867253.911446 rgb/1311867253.911446.png 1311867253.909536 depth/1311867253.909536.png +1311867253.946104 rgb/1311867253.946104.png 1311867253.946160 depth/1311867253.946160.png +1311867253.979415 rgb/1311867253.979415.png 1311867253.977869 depth/1311867253.977869.png +1311867254.011966 rgb/1311867254.011966.png 1311867254.011998 depth/1311867254.011998.png +1311867254.045767 rgb/1311867254.045767.png 1311867254.045775 depth/1311867254.045775.png +1311867254.079374 rgb/1311867254.079374.png 1311867254.077738 depth/1311867254.077738.png +1311867254.111352 rgb/1311867254.111352.png 1311867254.109657 depth/1311867254.109657.png +1311867254.147685 rgb/1311867254.147685.png 1311867254.147695 depth/1311867254.147695.png +1311867254.179513 rgb/1311867254.179513.png 1311867254.177744 depth/1311867254.177744.png +1311867254.211494 rgb/1311867254.211494.png 1311867254.209721 depth/1311867254.209721.png +1311867254.246904 rgb/1311867254.246904.png 1311867254.246916 depth/1311867254.246916.png +1311867254.279857 rgb/1311867254.279857.png 1311867254.278806 depth/1311867254.278806.png +1311867254.311463 rgb/1311867254.311463.png 1311867254.309669 depth/1311867254.309669.png +1311867254.347540 rgb/1311867254.347540.png 1311867254.347559 depth/1311867254.347559.png +1311867254.379449 rgb/1311867254.379449.png 1311867254.377658 depth/1311867254.377658.png +1311867254.411535 rgb/1311867254.411535.png 1311867254.410412 depth/1311867254.410412.png +1311867254.448323 rgb/1311867254.448323.png 1311867254.448344 depth/1311867254.448344.png +1311867254.479448 rgb/1311867254.479448.png 1311867254.477669 depth/1311867254.477669.png +1311867254.511443 rgb/1311867254.511443.png 1311867254.509518 depth/1311867254.509518.png +1311867254.550046 rgb/1311867254.550046.png 1311867254.549299 depth/1311867254.549299.png +1311867254.579487 rgb/1311867254.579487.png 1311867254.577488 depth/1311867254.577488.png +1311867254.611481 rgb/1311867254.611481.png 1311867254.609387 depth/1311867254.609387.png +1311867254.645227 rgb/1311867254.645227.png 1311867254.645293 depth/1311867254.645293.png +1311867254.679490 rgb/1311867254.679490.png 1311867254.677379 depth/1311867254.677379.png +1311867254.711323 rgb/1311867254.711323.png 1311867254.710256 depth/1311867254.710256.png +1311867254.745273 rgb/1311867254.745273.png 1311867254.745333 depth/1311867254.745333.png +1311867254.779465 rgb/1311867254.779465.png 1311867254.777416 depth/1311867254.777416.png +1311867254.811574 rgb/1311867254.811574.png 1311867254.809383 depth/1311867254.809383.png +1311867254.848265 rgb/1311867254.848265.png 1311867254.848278 depth/1311867254.848278.png +1311867254.879491 rgb/1311867254.879491.png 1311867254.879292 depth/1311867254.879292.png +1311867254.913881 rgb/1311867254.913881.png 1311867254.913893 depth/1311867254.913893.png +1311867254.949070 rgb/1311867254.949070.png 1311867254.949076 depth/1311867254.949076.png +1311867254.981925 rgb/1311867254.981925.png 1311867254.981958 depth/1311867254.981958.png +1311867255.015430 rgb/1311867255.015430.png 1311867255.015436 depth/1311867255.015436.png +1311867255.049418 rgb/1311867255.049418.png 1311867255.049438 depth/1311867255.049438.png +1311867255.082194 rgb/1311867255.082194.png 1311867255.082208 depth/1311867255.082208.png +1311867255.117684 rgb/1311867255.117684.png 1311867255.117586 depth/1311867255.117586.png +1311867255.151015 rgb/1311867255.151015.png 1311867255.150610 depth/1311867255.150610.png +1311867255.183783 rgb/1311867255.183783.png 1311867255.183880 depth/1311867255.183880.png +1311867255.216913 rgb/1311867255.216913.png 1311867255.216913 depth/1311867255.216913.png +1311867255.245906 rgb/1311867255.245906.png 1311867255.245937 depth/1311867255.245937.png +1311867255.279366 rgb/1311867255.279366.png 1311867255.279172 depth/1311867255.279172.png +1311867255.313847 rgb/1311867255.313847.png 1311867255.313863 depth/1311867255.313863.png +1311867255.346831 rgb/1311867255.346831.png 1311867255.346841 depth/1311867255.346841.png +1311867255.379475 rgb/1311867255.379475.png 1311867255.377963 depth/1311867255.377963.png +1311867255.413757 rgb/1311867255.413757.png 1311867255.413764 depth/1311867255.413764.png +1311867255.445540 rgb/1311867255.445540.png 1311867255.445553 depth/1311867255.445553.png +1311867255.479482 rgb/1311867255.479482.png 1311867255.478153 depth/1311867255.478153.png +1311867255.515585 rgb/1311867255.515585.png 1311867255.515610 depth/1311867255.515610.png +1311867255.545730 rgb/1311867255.545730.png 1311867255.545778 depth/1311867255.545778.png +1311867255.579442 rgb/1311867255.579442.png 1311867255.578444 depth/1311867255.578444.png +1311867255.615323 rgb/1311867255.615323.png 1311867255.615333 depth/1311867255.615333.png +1311867255.645642 rgb/1311867255.645642.png 1311867255.645648 depth/1311867255.645648.png +1311867255.680081 rgb/1311867255.680081.png 1311867255.680102 depth/1311867255.680102.png +1311867255.718269 rgb/1311867255.718269.png 1311867255.718292 depth/1311867255.718292.png +1311867255.745767 rgb/1311867255.745767.png 1311867255.745775 depth/1311867255.745775.png +1311867255.780996 rgb/1311867255.780996.png 1311867255.781093 depth/1311867255.781093.png +1311867255.817593 rgb/1311867255.817593.png 1311867255.817610 depth/1311867255.817610.png +1311867255.845687 rgb/1311867255.845687.png 1311867255.845725 depth/1311867255.845725.png +1311867255.879379 rgb/1311867255.879379.png 1311867255.878755 depth/1311867255.878755.png +1311867255.914024 rgb/1311867255.914024.png 1311867255.914031 depth/1311867255.914031.png +1311867255.945901 rgb/1311867255.945901.png 1311867255.945908 depth/1311867255.945908.png +1311867255.979486 rgb/1311867255.979486.png 1311867255.977784 depth/1311867255.977784.png +1311867256.017783 rgb/1311867256.017783.png 1311867256.017797 depth/1311867256.017797.png +1311867256.046004 rgb/1311867256.046004.png 1311867256.046014 depth/1311867256.046014.png +1311867256.079590 rgb/1311867256.079590.png 1311867256.085688 depth/1311867256.085688.png +1311867256.116730 rgb/1311867256.116730.png 1311867256.116497 depth/1311867256.116497.png +1311867256.145219 rgb/1311867256.145219.png 1311867256.145227 depth/1311867256.145227.png +1311867256.179506 rgb/1311867256.179506.png 1311867256.177549 depth/1311867256.177549.png +1311867256.217737 rgb/1311867256.217737.png 1311867256.217749 depth/1311867256.217749.png +1311867256.245462 rgb/1311867256.245462.png 1311867256.245469 depth/1311867256.245469.png +1311867256.284698 rgb/1311867256.284698.png 1311867256.284704 depth/1311867256.284704.png +1311867256.314334 rgb/1311867256.314334.png 1311867256.314342 depth/1311867256.314342.png +1311867256.347169 rgb/1311867256.347169.png 1311867256.347179 depth/1311867256.347179.png +1311867256.384803 rgb/1311867256.384803.png 1311867256.384865 depth/1311867256.384865.png +1311867256.415853 rgb/1311867256.415853.png 1311867256.415865 depth/1311867256.415865.png +1311867256.445283 rgb/1311867256.445283.png 1311867256.445284 depth/1311867256.445284.png +1311867256.484375 rgb/1311867256.484375.png 1311867256.484460 depth/1311867256.484460.png +1311867256.513577 rgb/1311867256.513577.png 1311867256.513583 depth/1311867256.513583.png +1311867256.547861 rgb/1311867256.547861.png 1311867256.547879 depth/1311867256.547879.png +1311867256.583591 rgb/1311867256.583591.png 1311867256.583649 depth/1311867256.583649.png +1311867256.616028 rgb/1311867256.616028.png 1311867256.616037 depth/1311867256.616037.png +1311867256.645225 rgb/1311867256.645225.png 1311867256.645231 depth/1311867256.645231.png +1311867256.683263 rgb/1311867256.683263.png 1311867256.683276 depth/1311867256.683276.png +1311867256.714018 rgb/1311867256.714018.png 1311867256.714030 depth/1311867256.714030.png +1311867256.746329 rgb/1311867256.746329.png 1311867256.746337 depth/1311867256.746337.png +1311867256.782735 rgb/1311867256.782735.png 1311867256.782740 depth/1311867256.782740.png +1311867256.814038 rgb/1311867256.814038.png 1311867256.814043 depth/1311867256.814043.png +1311867256.847722 rgb/1311867256.847722.png 1311867256.847740 depth/1311867256.847740.png +1311867256.883890 rgb/1311867256.883890.png 1311867256.883898 depth/1311867256.883898.png +1311867256.914798 rgb/1311867256.914798.png 1311867256.914811 depth/1311867256.914811.png +1311867256.946531 rgb/1311867256.946531.png 1311867256.946538 depth/1311867256.946538.png +1311867256.981447 rgb/1311867256.981447.png 1311867256.981461 depth/1311867256.981461.png +1311867257.012988 rgb/1311867257.012988.png 1311867257.012996 depth/1311867257.012996.png +1311867257.045185 rgb/1311867257.045185.png 1311867257.045191 depth/1311867257.045191.png +1311867257.084110 rgb/1311867257.084110.png 1311867257.084137 depth/1311867257.084137.png +1311867257.113385 rgb/1311867257.113385.png 1311867257.113443 depth/1311867257.113443.png +1311867257.147422 rgb/1311867257.147422.png 1311867257.147431 depth/1311867257.147431.png +1311867257.182069 rgb/1311867257.182069.png 1311867257.182123 depth/1311867257.182123.png +1311867257.214758 rgb/1311867257.214758.png 1311867257.214784 depth/1311867257.214784.png +1311867257.245697 rgb/1311867257.245697.png 1311867257.245704 depth/1311867257.245704.png +1311867257.282412 rgb/1311867257.282412.png 1311867257.282449 depth/1311867257.282449.png +1311867257.313334 rgb/1311867257.313334.png 1311867257.313343 depth/1311867257.313343.png +1311867257.345279 rgb/1311867257.345279.png 1311867257.345285 depth/1311867257.345285.png +1311867257.383951 rgb/1311867257.383951.png 1311867257.383963 depth/1311867257.383963.png +1311867257.416062 rgb/1311867257.416062.png 1311867257.419813 depth/1311867257.419813.png +1311867257.445852 rgb/1311867257.445852.png 1311867257.445861 depth/1311867257.445861.png +1311867257.485117 rgb/1311867257.485117.png 1311867257.485127 depth/1311867257.485127.png +1311867257.516611 rgb/1311867257.516611.png 1311867257.516625 depth/1311867257.516625.png +1311867257.543702 rgb/1311867257.543702.png 1311867257.553788 depth/1311867257.553788.png +1311867257.583609 rgb/1311867257.583609.png 1311867257.583620 depth/1311867257.583620.png +1311867257.615413 rgb/1311867257.615413.png 1311867257.615446 depth/1311867257.615446.png +1311867257.643749 rgb/1311867257.643749.png 1311867257.651972 depth/1311867257.651972.png +1311867257.684241 rgb/1311867257.684241.png 1311867257.684296 depth/1311867257.684296.png +1311867257.718778 rgb/1311867257.718778.png 1311867257.714646 depth/1311867257.714646.png +1311867257.743747 rgb/1311867257.743747.png 1311867257.752781 depth/1311867257.752781.png +1311867257.783800 rgb/1311867257.783800.png 1311867257.783843 depth/1311867257.783843.png +1311867257.818099 rgb/1311867257.818099.png 1311867257.818141 depth/1311867257.818141.png +1311867257.843575 rgb/1311867257.843575.png 1311867257.853070 depth/1311867257.853070.png +1311867257.885458 rgb/1311867257.885458.png 1311867257.885405 depth/1311867257.885405.png +1311867257.915235 rgb/1311867257.915235.png 1311867257.915253 depth/1311867257.915253.png +1311867257.943765 rgb/1311867257.943765.png 1311867257.955903 depth/1311867257.955903.png +1311867257.985062 rgb/1311867257.985062.png 1311867257.985078 depth/1311867257.985078.png +1311867258.013561 rgb/1311867258.013561.png 1311867258.013571 depth/1311867258.013571.png +1311867258.043623 rgb/1311867258.043623.png 1311867258.052661 depth/1311867258.052661.png +1311867258.083652 rgb/1311867258.083652.png 1311867258.083661 depth/1311867258.083661.png +1311867258.113782 rgb/1311867258.113782.png 1311867258.113786 depth/1311867258.113786.png +1311867258.143714 rgb/1311867258.143714.png 1311867258.150107 depth/1311867258.150107.png +1311867258.184833 rgb/1311867258.184833.png 1311867258.184848 depth/1311867258.184848.png +1311867258.216268 rgb/1311867258.216268.png 1311867258.216273 depth/1311867258.216273.png +1311867258.243624 rgb/1311867258.243624.png 1311867258.252498 depth/1311867258.252498.png +1311867258.285010 rgb/1311867258.285010.png 1311867258.285783 depth/1311867258.285783.png +1311867258.313274 rgb/1311867258.313274.png 1311867258.313291 depth/1311867258.313291.png +1311867258.343642 rgb/1311867258.343642.png 1311867258.351071 depth/1311867258.351071.png +1311867258.381205 rgb/1311867258.381205.png 1311867258.381212 depth/1311867258.381212.png +1311867258.414263 rgb/1311867258.414263.png 1311867258.414271 depth/1311867258.414271.png +1311867258.443907 rgb/1311867258.443907.png 1311867258.450701 depth/1311867258.450701.png +1311867258.482546 rgb/1311867258.482546.png 1311867258.482606 depth/1311867258.482606.png +1311867258.513980 rgb/1311867258.513980.png 1311867258.513990 depth/1311867258.513990.png +1311867258.543595 rgb/1311867258.543595.png 1311867258.550051 depth/1311867258.550051.png +1311867258.583598 rgb/1311867258.583598.png 1311867258.583604 depth/1311867258.583604.png +1311867258.614160 rgb/1311867258.614160.png 1311867258.614168 depth/1311867258.614168.png +1311867258.643778 rgb/1311867258.643778.png 1311867258.650686 depth/1311867258.650686.png +1311867258.685220 rgb/1311867258.685220.png 1311867258.685647 depth/1311867258.685647.png +1311867258.713406 rgb/1311867258.713406.png 1311867258.713424 depth/1311867258.713424.png +1311867258.743665 rgb/1311867258.743665.png 1311867258.754356 depth/1311867258.754356.png +1311867258.784349 rgb/1311867258.784349.png 1311867258.784359 depth/1311867258.784359.png +1311867258.811690 rgb/1311867258.811690.png 1311867258.819369 depth/1311867258.819369.png +1311867258.843893 rgb/1311867258.843893.png 1311867258.851441 depth/1311867258.851441.png +1311867258.884560 rgb/1311867258.884560.png 1311867258.884601 depth/1311867258.884601.png +1311867258.911750 rgb/1311867258.911750.png 1311867258.917897 depth/1311867258.917897.png +1311867258.944000 rgb/1311867258.944000.png 1311867258.950620 depth/1311867258.950620.png +1311867258.984155 rgb/1311867258.984155.png 1311867258.984167 depth/1311867258.984167.png +1311867259.011907 rgb/1311867259.011907.png 1311867259.019439 depth/1311867259.019439.png +1311867259.043970 rgb/1311867259.043970.png 1311867259.049796 depth/1311867259.049796.png +1311867259.084547 rgb/1311867259.084547.png 1311867259.084510 depth/1311867259.084510.png +1311867259.111734 rgb/1311867259.111734.png 1311867259.118993 depth/1311867259.118993.png +1311867259.143877 rgb/1311867259.143877.png 1311867259.150603 depth/1311867259.150603.png +1311867259.183764 rgb/1311867259.183764.png 1311867259.183782 depth/1311867259.183782.png +1311867259.211951 rgb/1311867259.211951.png 1311867259.219198 depth/1311867259.219198.png +1311867259.243853 rgb/1311867259.243853.png 1311867259.253290 depth/1311867259.253290.png +1311867259.281587 rgb/1311867259.281587.png 1311867259.281598 depth/1311867259.281598.png +1311867259.311928 rgb/1311867259.311928.png 1311867259.321272 depth/1311867259.321272.png +1311867259.343762 rgb/1311867259.343762.png 1311867259.351904 depth/1311867259.351904.png +1311867259.383911 rgb/1311867259.383911.png 1311867259.384019 depth/1311867259.384019.png +1311867259.411722 rgb/1311867259.411722.png 1311867259.420429 depth/1311867259.420429.png +1311867259.443793 rgb/1311867259.443793.png 1311867259.457918 depth/1311867259.457918.png +1311867259.481615 rgb/1311867259.481615.png 1311867259.485055 depth/1311867259.485055.png +1311867259.511730 rgb/1311867259.511730.png 1311867259.518982 depth/1311867259.518982.png +1311867259.550578 rgb/1311867259.550578.png 1311867259.550593 depth/1311867259.550593.png +1311867259.582216 rgb/1311867259.582216.png 1311867259.582324 depth/1311867259.582324.png +1311867259.611739 rgb/1311867259.611739.png 1311867259.619272 depth/1311867259.619272.png +1311867259.649471 rgb/1311867259.649471.png 1311867259.649484 depth/1311867259.649484.png +1311867259.682849 rgb/1311867259.682849.png 1311867259.682859 depth/1311867259.682859.png +1311867259.711827 rgb/1311867259.711827.png 1311867259.720199 depth/1311867259.720199.png +1311867259.752007 rgb/1311867259.752007.png 1311867259.755769 depth/1311867259.755769.png +1311867259.781780 rgb/1311867259.781780.png 1311867259.781786 depth/1311867259.781786.png +1311867259.811817 rgb/1311867259.811817.png 1311867259.817701 depth/1311867259.817701.png +1311867259.850399 rgb/1311867259.850399.png 1311867259.854894 depth/1311867259.854894.png +1311867259.881835 rgb/1311867259.881835.png 1311867259.881841 depth/1311867259.881841.png +1311867259.912113 rgb/1311867259.912113.png 1311867259.921918 depth/1311867259.921918.png +1311867259.952003 rgb/1311867259.952003.png 1311867259.952013 depth/1311867259.952013.png +1311867259.979767 rgb/1311867259.979767.png 1311867259.992364 depth/1311867259.992364.png +1311867260.012691 rgb/1311867260.012691.png 1311867260.021947 depth/1311867260.021947.png +1311867260.049315 rgb/1311867260.049315.png 1311867260.049321 depth/1311867260.049321.png +1311867260.079913 rgb/1311867260.079913.png 1311867260.088808 depth/1311867260.088808.png +1311867260.111941 rgb/1311867260.111941.png 1311867260.121050 depth/1311867260.121050.png +1311867260.151371 rgb/1311867260.151371.png 1311867260.151387 depth/1311867260.151387.png +1311867260.179934 rgb/1311867260.179934.png 1311867260.190886 depth/1311867260.190886.png +1311867260.211913 rgb/1311867260.211913.png 1311867260.220444 depth/1311867260.220444.png +1311867260.249637 rgb/1311867260.249637.png 1311867260.249667 depth/1311867260.249667.png +1311867260.279865 rgb/1311867260.279865.png 1311867260.286988 depth/1311867260.286988.png +1311867260.312068 rgb/1311867260.312068.png 1311867260.319559 depth/1311867260.319559.png +1311867260.350508 rgb/1311867260.350508.png 1311867260.350526 depth/1311867260.350526.png +1311867260.380002 rgb/1311867260.380002.png 1311867260.386890 depth/1311867260.386890.png +1311867260.412000 rgb/1311867260.412000.png 1311867260.421130 depth/1311867260.421130.png +1311867260.452169 rgb/1311867260.452169.png 1311867260.452177 depth/1311867260.452177.png +1311867260.479772 rgb/1311867260.479772.png 1311867260.486747 depth/1311867260.486747.png +1311867260.512102 rgb/1311867260.512102.png 1311867260.519293 depth/1311867260.519293.png +1311867260.552766 rgb/1311867260.552766.png 1311867260.552787 depth/1311867260.552787.png +1311867260.579905 rgb/1311867260.579905.png 1311867260.588045 depth/1311867260.588045.png +1311867260.612014 rgb/1311867260.612014.png 1311867260.619619 depth/1311867260.619619.png +1311867260.649334 rgb/1311867260.649334.png 1311867260.649341 depth/1311867260.649341.png +1311867260.679860 rgb/1311867260.679860.png 1311867260.686534 depth/1311867260.686534.png +1311867260.711867 rgb/1311867260.711867.png 1311867260.718823 depth/1311867260.718823.png +1311867260.749329 rgb/1311867260.749329.png 1311867260.749337 depth/1311867260.749337.png +1311867260.780035 rgb/1311867260.780035.png 1311867260.785965 depth/1311867260.785965.png +1311867260.812146 rgb/1311867260.812146.png 1311867260.817908 depth/1311867260.817908.png +1311867260.851416 rgb/1311867260.851416.png 1311867260.851460 depth/1311867260.851460.png +1311867260.879809 rgb/1311867260.879809.png 1311867260.886743 depth/1311867260.886743.png +1311867260.912017 rgb/1311867260.912017.png 1311867260.917785 depth/1311867260.917785.png +1311867260.949439 rgb/1311867260.949439.png 1311867260.949446 depth/1311867260.949446.png +1311867260.979950 rgb/1311867260.979950.png 1311867260.986968 depth/1311867260.986968.png +1311867261.011875 rgb/1311867261.011875.png 1311867261.020226 depth/1311867261.020226.png +1311867261.051950 rgb/1311867261.051950.png 1311867261.051964 depth/1311867261.051964.png +1311867261.079805 rgb/1311867261.079805.png 1311867261.087158 depth/1311867261.087158.png +1311867261.111871 rgb/1311867261.111871.png 1311867261.119766 depth/1311867261.119766.png +1311867261.153079 rgb/1311867261.153079.png 1311867261.152864 depth/1311867261.152864.png +1311867261.179986 rgb/1311867261.179986.png 1311867261.187263 depth/1311867261.187263.png +1311867261.211987 rgb/1311867261.211987.png 1311867261.219109 depth/1311867261.219109.png +1311867261.247791 rgb/1311867261.247791.png 1311867261.254823 depth/1311867261.254823.png +1311867261.280012 rgb/1311867261.280012.png 1311867261.287960 depth/1311867261.287960.png +1311867261.312072 rgb/1311867261.312072.png 1311867261.318503 depth/1311867261.318503.png +1311867261.347781 rgb/1311867261.347781.png 1311867261.354630 depth/1311867261.354630.png +1311867261.379963 rgb/1311867261.379963.png 1311867261.385833 depth/1311867261.385833.png +1311867261.412118 rgb/1311867261.412118.png 1311867261.418638 depth/1311867261.418638.png +1311867261.448088 rgb/1311867261.448088.png 1311867261.455868 depth/1311867261.455868.png +1311867261.479857 rgb/1311867261.479857.png 1311867261.486219 depth/1311867261.486219.png +1311867261.512250 rgb/1311867261.512250.png 1311867261.517863 depth/1311867261.517863.png +1311867261.547863 rgb/1311867261.547863.png 1311867261.555652 depth/1311867261.555652.png +1311867261.579903 rgb/1311867261.579903.png 1311867261.585790 depth/1311867261.585790.png +1311867261.612131 rgb/1311867261.612131.png 1311867261.617464 depth/1311867261.617464.png +1311867261.648078 rgb/1311867261.648078.png 1311867261.665201 depth/1311867261.665201.png +1311867261.680301 rgb/1311867261.680301.png 1311867261.688993 depth/1311867261.688993.png +1311867261.712383 rgb/1311867261.712383.png 1311867261.719311 depth/1311867261.719311.png +1311867261.748085 rgb/1311867261.748085.png 1311867261.760155 depth/1311867261.760155.png +1311867261.779918 rgb/1311867261.779918.png 1311867261.787688 depth/1311867261.787688.png +1311867261.811956 rgb/1311867261.811956.png 1311867261.821394 depth/1311867261.821394.png +1311867261.848006 rgb/1311867261.848006.png 1311867261.859815 depth/1311867261.859815.png +1311867261.880073 rgb/1311867261.880073.png 1311867261.888546 depth/1311867261.888546.png +1311867261.912163 rgb/1311867261.912163.png 1311867261.921236 depth/1311867261.921236.png +1311867261.948000 rgb/1311867261.948000.png 1311867261.959230 depth/1311867261.959230.png +1311867261.980242 rgb/1311867261.980242.png 1311867261.988614 depth/1311867261.988614.png +1311867262.011962 rgb/1311867262.011962.png 1311867262.021953 depth/1311867262.021953.png +1311867262.047907 rgb/1311867262.047907.png 1311867262.057663 depth/1311867262.057663.png +1311867262.080301 rgb/1311867262.080301.png 1311867262.094468 depth/1311867262.094468.png +1311867262.117955 rgb/1311867262.117955.png 1311867262.118048 depth/1311867262.118048.png +1311867262.147860 rgb/1311867262.147860.png 1311867262.153988 depth/1311867262.153988.png +1311867262.180119 rgb/1311867262.180119.png 1311867262.190654 depth/1311867262.190654.png +1311867262.212167 rgb/1311867262.212167.png 1311867262.220062 depth/1311867262.220062.png +1311867262.247855 rgb/1311867262.247855.png 1311867262.255759 depth/1311867262.255759.png +1311867262.279909 rgb/1311867262.279909.png 1311867262.289356 depth/1311867262.289356.png +1311867262.312207 rgb/1311867262.312207.png 1311867262.319283 depth/1311867262.319283.png +1311867262.347903 rgb/1311867262.347903.png 1311867262.354351 depth/1311867262.354351.png +1311867262.379904 rgb/1311867262.379904.png 1311867262.386276 depth/1311867262.386276.png +1311867262.411961 rgb/1311867262.411961.png 1311867262.419248 depth/1311867262.419248.png +1311867262.448089 rgb/1311867262.448089.png 1311867262.457937 depth/1311867262.457937.png +1311867262.479872 rgb/1311867262.479872.png 1311867262.488291 depth/1311867262.488291.png +1311867262.512133 rgb/1311867262.512133.png 1311867262.522872 depth/1311867262.522872.png +1311867262.547912 rgb/1311867262.547912.png 1311867262.555407 depth/1311867262.555407.png +1311867262.579872 rgb/1311867262.579872.png 1311867262.587320 depth/1311867262.587320.png +1311867262.612224 rgb/1311867262.612224.png 1311867262.623551 depth/1311867262.623551.png +1311867262.647862 rgb/1311867262.647862.png 1311867262.654801 depth/1311867262.654801.png +1311867262.680238 rgb/1311867262.680238.png 1311867262.690114 depth/1311867262.690114.png +1311867262.712055 rgb/1311867262.712055.png 1311867262.723480 depth/1311867262.723480.png +1311867262.748013 rgb/1311867262.748013.png 1311867262.755088 depth/1311867262.755088.png +1311867262.780047 rgb/1311867262.780047.png 1311867262.789079 depth/1311867262.789079.png +1311867262.812118 rgb/1311867262.812118.png 1311867262.823227 depth/1311867262.823227.png +1311867262.847972 rgb/1311867262.847972.png 1311867262.856114 depth/1311867262.856114.png +1311867262.880083 rgb/1311867262.880083.png 1311867262.887828 depth/1311867262.887828.png +1311867262.912008 rgb/1311867262.912008.png 1311867262.922193 depth/1311867262.922193.png +1311867262.947979 rgb/1311867262.947979.png 1311867262.953997 depth/1311867262.953997.png +1311867262.979967 rgb/1311867262.979967.png 1311867262.987732 depth/1311867262.987732.png +1311867263.012291 rgb/1311867263.012291.png 1311867263.023844 depth/1311867263.023844.png +1311867263.048000 rgb/1311867263.048000.png 1311867263.055280 depth/1311867263.055280.png +1311867263.079930 rgb/1311867263.079930.png 1311867263.087004 depth/1311867263.087004.png +1311867263.111968 rgb/1311867263.111968.png 1311867263.122690 depth/1311867263.122690.png +1311867263.148043 rgb/1311867263.148043.png 1311867263.153708 depth/1311867263.153708.png +1311867263.180026 rgb/1311867263.180026.png 1311867263.188423 depth/1311867263.188423.png +1311867263.212088 rgb/1311867263.212088.png 1311867263.222581 depth/1311867263.222581.png +1311867263.248034 rgb/1311867263.248034.png 1311867263.253614 depth/1311867263.253614.png +1311867263.280002 rgb/1311867263.280002.png 1311867263.288447 depth/1311867263.288447.png +1311867263.312094 rgb/1311867263.312094.png 1311867263.323627 depth/1311867263.323627.png +1311867263.348120 rgb/1311867263.348120.png 1311867263.353947 depth/1311867263.353947.png +1311867263.380039 rgb/1311867263.380039.png 1311867263.385653 depth/1311867263.385653.png +1311867263.412375 rgb/1311867263.412375.png 1311867263.422146 depth/1311867263.422146.png +1311867263.448153 rgb/1311867263.448153.png 1311867263.454956 depth/1311867263.454956.png +1311867263.480018 rgb/1311867263.480018.png 1311867263.487639 depth/1311867263.487639.png +1311867263.511993 rgb/1311867263.511993.png 1311867263.523595 depth/1311867263.523595.png +1311867263.547977 rgb/1311867263.547977.png 1311867263.553510 depth/1311867263.553510.png +1311867263.580059 rgb/1311867263.580059.png 1311867263.585504 depth/1311867263.585504.png +1311867263.612205 rgb/1311867263.612205.png 1311867263.623614 depth/1311867263.623614.png +1311867263.648021 rgb/1311867263.648021.png 1311867263.654392 depth/1311867263.654392.png +1311867263.679956 rgb/1311867263.679956.png 1311867263.690378 depth/1311867263.690378.png +1311867263.712221 rgb/1311867263.712221.png 1311867263.722763 depth/1311867263.722763.png +1311867263.748100 rgb/1311867263.748100.png 1311867263.755967 depth/1311867263.755967.png +1311867263.780318 rgb/1311867263.780318.png 1311867263.791156 depth/1311867263.791156.png +1311867263.812318 rgb/1311867263.812318.png 1311867263.823519 depth/1311867263.823519.png +1311867263.848119 rgb/1311867263.848119.png 1311867263.855552 depth/1311867263.855552.png +1311867263.880150 rgb/1311867263.880150.png 1311867263.892539 depth/1311867263.892539.png +1311867263.912334 rgb/1311867263.912334.png 1311867263.925589 depth/1311867263.925589.png +1311867263.948206 rgb/1311867263.948206.png 1311867263.955721 depth/1311867263.955721.png +1311867263.979999 rgb/1311867263.979999.png 1311867263.991345 depth/1311867263.991345.png +1311867264.012231 rgb/1311867264.012231.png 1311867264.026508 depth/1311867264.026508.png +1311867264.048127 rgb/1311867264.048127.png 1311867264.053984 depth/1311867264.053984.png +1311867264.080210 rgb/1311867264.080210.png 1311867264.093584 depth/1311867264.093584.png +1311867264.112282 rgb/1311867264.112282.png 1311867264.123293 depth/1311867264.123293.png +1311867264.147983 rgb/1311867264.147983.png 1311867264.154781 depth/1311867264.154781.png +1311867264.180145 rgb/1311867264.180145.png 1311867264.190874 depth/1311867264.190874.png +1311867264.212109 rgb/1311867264.212109.png 1311867264.223044 depth/1311867264.223044.png +1311867264.248024 rgb/1311867264.248024.png 1311867264.254928 depth/1311867264.254928.png +1311867264.280169 rgb/1311867264.280169.png 1311867264.291094 depth/1311867264.291094.png +1311867264.312006 rgb/1311867264.312006.png 1311867264.322354 depth/1311867264.322354.png +1311867264.348192 rgb/1311867264.348192.png 1311867264.353971 depth/1311867264.353971.png +1311867264.380241 rgb/1311867264.380241.png 1311867264.390357 depth/1311867264.390357.png +1311867264.412214 rgb/1311867264.412214.png 1311867264.424713 depth/1311867264.424713.png +1311867264.448004 rgb/1311867264.448004.png 1311867264.453671 depth/1311867264.453671.png +1311867264.480074 rgb/1311867264.480074.png 1311867264.491122 depth/1311867264.491122.png +1311867264.512227 rgb/1311867264.512227.png 1311867264.522093 depth/1311867264.522093.png +1311867264.548155 rgb/1311867264.548155.png 1311867264.554466 depth/1311867264.554466.png +1311867264.580092 rgb/1311867264.580092.png 1311867264.591919 depth/1311867264.591919.png +1311867264.612330 rgb/1311867264.612330.png 1311867264.623954 depth/1311867264.623954.png +1311867264.648092 rgb/1311867264.648092.png 1311867264.653789 depth/1311867264.653789.png +1311867264.680199 rgb/1311867264.680199.png 1311867264.690898 depth/1311867264.690898.png +1311867264.712454 rgb/1311867264.712454.png 1311867264.722804 depth/1311867264.722804.png +1311867264.747965 rgb/1311867264.747965.png 1311867264.754714 depth/1311867264.754714.png +1311867264.780125 rgb/1311867264.780125.png 1311867264.790914 depth/1311867264.790914.png +1311867264.812115 rgb/1311867264.812115.png 1311867264.823344 depth/1311867264.823344.png +1311867264.848189 rgb/1311867264.848189.png 1311867264.854079 depth/1311867264.854079.png +1311867264.880141 rgb/1311867264.880141.png 1311867264.890441 depth/1311867264.890441.png +1311867264.912230 rgb/1311867264.912230.png 1311867264.923558 depth/1311867264.923558.png +1311867264.948186 rgb/1311867264.948186.png 1311867264.959884 depth/1311867264.959884.png +1311867264.980433 rgb/1311867264.980433.png 1311867264.991684 depth/1311867264.991684.png +1311867265.012192 rgb/1311867265.012192.png 1311867265.022003 depth/1311867265.022003.png +1311867265.048128 rgb/1311867265.048128.png 1311867265.058149 depth/1311867265.058149.png +1311867265.080210 rgb/1311867265.080210.png 1311867265.091172 depth/1311867265.091172.png +1311867265.112164 rgb/1311867265.112164.png 1311867265.121711 depth/1311867265.121711.png +1311867265.148104 rgb/1311867265.148104.png 1311867265.158209 depth/1311867265.158209.png +1311867265.180303 rgb/1311867265.180303.png 1311867265.189952 depth/1311867265.189952.png +1311867265.212300 rgb/1311867265.212300.png 1311867265.222522 depth/1311867265.222522.png +1311867265.248214 rgb/1311867265.248214.png 1311867265.258185 depth/1311867265.258185.png +1311867265.280318 rgb/1311867265.280318.png 1311867265.291513 depth/1311867265.291513.png +1311867265.312310 rgb/1311867265.312310.png 1311867265.322086 depth/1311867265.322086.png +1311867265.348200 rgb/1311867265.348200.png 1311867265.358559 depth/1311867265.358559.png +1311867265.380133 rgb/1311867265.380133.png 1311867265.391247 depth/1311867265.391247.png +1311867265.412207 rgb/1311867265.412207.png 1311867265.424453 depth/1311867265.424453.png +1311867265.448180 rgb/1311867265.448180.png 1311867265.460441 depth/1311867265.460441.png +1311867265.480231 rgb/1311867265.480231.png 1311867265.490242 depth/1311867265.490242.png +1311867265.512277 rgb/1311867265.512277.png 1311867265.523057 depth/1311867265.523057.png +1311867265.548378 rgb/1311867265.548378.png 1311867265.559452 depth/1311867265.559452.png +1311867265.580223 rgb/1311867265.580223.png 1311867265.593230 depth/1311867265.593230.png +1311867265.612065 rgb/1311867265.612065.png 1311867265.625070 depth/1311867265.625070.png +1311867265.648285 rgb/1311867265.648285.png 1311867265.661073 depth/1311867265.661073.png +1311867265.680305 rgb/1311867265.680305.png 1311867265.695601 depth/1311867265.695601.png +1311867265.712166 rgb/1311867265.712166.png 1311867265.722189 depth/1311867265.722189.png +1311867265.748225 rgb/1311867265.748225.png 1311867265.762627 depth/1311867265.762627.png +1311867265.780694 rgb/1311867265.780694.png 1311867265.792592 depth/1311867265.792592.png +1311867265.812278 rgb/1311867265.812278.png 1311867265.822421 depth/1311867265.822421.png +1311867265.848187 rgb/1311867265.848187.png 1311867265.859339 depth/1311867265.859339.png +1311867265.880193 rgb/1311867265.880193.png 1311867265.894360 depth/1311867265.894360.png +1311867265.912326 rgb/1311867265.912326.png 1311867265.925645 depth/1311867265.925645.png +1311867265.948259 rgb/1311867265.948259.png 1311867265.962098 depth/1311867265.962098.png +1311867265.980599 rgb/1311867265.980599.png 1311867265.990899 depth/1311867265.990899.png +1311867266.012180 rgb/1311867266.012180.png 1311867266.023347 depth/1311867266.023347.png +1311867266.048362 rgb/1311867266.048362.png 1311867266.063426 depth/1311867266.063426.png +1311867266.080451 rgb/1311867266.080451.png 1311867266.095464 depth/1311867266.095464.png +1311867266.112239 rgb/1311867266.112239.png 1311867266.124160 depth/1311867266.124160.png +1311867266.148464 rgb/1311867266.148464.png 1311867266.163481 depth/1311867266.163481.png +1311867266.180282 rgb/1311867266.180282.png 1311867266.192269 depth/1311867266.192269.png +1311867266.212181 rgb/1311867266.212181.png 1311867266.225520 depth/1311867266.225520.png +1311867266.248205 rgb/1311867266.248205.png 1311867266.259785 depth/1311867266.259785.png +1311867266.280227 rgb/1311867266.280227.png 1311867266.291512 depth/1311867266.291512.png +1311867266.312311 rgb/1311867266.312311.png 1311867266.325804 depth/1311867266.325804.png +1311867266.348175 rgb/1311867266.348175.png 1311867266.360155 depth/1311867266.360155.png +1311867266.380379 rgb/1311867266.380379.png 1311867266.391316 depth/1311867266.391316.png +1311867266.412323 rgb/1311867266.412323.png 1311867266.425487 depth/1311867266.425487.png +1311867266.448402 rgb/1311867266.448402.png 1311867266.461291 depth/1311867266.461291.png +1311867266.480472 rgb/1311867266.480472.png 1311867266.491260 depth/1311867266.491260.png +1311867266.512523 rgb/1311867266.512523.png 1311867266.528493 depth/1311867266.528493.png +1311867266.548233 rgb/1311867266.548233.png 1311867266.558736 depth/1311867266.558736.png +1311867266.580375 rgb/1311867266.580375.png 1311867266.590682 depth/1311867266.590682.png +1311867266.612250 rgb/1311867266.612250.png 1311867266.625647 depth/1311867266.625647.png +1311867266.648261 rgb/1311867266.648261.png 1311867266.659642 depth/1311867266.659642.png +1311867266.680311 rgb/1311867266.680311.png 1311867266.691494 depth/1311867266.691494.png +1311867266.712145 rgb/1311867266.712145.png 1311867266.726079 depth/1311867266.726079.png +1311867266.748428 rgb/1311867266.748428.png 1311867266.757624 depth/1311867266.757624.png +1311867266.780320 rgb/1311867266.780320.png 1311867266.789824 depth/1311867266.789824.png +1311867266.812282 rgb/1311867266.812282.png 1311867266.825713 depth/1311867266.825713.png +1311867266.848160 rgb/1311867266.848160.png 1311867266.857500 depth/1311867266.857500.png +1311867266.880318 rgb/1311867266.880318.png 1311867266.889874 depth/1311867266.889874.png +1311867266.912179 rgb/1311867266.912179.png 1311867266.926619 depth/1311867266.926619.png +1311867266.948171 rgb/1311867266.948171.png 1311867266.957655 depth/1311867266.957655.png +1311867266.980363 rgb/1311867266.980363.png 1311867266.992077 depth/1311867266.992077.png +1311867267.012371 rgb/1311867267.012371.png 1311867267.025948 depth/1311867267.025948.png +1311867267.048343 rgb/1311867267.048343.png 1311867267.060361 depth/1311867267.060361.png +1311867267.080246 rgb/1311867267.080246.png 1311867267.092980 depth/1311867267.092980.png +1311867267.112351 rgb/1311867267.112351.png 1311867267.126690 depth/1311867267.126690.png +1311867267.148264 rgb/1311867267.148264.png 1311867267.158691 depth/1311867267.158691.png +1311867267.180231 rgb/1311867267.180231.png 1311867267.191613 depth/1311867267.191613.png +1311867267.212337 rgb/1311867267.212337.png 1311867267.226204 depth/1311867267.226204.png +1311867267.248213 rgb/1311867267.248213.png 1311867267.258745 depth/1311867267.258745.png +1311867267.280459 rgb/1311867267.280459.png 1311867267.292076 depth/1311867267.292076.png +1311867267.312219 rgb/1311867267.312219.png 1311867267.326581 depth/1311867267.326581.png +1311867267.348391 rgb/1311867267.348391.png 1311867267.360995 depth/1311867267.360995.png +1311867267.380442 rgb/1311867267.380442.png 1311867267.394598 depth/1311867267.394598.png +1311867267.412292 rgb/1311867267.412292.png 1311867267.428619 depth/1311867267.428619.png +1311867267.448184 rgb/1311867267.448184.png 1311867267.459579 depth/1311867267.459579.png +1311867267.480293 rgb/1311867267.480293.png 1311867267.493543 depth/1311867267.493543.png +1311867267.512328 rgb/1311867267.512328.png 1311867267.526410 depth/1311867267.526410.png +1311867267.548255 rgb/1311867267.548255.png 1311867267.557797 depth/1311867267.557797.png +1311867267.580291 rgb/1311867267.580291.png 1311867267.595448 depth/1311867267.595448.png +1311867267.612361 rgb/1311867267.612361.png 1311867267.627202 depth/1311867267.627202.png +1311867267.648438 rgb/1311867267.648438.png 1311867267.660897 depth/1311867267.660897.png +1311867267.680321 rgb/1311867267.680321.png 1311867267.695573 depth/1311867267.695573.png +1311867267.712540 rgb/1311867267.712540.png 1311867267.726455 depth/1311867267.726455.png +1311867267.748385 rgb/1311867267.748385.png 1311867267.762498 depth/1311867267.762498.png +1311867267.780391 rgb/1311867267.780391.png 1311867267.795798 depth/1311867267.795798.png +1311867267.812725 rgb/1311867267.812725.png 1311867267.832397 depth/1311867267.832397.png +1311867267.848368 rgb/1311867267.848368.png 1311867267.860108 depth/1311867267.860108.png +1311867267.912736 rgb/1311867267.912736.png 1311867267.898958 depth/1311867267.898958.png +1311867267.948451 rgb/1311867267.948451.png 1311867267.964301 depth/1311867267.964301.png +1311867267.980316 rgb/1311867267.980316.png 1311867267.994746 depth/1311867267.994746.png +1311867268.012300 rgb/1311867268.012300.png 1311867268.028712 depth/1311867268.028712.png +1311867268.048405 rgb/1311867268.048405.png 1311867268.058833 depth/1311867268.058833.png +1311867268.080313 rgb/1311867268.080313.png 1311867268.094608 depth/1311867268.094608.png +1311867268.112446 rgb/1311867268.112446.png 1311867268.125391 depth/1311867268.125391.png +1311867268.148507 rgb/1311867268.148507.png 1311867268.160666 depth/1311867268.160666.png +1311867268.212453 rgb/1311867268.212453.png 1311867268.198196 depth/1311867268.198196.png +1311867268.248305 rgb/1311867268.248305.png 1311867268.257920 depth/1311867268.257920.png +1311867268.280500 rgb/1311867268.280500.png 1311867268.295155 depth/1311867268.295155.png +1311867268.312510 rgb/1311867268.312510.png 1311867268.327417 depth/1311867268.327417.png +1311867268.348270 rgb/1311867268.348270.png 1311867268.358689 depth/1311867268.358689.png +1311867268.380493 rgb/1311867268.380493.png 1311867268.393480 depth/1311867268.393480.png +1311867268.412369 rgb/1311867268.412369.png 1311867268.426148 depth/1311867268.426148.png +1311867268.448606 rgb/1311867268.448606.png 1311867268.458117 depth/1311867268.458117.png +1311867268.480858 rgb/1311867268.480858.png 1311867268.494354 depth/1311867268.494354.png +1311867268.512523 rgb/1311867268.512523.png 1311867268.528033 depth/1311867268.528033.png +1311867268.548506 rgb/1311867268.548506.png 1311867268.561615 depth/1311867268.561615.png +1311867268.580494 rgb/1311867268.580494.png 1311867268.594934 depth/1311867268.594934.png +1311867268.616531 rgb/1311867268.616531.png 1311867268.629458 depth/1311867268.629458.png +1311867268.648346 rgb/1311867268.648346.png 1311867268.663937 depth/1311867268.663937.png +1311867268.680446 rgb/1311867268.680446.png 1311867268.693781 depth/1311867268.693781.png +1311867268.716434 rgb/1311867268.716434.png 1311867268.728257 depth/1311867268.728257.png +1311867268.748466 rgb/1311867268.748466.png 1311867268.762931 depth/1311867268.762931.png +1311867268.780581 rgb/1311867268.780581.png 1311867268.795122 depth/1311867268.795122.png +1311867268.816596 rgb/1311867268.816596.png 1311867268.826463 depth/1311867268.826463.png +1311867268.848629 rgb/1311867268.848629.png 1311867268.861582 depth/1311867268.861582.png +1311867268.880642 rgb/1311867268.880642.png 1311867268.894771 depth/1311867268.894771.png +1311867268.916457 rgb/1311867268.916457.png 1311867268.927190 depth/1311867268.927190.png +1311867268.948366 rgb/1311867268.948366.png 1311867268.963374 depth/1311867268.963374.png +1311867268.980529 rgb/1311867268.980529.png 1311867268.994226 depth/1311867268.994226.png +1311867269.016581 rgb/1311867269.016581.png 1311867269.029342 depth/1311867269.029342.png +1311867269.048325 rgb/1311867269.048325.png 1311867269.062834 depth/1311867269.062834.png +1311867269.082135 rgb/1311867269.082135.png 1311867269.094213 depth/1311867269.094213.png +1311867269.116536 rgb/1311867269.116536.png 1311867269.126398 depth/1311867269.126398.png +1311867269.148627 rgb/1311867269.148627.png 1311867269.161827 depth/1311867269.161827.png +1311867269.180463 rgb/1311867269.180463.png 1311867269.194162 depth/1311867269.194162.png +1311867269.216287 rgb/1311867269.216287.png 1311867269.226625 depth/1311867269.226625.png +1311867269.248318 rgb/1311867269.248318.png 1311867269.262372 depth/1311867269.262372.png +1311867269.280464 rgb/1311867269.280464.png 1311867269.294820 depth/1311867269.294820.png +1311867269.316373 rgb/1311867269.316373.png 1311867269.326183 depth/1311867269.326183.png +1311867269.348345 rgb/1311867269.348345.png 1311867269.364156 depth/1311867269.364156.png +1311867269.380431 rgb/1311867269.380431.png 1311867269.396774 depth/1311867269.396774.png +1311867269.416552 rgb/1311867269.416552.png 1311867269.427582 depth/1311867269.427582.png +1311867269.448314 rgb/1311867269.448314.png 1311867269.462644 depth/1311867269.462644.png +1311867269.480591 rgb/1311867269.480591.png 1311867269.493828 depth/1311867269.493828.png +1311867269.516521 rgb/1311867269.516521.png 1311867269.527859 depth/1311867269.527859.png +1311867269.548348 rgb/1311867269.548348.png 1311867269.563459 depth/1311867269.563459.png +1311867269.580494 rgb/1311867269.580494.png 1311867269.596239 depth/1311867269.596239.png +1311867269.616429 rgb/1311867269.616429.png 1311867269.630608 depth/1311867269.630608.png +1311867269.648449 rgb/1311867269.648449.png 1311867269.663156 depth/1311867269.663156.png +1311867269.680483 rgb/1311867269.680483.png 1311867269.696460 depth/1311867269.696460.png +1311867269.716488 rgb/1311867269.716488.png 1311867269.728087 depth/1311867269.728087.png +1311867269.748333 rgb/1311867269.748333.png 1311867269.762226 depth/1311867269.762226.png +1311867269.780366 rgb/1311867269.780366.png 1311867269.797409 depth/1311867269.797409.png +1311867269.816455 rgb/1311867269.816455.png 1311867269.829587 depth/1311867269.829587.png +1311867269.880365 rgb/1311867269.880365.png 1311867269.867623 depth/1311867269.867623.png +1311867269.948447 rgb/1311867269.948447.png 1311867269.934472 depth/1311867269.934472.png +1311867269.980791 rgb/1311867269.980791.png 1311867269.998726 depth/1311867269.998726.png +1311867270.016606 rgb/1311867270.016606.png 1311867270.030699 depth/1311867270.030699.png +1311867270.048449 rgb/1311867270.048449.png 1311867270.066095 depth/1311867270.066095.png +1311867270.080609 rgb/1311867270.080609.png 1311867270.094820 depth/1311867270.094820.png +1311867270.116645 rgb/1311867270.116645.png 1311867270.133634 depth/1311867270.133634.png +1311867270.148642 rgb/1311867270.148642.png 1311867270.162409 depth/1311867270.162409.png +1311867270.180528 rgb/1311867270.180528.png 1311867270.194354 depth/1311867270.194354.png +1311867270.216437 rgb/1311867270.216437.png 1311867270.232337 depth/1311867270.232337.png +1311867270.280555 rgb/1311867270.280555.png 1311867270.265575 depth/1311867270.265575.png +1311867270.348361 rgb/1311867270.348361.png 1311867270.334610 depth/1311867270.334610.png +1311867270.380591 rgb/1311867270.380591.png 1311867270.395747 depth/1311867270.395747.png +1311867270.448370 rgb/1311867270.448370.png 1311867270.433436 depth/1311867270.433436.png +1311867270.480611 rgb/1311867270.480611.png 1311867270.495461 depth/1311867270.495461.png +1311867270.516588 rgb/1311867270.516588.png 1311867270.533187 depth/1311867270.533187.png +1311867270.548435 rgb/1311867270.548435.png 1311867270.562988 depth/1311867270.562988.png +1311867270.580811 rgb/1311867270.580811.png 1311867270.594486 depth/1311867270.594486.png +1311867270.616443 rgb/1311867270.616443.png 1311867270.631211 depth/1311867270.631211.png +1311867270.648558 rgb/1311867270.648558.png 1311867270.664444 depth/1311867270.664444.png +1311867270.680625 rgb/1311867270.680625.png 1311867270.695018 depth/1311867270.695018.png +1311867270.716482 rgb/1311867270.716482.png 1311867270.731845 depth/1311867270.731845.png +1311867270.748564 rgb/1311867270.748564.png 1311867270.762390 depth/1311867270.762390.png +1311867270.780573 rgb/1311867270.780573.png 1311867270.796050 depth/1311867270.796050.png +1311867270.816524 rgb/1311867270.816524.png 1311867270.832273 depth/1311867270.832273.png +1311867270.848467 rgb/1311867270.848467.png 1311867270.863549 depth/1311867270.863549.png +1311867270.880574 rgb/1311867270.880574.png 1311867270.894589 depth/1311867270.894589.png +1311867270.916494 rgb/1311867270.916494.png 1311867270.932618 depth/1311867270.932618.png +1311867270.948425 rgb/1311867270.948425.png 1311867270.962455 depth/1311867270.962455.png +1311867270.980570 rgb/1311867270.980570.png 1311867270.994456 depth/1311867270.994456.png +1311867271.016615 rgb/1311867271.016615.png 1311867271.030665 depth/1311867271.030665.png +1311867271.048583 rgb/1311867271.048583.png 1311867271.062391 depth/1311867271.062391.png +1311867271.080591 rgb/1311867271.080591.png 1311867271.098346 depth/1311867271.098346.png +1311867271.116562 rgb/1311867271.116562.png 1311867271.132202 depth/1311867271.132202.png +1311867271.152897 rgb/1311867271.152897.png 1311867271.164374 depth/1311867271.164374.png +1311867271.180582 rgb/1311867271.180582.png 1311867271.198803 depth/1311867271.198803.png +1311867271.216570 rgb/1311867271.216570.png 1311867271.232082 depth/1311867271.232082.png +1311867271.280629 rgb/1311867271.280629.png 1311867271.264574 depth/1311867271.264574.png +1311867271.316655 rgb/1311867271.316655.png 1311867271.299855 depth/1311867271.299855.png +1311867271.348780 rgb/1311867271.348780.png 1311867271.335429 depth/1311867271.335429.png +1311867271.380667 rgb/1311867271.380667.png 1311867271.367367 depth/1311867271.367367.png +1311867271.416663 rgb/1311867271.416663.png 1311867271.398881 depth/1311867271.398881.png +1311867271.448701 rgb/1311867271.448701.png 1311867271.435534 depth/1311867271.435534.png +1311867271.480623 rgb/1311867271.480623.png 1311867271.465717 depth/1311867271.465717.png +1311867271.516531 rgb/1311867271.516531.png 1311867271.532396 depth/1311867271.532396.png +1311867271.580572 rgb/1311867271.580572.png 1311867271.567619 depth/1311867271.567619.png +1311867271.616650 rgb/1311867271.616650.png 1311867271.599123 depth/1311867271.599123.png +1311867271.648669 rgb/1311867271.648669.png 1311867271.634989 depth/1311867271.634989.png +1311867271.680718 rgb/1311867271.680718.png 1311867271.665832 depth/1311867271.665832.png +1311867271.716588 rgb/1311867271.716588.png 1311867271.700523 depth/1311867271.700523.png +1311867271.749245 rgb/1311867271.749245.png 1311867271.734954 depth/1311867271.734954.png +1311867271.780613 rgb/1311867271.780613.png 1311867271.766185 depth/1311867271.766185.png +1311867271.816503 rgb/1311867271.816503.png 1311867271.799453 depth/1311867271.799453.png +1311867271.848511 rgb/1311867271.848511.png 1311867271.862915 depth/1311867271.862915.png +1311867271.916677 rgb/1311867271.916677.png 1311867271.930480 depth/1311867271.930480.png +1311867271.980726 rgb/1311867271.980726.png 1311867271.966977 depth/1311867271.966977.png +1311867272.016678 rgb/1311867272.016678.png 1311867272.033760 depth/1311867272.033760.png +1311867272.048486 rgb/1311867272.048486.png 1311867272.062640 depth/1311867272.062640.png +1311867272.116570 rgb/1311867272.116570.png 1311867272.098803 depth/1311867272.098803.png +1311867272.148719 rgb/1311867272.148719.png 1311867272.133621 depth/1311867272.133621.png +1311867272.180820 rgb/1311867272.180820.png 1311867272.165935 depth/1311867272.165935.png +1311867272.216614 rgb/1311867272.216614.png 1311867272.231976 depth/1311867272.231976.png +1311867272.280675 rgb/1311867272.280675.png 1311867272.265511 depth/1311867272.265511.png +1311867272.316580 rgb/1311867272.316580.png 1311867272.331502 depth/1311867272.331502.png +1311867272.380604 rgb/1311867272.380604.png 1311867272.369675 depth/1311867272.369675.png +1311867272.416575 rgb/1311867272.416575.png 1311867272.398705 depth/1311867272.398705.png +1311867272.448579 rgb/1311867272.448579.png 1311867272.433573 depth/1311867272.433573.png +1311867272.481087 rgb/1311867272.481087.png 1311867272.468614 depth/1311867272.468614.png +1311867272.516777 rgb/1311867272.516777.png 1311867272.501142 depth/1311867272.501142.png +1311867272.548588 rgb/1311867272.548588.png 1311867272.532548 depth/1311867272.532548.png +1311867272.580582 rgb/1311867272.580582.png 1311867272.567660 depth/1311867272.567660.png +1311867272.616652 rgb/1311867272.616652.png 1311867272.631536 depth/1311867272.631536.png +1311867272.680692 rgb/1311867272.680692.png 1311867272.666129 depth/1311867272.666129.png +1311867272.716489 rgb/1311867272.716489.png 1311867272.730711 depth/1311867272.730711.png +1311867272.780656 rgb/1311867272.780656.png 1311867272.768615 depth/1311867272.768615.png +1311867272.816623 rgb/1311867272.816623.png 1311867272.831016 depth/1311867272.831016.png +1311867272.880537 rgb/1311867272.880537.png 1311867272.867485 depth/1311867272.867485.png +1311867272.916603 rgb/1311867272.916603.png 1311867272.931411 depth/1311867272.931411.png +1311867272.980676 rgb/1311867272.980676.png 1311867272.966467 depth/1311867272.966467.png +1311867273.016608 rgb/1311867273.016608.png 1311867272.998760 depth/1311867272.998760.png +1311867273.048578 rgb/1311867273.048578.png 1311867273.032849 depth/1311867273.032849.png +1311867273.080754 rgb/1311867273.080754.png 1311867273.066274 depth/1311867273.066274.png +1311867273.116731 rgb/1311867273.116731.png 1311867273.131071 depth/1311867273.131071.png +1311867273.180697 rgb/1311867273.180697.png 1311867273.166574 depth/1311867273.166574.png +1311867273.216838 rgb/1311867273.216838.png 1311867273.199752 depth/1311867273.199752.png +1311867273.248544 rgb/1311867273.248544.png 1311867273.233182 depth/1311867273.233182.png +1311867273.280714 rgb/1311867273.280714.png 1311867273.266838 depth/1311867273.266838.png +1311867273.316838 rgb/1311867273.316838.png 1311867273.330801 depth/1311867273.330801.png +1311867273.380697 rgb/1311867273.380697.png 1311867273.366351 depth/1311867273.366351.png +1311867273.416830 rgb/1311867273.416830.png 1311867273.430841 depth/1311867273.430841.png +1311867273.480769 rgb/1311867273.480769.png 1311867273.466325 depth/1311867273.466325.png +1311867273.516690 rgb/1311867273.516690.png 1311867273.531842 depth/1311867273.531842.png +1311867273.580631 rgb/1311867273.580631.png 1311867273.568791 depth/1311867273.568791.png +1311867273.616742 rgb/1311867273.616742.png 1311867273.600039 depth/1311867273.600039.png +1311867273.648674 rgb/1311867273.648674.png 1311867273.634960 depth/1311867273.634960.png +1311867273.680974 rgb/1311867273.680974.png 1311867273.667377 depth/1311867273.667377.png +1311867273.716707 rgb/1311867273.716707.png 1311867273.698786 depth/1311867273.698786.png +1311867273.748711 rgb/1311867273.748711.png 1311867273.734674 depth/1311867273.734674.png +1311867273.780735 rgb/1311867273.780735.png 1311867273.766596 depth/1311867273.766596.png +1311867273.816639 rgb/1311867273.816639.png 1311867273.799070 depth/1311867273.799070.png +1311867273.849123 rgb/1311867273.849123.png 1311867273.835813 depth/1311867273.835813.png +1311867273.880737 rgb/1311867273.880737.png 1311867273.866806 depth/1311867273.866806.png +1311867273.916618 rgb/1311867273.916618.png 1311867273.899072 depth/1311867273.899072.png +1311867273.949213 rgb/1311867273.949213.png 1311867273.938482 depth/1311867273.938482.png +1311867273.980666 rgb/1311867273.980666.png 1311867273.966905 depth/1311867273.966905.png +1311867274.016822 rgb/1311867274.016822.png 1311867273.999658 depth/1311867273.999658.png +1311867274.048756 rgb/1311867274.048756.png 1311867274.034849 depth/1311867274.034849.png +1311867274.080678 rgb/1311867274.080678.png 1311867274.067002 depth/1311867274.067002.png +1311867274.116619 rgb/1311867274.116619.png 1311867274.102568 depth/1311867274.102568.png +1311867274.149224 rgb/1311867274.149224.png 1311867274.135057 depth/1311867274.135057.png +1311867274.180919 rgb/1311867274.180919.png 1311867274.166797 depth/1311867274.166797.png +1311867274.216954 rgb/1311867274.216954.png 1311867274.200855 depth/1311867274.200855.png +1311867274.248965 rgb/1311867274.248965.png 1311867274.238918 depth/1311867274.238918.png +1311867274.280784 rgb/1311867274.280784.png 1311867274.266854 depth/1311867274.266854.png +1311867274.317121 rgb/1311867274.317121.png 1311867274.301894 depth/1311867274.301894.png +1311867274.348830 rgb/1311867274.348830.png 1311867274.335814 depth/1311867274.335814.png +1311867274.380862 rgb/1311867274.380862.png 1311867274.367976 depth/1311867274.367976.png +1311867274.416837 rgb/1311867274.416837.png 1311867274.400755 depth/1311867274.400755.png +1311867274.448780 rgb/1311867274.448780.png 1311867274.435768 depth/1311867274.435768.png +1311867274.480661 rgb/1311867274.480661.png 1311867274.468921 depth/1311867274.468921.png +1311867274.516798 rgb/1311867274.516798.png 1311867274.499770 depth/1311867274.499770.png +1311867274.548944 rgb/1311867274.548944.png 1311867274.534598 depth/1311867274.534598.png +1311867274.580883 rgb/1311867274.580883.png 1311867274.568684 depth/1311867274.568684.png +1311867274.616863 rgb/1311867274.616863.png 1311867274.600119 depth/1311867274.600119.png +1311867274.649010 rgb/1311867274.649010.png 1311867274.634927 depth/1311867274.634927.png +1311867274.680804 rgb/1311867274.680804.png 1311867274.666565 depth/1311867274.666565.png +1311867274.716711 rgb/1311867274.716711.png 1311867274.698870 depth/1311867274.698870.png +1311867274.748763 rgb/1311867274.748763.png 1311867274.735576 depth/1311867274.735576.png +1311867274.780646 rgb/1311867274.780646.png 1311867274.766900 depth/1311867274.766900.png +1311867274.816702 rgb/1311867274.816702.png 1311867274.804002 depth/1311867274.804002.png +1311867274.848794 rgb/1311867274.848794.png 1311867274.835089 depth/1311867274.835089.png +1311867274.880821 rgb/1311867274.880821.png 1311867274.867136 depth/1311867274.867136.png +1311867274.916628 rgb/1311867274.916628.png 1311867274.904429 depth/1311867274.904429.png +1311867274.948646 rgb/1311867274.948646.png 1311867274.935055 depth/1311867274.935055.png +1311867274.980903 rgb/1311867274.980903.png 1311867274.966649 depth/1311867274.966649.png +1311867275.016675 rgb/1311867275.016675.png 1311867275.003083 depth/1311867275.003083.png +1311867275.048721 rgb/1311867275.048721.png 1311867275.036808 depth/1311867275.036808.png +1311867275.080754 rgb/1311867275.080754.png 1311867275.066445 depth/1311867275.066445.png +1311867275.116833 rgb/1311867275.116833.png 1311867275.102327 depth/1311867275.102327.png +1311867275.148689 rgb/1311867275.148689.png 1311867275.135123 depth/1311867275.135123.png +1311867275.180701 rgb/1311867275.180701.png 1311867275.166718 depth/1311867275.166718.png +1311867275.216737 rgb/1311867275.216737.png 1311867275.204175 depth/1311867275.204175.png +1311867275.248735 rgb/1311867275.248735.png 1311867275.237178 depth/1311867275.237178.png +1311867275.280811 rgb/1311867275.280811.png 1311867275.266818 depth/1311867275.266818.png +1311867275.316666 rgb/1311867275.316666.png 1311867275.302680 depth/1311867275.302680.png +1311867275.348709 rgb/1311867275.348709.png 1311867275.335188 depth/1311867275.335188.png +1311867275.381040 rgb/1311867275.381040.png 1311867275.366911 depth/1311867275.366911.png +1311867275.416695 rgb/1311867275.416695.png 1311867275.403837 depth/1311867275.403837.png +1311867275.448851 rgb/1311867275.448851.png 1311867275.434960 depth/1311867275.434960.png +1311867275.480860 rgb/1311867275.480860.png 1311867275.466940 depth/1311867275.466940.png +1311867275.516817 rgb/1311867275.516817.png 1311867275.503729 depth/1311867275.503729.png +1311867275.548814 rgb/1311867275.548814.png 1311867275.535333 depth/1311867275.535333.png +1311867275.580874 rgb/1311867275.580874.png 1311867275.566891 depth/1311867275.566891.png +1311867275.616794 rgb/1311867275.616794.png 1311867275.602830 depth/1311867275.602830.png +1311867275.648733 rgb/1311867275.648733.png 1311867275.638328 depth/1311867275.638328.png +1311867275.680883 rgb/1311867275.680883.png 1311867275.668221 depth/1311867275.668221.png +1311867275.716827 rgb/1311867275.716827.png 1311867275.704589 depth/1311867275.704589.png +1311867275.749216 rgb/1311867275.749216.png 1311867275.734982 depth/1311867275.734982.png +1311867275.780810 rgb/1311867275.780810.png 1311867275.779228 depth/1311867275.779228.png +1311867275.816772 rgb/1311867275.816772.png 1311867275.802849 depth/1311867275.802849.png +1311867275.848840 rgb/1311867275.848840.png 1311867275.835596 depth/1311867275.835596.png +1311867275.880760 rgb/1311867275.880760.png 1311867275.870156 depth/1311867275.870156.png +1311867275.917061 rgb/1311867275.917061.png 1311867275.903212 depth/1311867275.903212.png +1311867275.948821 rgb/1311867275.948821.png 1311867275.937132 depth/1311867275.937132.png +1311867275.980896 rgb/1311867275.980896.png 1311867275.968386 depth/1311867275.968386.png +1311867276.016817 rgb/1311867276.016817.png 1311867276.004847 depth/1311867276.004847.png +1311867276.048985 rgb/1311867276.048985.png 1311867276.038754 depth/1311867276.038754.png +1311867276.081061 rgb/1311867276.081061.png 1311867276.073903 depth/1311867276.073903.png +1311867276.117046 rgb/1311867276.117046.png 1311867276.105137 depth/1311867276.105137.png +1311867276.148911 rgb/1311867276.148911.png 1311867276.138238 depth/1311867276.138238.png +1311867276.180826 rgb/1311867276.180826.png 1311867276.170939 depth/1311867276.170939.png +1311867276.216827 rgb/1311867276.216827.png 1311867276.204228 depth/1311867276.204228.png +1311867276.248954 rgb/1311867276.248954.png 1311867276.235786 depth/1311867276.235786.png +1311867276.281034 rgb/1311867276.281034.png 1311867276.274772 depth/1311867276.274772.png +1311867276.316847 rgb/1311867276.316847.png 1311867276.302752 depth/1311867276.302752.png +1311867276.348823 rgb/1311867276.348823.png 1311867276.338719 depth/1311867276.338719.png +1311867276.380997 rgb/1311867276.380997.png 1311867276.372960 depth/1311867276.372960.png +1311867276.416760 rgb/1311867276.416760.png 1311867276.403193 depth/1311867276.403193.png +1311867276.449013 rgb/1311867276.449013.png 1311867276.436013 depth/1311867276.436013.png +1311867276.481045 rgb/1311867276.481045.png 1311867276.473709 depth/1311867276.473709.png +1311867276.516812 rgb/1311867276.516812.png 1311867276.504842 depth/1311867276.504842.png +1311867276.548975 rgb/1311867276.548975.png 1311867276.538747 depth/1311867276.538747.png +1311867276.581007 rgb/1311867276.581007.png 1311867276.574678 depth/1311867276.574678.png +1311867276.616955 rgb/1311867276.616955.png 1311867276.604192 depth/1311867276.604192.png +1311867276.648797 rgb/1311867276.648797.png 1311867276.636147 depth/1311867276.636147.png +1311867276.680881 rgb/1311867276.680881.png 1311867276.671092 depth/1311867276.671092.png +1311867276.716834 rgb/1311867276.716834.png 1311867276.702972 depth/1311867276.702972.png +1311867276.749007 rgb/1311867276.749007.png 1311867276.736078 depth/1311867276.736078.png +1311867276.781174 rgb/1311867276.781174.png 1311867276.772196 depth/1311867276.772196.png +1311867276.816885 rgb/1311867276.816885.png 1311867276.802909 depth/1311867276.802909.png +1311867276.849154 rgb/1311867276.849154.png 1311867276.837570 depth/1311867276.837570.png +1311867276.880864 rgb/1311867276.880864.png 1311867276.874097 depth/1311867276.874097.png +1311867276.916961 rgb/1311867276.916961.png 1311867276.902975 depth/1311867276.902975.png +1311867276.948866 rgb/1311867276.948866.png 1311867276.937498 depth/1311867276.937498.png +1311867276.980866 rgb/1311867276.980866.png 1311867276.972691 depth/1311867276.972691.png +1311867277.016880 rgb/1311867277.016880.png 1311867277.005003 depth/1311867277.005003.png +1311867277.049009 rgb/1311867277.049009.png 1311867277.035607 depth/1311867277.035607.png +1311867277.081265 rgb/1311867277.081265.png 1311867277.071161 depth/1311867277.071161.png +1311867277.116824 rgb/1311867277.116824.png 1311867277.103977 depth/1311867277.103977.png +1311867277.148834 rgb/1311867277.148834.png 1311867277.135027 depth/1311867277.135027.png +1311867277.180831 rgb/1311867277.180831.png 1311867277.170849 depth/1311867277.170849.png +1311867277.216967 rgb/1311867277.216967.png 1311867277.202976 depth/1311867277.202976.png +1311867277.248926 rgb/1311867277.248926.png 1311867277.235100 depth/1311867277.235100.png +1311867277.280849 rgb/1311867277.280849.png 1311867277.273315 depth/1311867277.273315.png +1311867277.316929 rgb/1311867277.316929.png 1311867277.306378 depth/1311867277.306378.png +1311867277.349051 rgb/1311867277.349051.png 1311867277.339603 depth/1311867277.339603.png +1311867277.384209 rgb/1311867277.384209.png 1311867277.377389 depth/1311867277.377389.png +1311867277.416922 rgb/1311867277.416922.png 1311867277.405553 depth/1311867277.405553.png +1311867277.450161 rgb/1311867277.450161.png 1311867277.442508 depth/1311867277.442508.png +1311867277.480901 rgb/1311867277.480901.png 1311867277.472375 depth/1311867277.472375.png +1311867277.517078 rgb/1311867277.517078.png 1311867277.505778 depth/1311867277.505778.png +1311867277.548828 rgb/1311867277.548828.png 1311867277.540194 depth/1311867277.540194.png +1311867277.580920 rgb/1311867277.580920.png 1311867277.571535 depth/1311867277.571535.png +1311867277.616897 rgb/1311867277.616897.png 1311867277.602771 depth/1311867277.602771.png +1311867277.649076 rgb/1311867277.649076.png 1311867277.641613 depth/1311867277.641613.png +1311867277.681057 rgb/1311867277.681057.png 1311867277.671301 depth/1311867277.671301.png +1311867277.717139 rgb/1311867277.717139.png 1311867277.706359 depth/1311867277.706359.png +1311867277.748909 rgb/1311867277.748909.png 1311867277.740141 depth/1311867277.740141.png +1311867277.784818 rgb/1311867277.784818.png 1311867277.772008 depth/1311867277.772008.png +1311867277.816868 rgb/1311867277.816868.png 1311867277.803688 depth/1311867277.803688.png +1311867277.848906 rgb/1311867277.848906.png 1311867277.840050 depth/1311867277.840050.png +1311867277.884896 rgb/1311867277.884896.png 1311867277.871117 depth/1311867277.871117.png +1311867277.916858 rgb/1311867277.916858.png 1311867277.903161 depth/1311867277.903161.png +1311867277.948933 rgb/1311867277.948933.png 1311867277.939302 depth/1311867277.939302.png +1311867277.985092 rgb/1311867277.985092.png 1311867277.971423 depth/1311867277.971423.png +1311867278.016848 rgb/1311867278.016848.png 1311867278.004136 depth/1311867278.004136.png +1311867278.049001 rgb/1311867278.049001.png 1311867278.039421 depth/1311867278.039421.png +1311867278.084826 rgb/1311867278.084826.png 1311867278.071263 depth/1311867278.071263.png +1311867278.116862 rgb/1311867278.116862.png 1311867278.105629 depth/1311867278.105629.png +1311867278.149018 rgb/1311867278.149018.png 1311867278.139198 depth/1311867278.139198.png +1311867278.184865 rgb/1311867278.184865.png 1311867278.171037 depth/1311867278.171037.png +1311867278.216940 rgb/1311867278.216940.png 1311867278.203861 depth/1311867278.203861.png +1311867278.248940 rgb/1311867278.248940.png 1311867278.238806 depth/1311867278.238806.png +1311867278.284908 rgb/1311867278.284908.png 1311867278.270763 depth/1311867278.270763.png +1311867278.317404 rgb/1311867278.317404.png 1311867278.302763 depth/1311867278.302763.png +1311867278.349011 rgb/1311867278.349011.png 1311867278.342160 depth/1311867278.342160.png +1311867278.384931 rgb/1311867278.384931.png 1311867278.371436 depth/1311867278.371436.png +1311867278.416856 rgb/1311867278.416856.png 1311867278.403535 depth/1311867278.403535.png +1311867278.448914 rgb/1311867278.448914.png 1311867278.439117 depth/1311867278.439117.png +1311867278.485032 rgb/1311867278.485032.png 1311867278.471334 depth/1311867278.471334.png +1311867278.516899 rgb/1311867278.516899.png 1311867278.504124 depth/1311867278.504124.png +1311867278.549265 rgb/1311867278.549265.png 1311867278.542391 depth/1311867278.542391.png +1311867278.584923 rgb/1311867278.584923.png 1311867278.571026 depth/1311867278.571026.png +1311867278.616874 rgb/1311867278.616874.png 1311867278.606903 depth/1311867278.606903.png +1311867278.649080 rgb/1311867278.649080.png 1311867278.639324 depth/1311867278.639324.png +1311867278.684905 rgb/1311867278.684905.png 1311867278.670971 depth/1311867278.670971.png +1311867278.717052 rgb/1311867278.717052.png 1311867278.706913 depth/1311867278.706913.png +1311867278.749117 rgb/1311867278.749117.png 1311867278.739068 depth/1311867278.739068.png +1311867278.785013 rgb/1311867278.785013.png 1311867278.771830 depth/1311867278.771830.png +1311867278.816933 rgb/1311867278.816933.png 1311867278.806824 depth/1311867278.806824.png +1311867278.848909 rgb/1311867278.848909.png 1311867278.838653 depth/1311867278.838653.png +1311867278.884953 rgb/1311867278.884953.png 1311867278.874170 depth/1311867278.874170.png +1311867278.916959 rgb/1311867278.916959.png 1311867278.909065 depth/1311867278.909065.png +1311867278.949082 rgb/1311867278.949082.png 1311867278.939277 depth/1311867278.939277.png +1311867278.985050 rgb/1311867278.985050.png 1311867278.971143 depth/1311867278.971143.png +1311867279.016951 rgb/1311867279.016951.png 1311867279.007311 depth/1311867279.007311.png +1311867279.049207 rgb/1311867279.049207.png 1311867279.039773 depth/1311867279.039773.png +1311867279.085000 rgb/1311867279.085000.png 1311867279.073854 depth/1311867279.073854.png +1311867279.117024 rgb/1311867279.117024.png 1311867279.106844 depth/1311867279.106844.png +1311867279.149152 rgb/1311867279.149152.png 1311867279.139249 depth/1311867279.139249.png +1311867279.185056 rgb/1311867279.185056.png 1311867279.171204 depth/1311867279.171204.png +1311867279.216910 rgb/1311867279.216910.png 1311867279.207044 depth/1311867279.207044.png +1311867279.249252 rgb/1311867279.249252.png 1311867279.241121 depth/1311867279.241121.png +1311867279.284982 rgb/1311867279.284982.png 1311867279.271776 depth/1311867279.271776.png +1311867279.317001 rgb/1311867279.317001.png 1311867279.306722 depth/1311867279.306722.png +1311867279.349109 rgb/1311867279.349109.png 1311867279.338809 depth/1311867279.338809.png +1311867279.385350 rgb/1311867279.385350.png 1311867279.380493 depth/1311867279.380493.png +1311867279.417132 rgb/1311867279.417132.png 1311867279.408991 depth/1311867279.408991.png +1311867279.448972 rgb/1311867279.448972.png 1311867279.441097 depth/1311867279.441097.png +1311867279.485178 rgb/1311867279.485178.png 1311867279.472557 depth/1311867279.472557.png +1311867279.517352 rgb/1311867279.517352.png 1311867279.509571 depth/1311867279.509571.png +1311867279.549112 rgb/1311867279.549112.png 1311867279.540739 depth/1311867279.540739.png +1311867279.585000 rgb/1311867279.585000.png 1311867279.573423 depth/1311867279.573423.png +1311867279.617658 rgb/1311867279.617658.png 1311867279.612164 depth/1311867279.612164.png +1311867279.649149 rgb/1311867279.649149.png 1311867279.638944 depth/1311867279.638944.png +1311867279.685122 rgb/1311867279.685122.png 1311867279.674977 depth/1311867279.674977.png +1311867279.717608 rgb/1311867279.717608.png 1311867279.710798 depth/1311867279.710798.png +1311867279.749168 rgb/1311867279.749168.png 1311867279.741020 depth/1311867279.741020.png +1311867279.785184 rgb/1311867279.785184.png 1311867279.777706 depth/1311867279.777706.png +1311867279.817277 rgb/1311867279.817277.png 1311867279.811885 depth/1311867279.811885.png +1311867279.849225 rgb/1311867279.849225.png 1311867279.843825 depth/1311867279.843825.png +1311867279.885430 rgb/1311867279.885430.png 1311867279.880883 depth/1311867279.880883.png +1311867279.917304 rgb/1311867279.917304.png 1311867279.908818 depth/1311867279.908818.png +1311867279.952401 rgb/1311867279.952401.png 1311867279.944041 depth/1311867279.944041.png +1311867279.985229 rgb/1311867279.985229.png 1311867279.979519 depth/1311867279.979519.png +1311867280.018481 rgb/1311867280.018481.png 1311867280.011379 depth/1311867280.011379.png +1311867280.049281 rgb/1311867280.049281.png 1311867280.040186 depth/1311867280.040186.png +1311867280.085300 rgb/1311867280.085300.png 1311867280.078508 depth/1311867280.078508.png +1311867280.117762 rgb/1311867280.117762.png 1311867280.111193 depth/1311867280.111193.png +1311867280.149143 rgb/1311867280.149143.png 1311867280.145007 depth/1311867280.145007.png +1311867280.185202 rgb/1311867280.185202.png 1311867280.175310 depth/1311867280.175310.png +1311867280.218467 rgb/1311867280.218467.png 1311867280.212334 depth/1311867280.212334.png +1311867280.249139 rgb/1311867280.249139.png 1311867280.242286 depth/1311867280.242286.png +1311867280.285235 rgb/1311867280.285235.png 1311867280.279458 depth/1311867280.279458.png +1311867280.317120 rgb/1311867280.317120.png 1311867280.311473 depth/1311867280.311473.png +1311867280.349364 rgb/1311867280.349364.png 1311867280.344508 depth/1311867280.344508.png +1311867280.384986 rgb/1311867280.384986.png 1311867280.375534 depth/1311867280.375534.png +1311867280.417089 rgb/1311867280.417089.png 1311867280.407190 depth/1311867280.407190.png +1311867280.449359 rgb/1311867280.449359.png 1311867280.442411 depth/1311867280.442411.png +1311867280.485243 rgb/1311867280.485243.png 1311867280.478287 depth/1311867280.478287.png +1311867280.517164 rgb/1311867280.517164.png 1311867280.509126 depth/1311867280.509126.png +1311867280.549209 rgb/1311867280.549209.png 1311867280.545599 depth/1311867280.545599.png +1311867280.585098 rgb/1311867280.585098.png 1311867280.578208 depth/1311867280.578208.png +1311867280.619113 rgb/1311867280.619113.png 1311867280.613050 depth/1311867280.613050.png +1311867280.649186 rgb/1311867280.649186.png 1311867280.642274 depth/1311867280.642274.png +1311867280.685076 rgb/1311867280.685076.png 1311867280.675529 depth/1311867280.675529.png +1311867280.717291 rgb/1311867280.717291.png 1311867280.709488 depth/1311867280.709488.png +1311867280.749156 rgb/1311867280.749156.png 1311867280.741181 depth/1311867280.741181.png +1311867280.785051 rgb/1311867280.785051.png 1311867280.775267 depth/1311867280.775267.png +1311867280.817244 rgb/1311867280.817244.png 1311867280.807625 depth/1311867280.807625.png +1311867280.849336 rgb/1311867280.849336.png 1311867280.840101 depth/1311867280.840101.png +1311867280.885032 rgb/1311867280.885032.png 1311867280.875484 depth/1311867280.875484.png +1311867280.917146 rgb/1311867280.917146.png 1311867280.907911 depth/1311867280.907911.png +1311867280.949429 rgb/1311867280.949429.png 1311867280.939453 depth/1311867280.939453.png +1311867280.985057 rgb/1311867280.985057.png 1311867280.976699 depth/1311867280.976699.png +1311867281.017255 rgb/1311867281.017255.png 1311867281.007519 depth/1311867281.007519.png +1311867281.049159 rgb/1311867281.049159.png 1311867281.043343 depth/1311867281.043343.png +1311867281.085147 rgb/1311867281.085147.png 1311867281.075278 depth/1311867281.075278.png +1311867281.117112 rgb/1311867281.117112.png 1311867281.107490 depth/1311867281.107490.png +1311867281.149430 rgb/1311867281.149430.png 1311867281.145152 depth/1311867281.145152.png +1311867281.185052 rgb/1311867281.185052.png 1311867281.178669 depth/1311867281.178669.png +1311867281.217252 rgb/1311867281.217252.png 1311867281.208330 depth/1311867281.208330.png +1311867281.250106 rgb/1311867281.250106.png 1311867281.245795 depth/1311867281.245795.png +1311867281.285102 rgb/1311867281.285102.png 1311867281.275440 depth/1311867281.275440.png +1311867281.317215 rgb/1311867281.317215.png 1311867281.307299 depth/1311867281.307299.png +1311867281.349217 rgb/1311867281.349217.png 1311867281.346510 depth/1311867281.346510.png +1311867281.385101 rgb/1311867281.385101.png 1311867281.375153 depth/1311867281.375153.png +1311867281.417074 rgb/1311867281.417074.png 1311867281.408070 depth/1311867281.408070.png +1311867281.449183 rgb/1311867281.449183.png 1311867281.443411 depth/1311867281.443411.png +1311867281.485107 rgb/1311867281.485107.png 1311867281.475372 depth/1311867281.475372.png +1311867281.517167 rgb/1311867281.517167.png 1311867281.510197 depth/1311867281.510197.png +1311867281.549207 rgb/1311867281.549207.png 1311867281.543566 depth/1311867281.543566.png +1311867281.585193 rgb/1311867281.585193.png 1311867281.575475 depth/1311867281.575475.png +1311867281.617286 rgb/1311867281.617286.png 1311867281.611119 depth/1311867281.611119.png +1311867281.649274 rgb/1311867281.649274.png 1311867281.643561 depth/1311867281.643561.png +1311867281.685142 rgb/1311867281.685142.png 1311867281.675512 depth/1311867281.675512.png +1311867281.717170 rgb/1311867281.717170.png 1311867281.708919 depth/1311867281.708919.png +1311867281.749309 rgb/1311867281.749309.png 1311867281.745224 depth/1311867281.745224.png +1311867281.785115 rgb/1311867281.785115.png 1311867281.775529 depth/1311867281.775529.png +1311867281.817105 rgb/1311867281.817105.png 1311867281.807558 depth/1311867281.807558.png +1311867281.849170 rgb/1311867281.849170.png 1311867281.844782 depth/1311867281.844782.png +1311867281.885079 rgb/1311867281.885079.png 1311867281.875666 depth/1311867281.875666.png +1311867281.917153 rgb/1311867281.917153.png 1311867281.907723 depth/1311867281.907723.png +1311867281.949198 rgb/1311867281.949198.png 1311867281.944487 depth/1311867281.944487.png +1311867281.985074 rgb/1311867281.985074.png 1311867281.978540 depth/1311867281.978540.png +1311867282.017320 rgb/1311867282.017320.png 1311867282.009812 depth/1311867282.009812.png +1311867282.049154 rgb/1311867282.049154.png 1311867282.043680 depth/1311867282.043680.png +1311867282.085212 rgb/1311867282.085212.png 1311867282.075547 depth/1311867282.075547.png +1311867282.117596 rgb/1311867282.117596.png 1311867282.107791 depth/1311867282.107791.png +1311867282.154864 rgb/1311867282.154864.png 1311867282.146414 depth/1311867282.146414.png +1311867282.188493 rgb/1311867282.188493.png 1311867282.179748 depth/1311867282.179748.png +1311867282.219908 rgb/1311867282.219908.png 1311867282.213633 depth/1311867282.213633.png +1311867282.253156 rgb/1311867282.253156.png 1311867282.245317 depth/1311867282.245317.png +1311867282.288070 rgb/1311867282.288070.png 1311867282.284410 depth/1311867282.284410.png +1311867282.322429 rgb/1311867282.322429.png 1311867282.318730 depth/1311867282.318730.png +1311867282.350083 rgb/1311867282.350083.png 1311867282.344555 depth/1311867282.344555.png +1311867282.390746 rgb/1311867282.390746.png 1311867282.383713 depth/1311867282.383713.png +1311867282.417372 rgb/1311867282.417372.png 1311867282.411485 depth/1311867282.411485.png +1311867282.449215 rgb/1311867282.449215.png 1311867282.443704 depth/1311867282.443704.png +1311867282.485251 rgb/1311867282.485251.png 1311867282.475457 depth/1311867282.475457.png +1311867282.517375 rgb/1311867282.517375.png 1311867282.512856 depth/1311867282.512856.png +1311867282.549242 rgb/1311867282.549242.png 1311867282.543540 depth/1311867282.543540.png +1311867282.585190 rgb/1311867282.585190.png 1311867282.575564 depth/1311867282.575564.png +1311867282.617188 rgb/1311867282.617188.png 1311867282.611290 depth/1311867282.611290.png +1311867282.649230 rgb/1311867282.649230.png 1311867282.643726 depth/1311867282.643726.png +1311867282.685172 rgb/1311867282.685172.png 1311867282.676659 depth/1311867282.676659.png +1311867282.717391 rgb/1311867282.717391.png 1311867282.714725 depth/1311867282.714725.png +1311867282.749855 rgb/1311867282.749855.png 1311867282.746252 depth/1311867282.746252.png +1311867282.785198 rgb/1311867282.785198.png 1311867282.775429 depth/1311867282.775429.png +1311867282.817434 rgb/1311867282.817434.png 1311867282.811635 depth/1311867282.811635.png +1311867282.849193 rgb/1311867282.849193.png 1311867282.847537 depth/1311867282.847537.png +1311867282.885734 rgb/1311867282.885734.png 1311867282.875791 depth/1311867282.875791.png +1311867282.917314 rgb/1311867282.917314.png 1311867282.911463 depth/1311867282.911463.png +1311867282.950235 rgb/1311867282.950235.png 1311867282.945648 depth/1311867282.945648.png +1311867282.985476 rgb/1311867282.985476.png 1311867282.981189 depth/1311867282.981189.png +1311867283.017555 rgb/1311867283.017555.png 1311867283.011488 depth/1311867283.011488.png +1311867283.049392 rgb/1311867283.049392.png 1311867283.046246 depth/1311867283.046246.png +1311867283.085258 rgb/1311867283.085258.png 1311867283.075293 depth/1311867283.075293.png +1311867283.117441 rgb/1311867283.117441.png 1311867283.111688 depth/1311867283.111688.png +1311867283.149532 rgb/1311867283.149532.png 1311867283.143551 depth/1311867283.143551.png +1311867283.185409 rgb/1311867283.185409.png 1311867283.178822 depth/1311867283.178822.png +1311867283.217286 rgb/1311867283.217286.png 1311867283.215827 depth/1311867283.215827.png +1311867283.249357 rgb/1311867283.249357.png 1311867283.244175 depth/1311867283.244175.png +1311867283.285375 rgb/1311867283.285375.png 1311867283.277684 depth/1311867283.277684.png +1311867283.317623 rgb/1311867283.317623.png 1311867283.313466 depth/1311867283.313466.png +1311867283.349796 rgb/1311867283.349796.png 1311867283.349803 depth/1311867283.349803.png +1311867283.385222 rgb/1311867283.385222.png 1311867283.378247 depth/1311867283.378247.png +1311867283.417308 rgb/1311867283.417308.png 1311867283.411527 depth/1311867283.411527.png +1311867283.449265 rgb/1311867283.449265.png 1311867283.446462 depth/1311867283.446462.png +1311867283.485337 rgb/1311867283.485337.png 1311867283.483432 depth/1311867283.483432.png +1311867283.517216 rgb/1311867283.517216.png 1311867283.515474 depth/1311867283.515474.png +1311867283.549561 rgb/1311867283.549561.png 1311867283.543357 depth/1311867283.543357.png +1311867283.585388 rgb/1311867283.585388.png 1311867283.580230 depth/1311867283.580230.png +1311867283.617318 rgb/1311867283.617318.png 1311867283.611350 depth/1311867283.611350.png +1311867283.649382 rgb/1311867283.649382.png 1311867283.643515 depth/1311867283.643515.png +1311867283.685288 rgb/1311867283.685288.png 1311867283.682435 depth/1311867283.682435.png +1311867283.717915 rgb/1311867283.717915.png 1311867283.712030 depth/1311867283.712030.png +1311867283.749208 rgb/1311867283.749208.png 1311867283.747805 depth/1311867283.747805.png +1311867283.785317 rgb/1311867283.785317.png 1311867283.781469 depth/1311867283.781469.png +1311867283.817413 rgb/1311867283.817413.png 1311867283.811886 depth/1311867283.811886.png +1311867283.849452 rgb/1311867283.849452.png 1311867283.844653 depth/1311867283.844653.png +1311867283.885346 rgb/1311867283.885346.png 1311867283.882707 depth/1311867283.882707.png +1311867283.917540 rgb/1311867283.917540.png 1311867283.916866 depth/1311867283.916866.png +1311867283.949890 rgb/1311867283.949890.png 1311867283.945388 depth/1311867283.945388.png +1311867283.985663 rgb/1311867283.985663.png 1311867283.983650 depth/1311867283.983650.png +1311867284.017300 rgb/1311867284.017300.png 1311867284.015752 depth/1311867284.015752.png +1311867284.049779 rgb/1311867284.049779.png 1311867284.043327 depth/1311867284.043327.png +1311867284.085373 rgb/1311867284.085373.png 1311867284.082619 depth/1311867284.082619.png +1311867284.117504 rgb/1311867284.117504.png 1311867284.111840 depth/1311867284.111840.png +1311867284.149411 rgb/1311867284.149411.png 1311867284.145447 depth/1311867284.145447.png +1311867284.187489 rgb/1311867284.187489.png 1311867284.182905 depth/1311867284.182905.png +1311867284.217337 rgb/1311867284.217337.png 1311867284.213992 depth/1311867284.213992.png +1311867284.249431 rgb/1311867284.249431.png 1311867284.245100 depth/1311867284.245100.png +1311867284.285316 rgb/1311867284.285316.png 1311867284.282897 depth/1311867284.282897.png +1311867284.317835 rgb/1311867284.317835.png 1311867284.312841 depth/1311867284.312841.png +1311867284.349424 rgb/1311867284.349424.png 1311867284.343838 depth/1311867284.343838.png +1311867284.385433 rgb/1311867284.385433.png 1311867284.379601 depth/1311867284.379601.png +1311867284.417580 rgb/1311867284.417580.png 1311867284.416106 depth/1311867284.416106.png +1311867284.449514 rgb/1311867284.449514.png 1311867284.443699 depth/1311867284.443699.png +1311867284.485419 rgb/1311867284.485419.png 1311867284.482748 depth/1311867284.482748.png +1311867284.517730 rgb/1311867284.517730.png 1311867284.514261 depth/1311867284.514261.png +1311867284.549454 rgb/1311867284.549454.png 1311867284.544207 depth/1311867284.544207.png +1311867284.585418 rgb/1311867284.585418.png 1311867284.582664 depth/1311867284.582664.png +1311867284.617494 rgb/1311867284.617494.png 1311867284.612546 depth/1311867284.612546.png +1311867284.649523 rgb/1311867284.649523.png 1311867284.643869 depth/1311867284.643869.png +1311867284.685378 rgb/1311867284.685378.png 1311867284.679455 depth/1311867284.679455.png +1311867284.717486 rgb/1311867284.717486.png 1311867284.714820 depth/1311867284.714820.png +1311867284.749751 rgb/1311867284.749751.png 1311867284.749866 depth/1311867284.749866.png +1311867284.785409 rgb/1311867284.785409.png 1311867284.783227 depth/1311867284.783227.png +1311867284.818692 rgb/1311867284.818692.png 1311867284.813016 depth/1311867284.813016.png +1311867284.849277 rgb/1311867284.849277.png 1311867284.847988 depth/1311867284.847988.png +1311867284.885385 rgb/1311867284.885385.png 1311867284.882004 depth/1311867284.882004.png +1311867284.917461 rgb/1311867284.917461.png 1311867284.913002 depth/1311867284.913002.png +1311867284.949247 rgb/1311867284.949247.png 1311867284.948813 depth/1311867284.948813.png +1311867284.985258 rgb/1311867284.985258.png 1311867284.981655 depth/1311867284.981655.png +1311867285.017539 rgb/1311867285.017539.png 1311867285.011727 depth/1311867285.011727.png +1311867285.049368 rgb/1311867285.049368.png 1311867285.047501 depth/1311867285.047501.png +1311867285.085326 rgb/1311867285.085326.png 1311867285.082783 depth/1311867285.082783.png +1311867285.117712 rgb/1311867285.117712.png 1311867285.113140 depth/1311867285.113140.png +1311867285.150212 rgb/1311867285.150212.png 1311867285.150275 depth/1311867285.150275.png +1311867285.185580 rgb/1311867285.185580.png 1311867285.180224 depth/1311867285.180224.png +1311867285.218761 rgb/1311867285.218761.png 1311867285.212983 depth/1311867285.212983.png +1311867285.249366 rgb/1311867285.249366.png 1311867285.248852 depth/1311867285.248852.png +1311867285.285362 rgb/1311867285.285362.png 1311867285.282035 depth/1311867285.282035.png +1311867285.317503 rgb/1311867285.317503.png 1311867285.311875 depth/1311867285.311875.png +1311867285.349345 rgb/1311867285.349345.png 1311867285.349228 depth/1311867285.349228.png +1311867285.385541 rgb/1311867285.385541.png 1311867285.380239 depth/1311867285.380239.png +1311867285.417581 rgb/1311867285.417581.png 1311867285.411467 depth/1311867285.411467.png +1311867285.449284 rgb/1311867285.449284.png 1311867285.448322 depth/1311867285.448322.png +1311867285.485380 rgb/1311867285.485380.png 1311867285.479973 depth/1311867285.479973.png +1311867285.517648 rgb/1311867285.517648.png 1311867285.512012 depth/1311867285.512012.png +1311867285.549451 rgb/1311867285.549451.png 1311867285.549459 depth/1311867285.549459.png +1311867285.585574 rgb/1311867285.585574.png 1311867285.580140 depth/1311867285.580140.png +1311867285.617551 rgb/1311867285.617551.png 1311867285.612426 depth/1311867285.612426.png +1311867285.649403 rgb/1311867285.649403.png 1311867285.648790 depth/1311867285.648790.png +1311867285.685653 rgb/1311867285.685653.png 1311867285.680842 depth/1311867285.680842.png +1311867285.717719 rgb/1311867285.717719.png 1311867285.713476 depth/1311867285.713476.png +1311867285.749708 rgb/1311867285.749708.png 1311867285.749738 depth/1311867285.749738.png +1311867285.785478 rgb/1311867285.785478.png 1311867285.779481 depth/1311867285.779481.png +1311867285.817971 rgb/1311867285.817971.png 1311867285.814467 depth/1311867285.814467.png +1311867285.849628 rgb/1311867285.849628.png 1311867285.849623 depth/1311867285.849623.png +1311867285.885286 rgb/1311867285.885286.png 1311867285.879509 depth/1311867285.879509.png +1311867285.918737 rgb/1311867285.918737.png 1311867285.911572 depth/1311867285.911572.png +1311867285.949513 rgb/1311867285.949513.png 1311867285.949693 depth/1311867285.949693.png +1311867285.985836 rgb/1311867285.985836.png 1311867285.980474 depth/1311867285.980474.png +1311867286.018456 rgb/1311867286.018456.png 1311867286.018470 depth/1311867286.018470.png +1311867286.049422 rgb/1311867286.049422.png 1311867286.047399 depth/1311867286.047399.png +1311867286.085402 rgb/1311867286.085402.png 1311867286.079452 depth/1311867286.079452.png +1311867286.124098 rgb/1311867286.124098.png 1311867286.115849 depth/1311867286.115849.png +1311867286.150632 rgb/1311867286.150632.png 1311867286.149347 depth/1311867286.149347.png +1311867286.185759 rgb/1311867286.185759.png 1311867286.179991 depth/1311867286.179991.png +1311867286.217983 rgb/1311867286.217983.png 1311867286.216056 depth/1311867286.216056.png +1311867286.252521 rgb/1311867286.252521.png 1311867286.251559 depth/1311867286.251559.png +1311867286.286163 rgb/1311867286.286163.png 1311867286.283292 depth/1311867286.283292.png +1311867286.320349 rgb/1311867286.320349.png 1311867286.320352 depth/1311867286.320352.png +1311867286.352378 rgb/1311867286.352378.png 1311867286.352432 depth/1311867286.352432.png +1311867286.385563 rgb/1311867286.385563.png 1311867286.384776 depth/1311867286.384776.png +1311867286.417777 rgb/1311867286.417777.png 1311867286.415744 depth/1311867286.415744.png +1311867286.449420 rgb/1311867286.449420.png 1311867286.447630 depth/1311867286.447630.png +1311867286.485571 rgb/1311867286.485571.png 1311867286.479573 depth/1311867286.479573.png +1311867286.519022 rgb/1311867286.519022.png 1311867286.519037 depth/1311867286.519037.png +1311867286.551199 rgb/1311867286.551199.png 1311867286.551216 depth/1311867286.551216.png +1311867286.585520 rgb/1311867286.585520.png 1311867286.583881 depth/1311867286.583881.png +1311867286.619073 rgb/1311867286.619073.png 1311867286.619082 depth/1311867286.619082.png +1311867286.649991 rgb/1311867286.649991.png 1311867286.650006 depth/1311867286.650006.png +1311867286.685643 rgb/1311867286.685643.png 1311867286.679768 depth/1311867286.679768.png +1311867286.717616 rgb/1311867286.717616.png 1311867286.715446 depth/1311867286.715446.png +1311867286.749549 rgb/1311867286.749549.png 1311867286.747761 depth/1311867286.747761.png +1311867286.785646 rgb/1311867286.785646.png 1311867286.780410 depth/1311867286.780410.png +1311867286.817626 rgb/1311867286.817626.png 1311867286.815445 depth/1311867286.815445.png +1311867286.853582 rgb/1311867286.853582.png 1311867286.849774 depth/1311867286.849774.png +1311867286.886815 rgb/1311867286.886815.png 1311867286.879639 depth/1311867286.879639.png +1311867286.917438 rgb/1311867286.917438.png 1311867286.916996 depth/1311867286.916996.png +1311867286.954361 rgb/1311867286.954361.png 1311867286.947955 depth/1311867286.947955.png +1311867286.985412 rgb/1311867286.985412.png 1311867286.984719 depth/1311867286.984719.png +1311867287.017431 rgb/1311867287.017431.png 1311867287.016126 depth/1311867287.016126.png +1311867287.054702 rgb/1311867287.054702.png 1311867287.047992 depth/1311867287.047992.png +1311867287.085686 rgb/1311867287.085686.png 1311867287.080476 depth/1311867287.080476.png +1311867287.117817 rgb/1311867287.117817.png 1311867287.117822 depth/1311867287.117822.png +1311867287.153705 rgb/1311867287.153705.png 1311867287.149599 depth/1311867287.149599.png +1311867287.187445 rgb/1311867287.187445.png 1311867287.184349 depth/1311867287.184349.png +1311867287.217558 rgb/1311867287.217558.png 1311867287.215525 depth/1311867287.215525.png +1311867287.253668 rgb/1311867287.253668.png 1311867287.247482 depth/1311867287.247482.png +1311867287.287011 rgb/1311867287.287011.png 1311867287.287022 depth/1311867287.287022.png +1311867287.317563 rgb/1311867287.317563.png 1311867287.315527 depth/1311867287.315527.png +1311867287.354094 rgb/1311867287.354094.png 1311867287.349484 depth/1311867287.349484.png +1311867287.385542 rgb/1311867287.385542.png 1311867287.385554 depth/1311867287.385554.png +1311867287.417576 rgb/1311867287.417576.png 1311867287.416759 depth/1311867287.416759.png +1311867287.453529 rgb/1311867287.453529.png 1311867287.447562 depth/1311867287.447562.png +1311867287.486720 rgb/1311867287.486720.png 1311867287.486731 depth/1311867287.486731.png +1311867287.517500 rgb/1311867287.517500.png 1311867287.515489 depth/1311867287.515489.png +1311867287.553487 rgb/1311867287.553487.png 1311867287.550817 depth/1311867287.550817.png +1311867287.586854 rgb/1311867287.586854.png 1311867287.586952 depth/1311867287.586952.png +1311867287.617657 rgb/1311867287.617657.png 1311867287.617309 depth/1311867287.617309.png +1311867287.653916 rgb/1311867287.653916.png 1311867287.647862 depth/1311867287.647862.png +1311867287.687566 rgb/1311867287.687566.png 1311867287.684357 depth/1311867287.684357.png +1311867287.717628 rgb/1311867287.717628.png 1311867287.717048 depth/1311867287.717048.png +1311867287.755391 rgb/1311867287.755391.png 1311867287.749794 depth/1311867287.749794.png +1311867287.787243 rgb/1311867287.787243.png 1311867287.785349 depth/1311867287.785349.png +1311867287.826010 rgb/1311867287.826010.png 1311867287.818614 depth/1311867287.818614.png +1311867287.853651 rgb/1311867287.853651.png 1311867287.850417 depth/1311867287.850417.png +1311867287.893111 rgb/1311867287.893111.png 1311867287.884625 depth/1311867287.884625.png +1311867287.917571 rgb/1311867287.917571.png 1311867287.917157 depth/1311867287.917157.png +1311867287.953561 rgb/1311867287.953561.png 1311867287.948611 depth/1311867287.948611.png +1311867287.986839 rgb/1311867287.986839.png 1311867287.986852 depth/1311867287.986852.png +1311867288.017882 rgb/1311867288.017882.png 1311867288.016660 depth/1311867288.016660.png +1311867288.053639 rgb/1311867288.053639.png 1311867288.048741 depth/1311867288.048741.png +1311867288.085418 rgb/1311867288.085418.png 1311867288.084402 depth/1311867288.084402.png +1311867288.117594 rgb/1311867288.117594.png 1311867288.116353 depth/1311867288.116353.png +1311867288.154082 rgb/1311867288.154082.png 1311867288.148478 depth/1311867288.148478.png +1311867288.185455 rgb/1311867288.185455.png 1311867288.184693 depth/1311867288.184693.png +1311867288.217534 rgb/1311867288.217534.png 1311867288.217329 depth/1311867288.217329.png +1311867288.253581 rgb/1311867288.253581.png 1311867288.249817 depth/1311867288.249817.png +1311867288.285472 rgb/1311867288.285472.png 1311867288.284842 depth/1311867288.284842.png +1311867288.317583 rgb/1311867288.317583.png 1311867288.315892 depth/1311867288.315892.png +1311867288.353521 rgb/1311867288.353521.png 1311867288.349200 depth/1311867288.349200.png +1311867288.385883 rgb/1311867288.385883.png 1311867288.385889 depth/1311867288.385889.png +1311867288.417761 rgb/1311867288.417761.png 1311867288.416471 depth/1311867288.416471.png +1311867288.456019 rgb/1311867288.456019.png 1311867288.456030 depth/1311867288.456030.png +1311867288.485465 rgb/1311867288.485465.png 1311867288.483975 depth/1311867288.483975.png +1311867288.517689 rgb/1311867288.517689.png 1311867288.515938 depth/1311867288.515938.png +1311867288.554472 rgb/1311867288.554472.png 1311867288.554493 depth/1311867288.554493.png +1311867288.586600 rgb/1311867288.586600.png 1311867288.587434 depth/1311867288.587434.png +1311867288.617541 rgb/1311867288.617541.png 1311867288.617059 depth/1311867288.617059.png +1311867288.655102 rgb/1311867288.655102.png 1311867288.655120 depth/1311867288.655120.png +1311867288.687379 rgb/1311867288.687379.png 1311867288.687411 depth/1311867288.687411.png +1311867288.717702 rgb/1311867288.717702.png 1311867288.717718 depth/1311867288.717718.png +1311867288.756022 rgb/1311867288.756022.png 1311867288.756066 depth/1311867288.756066.png +1311867288.785509 rgb/1311867288.785509.png 1311867288.784216 depth/1311867288.784216.png +1311867288.819223 rgb/1311867288.819223.png 1311867288.819240 depth/1311867288.819240.png +1311867288.854331 rgb/1311867288.854331.png 1311867288.854345 depth/1311867288.854345.png +1311867288.885556 rgb/1311867288.885556.png 1311867288.883768 depth/1311867288.883768.png +1311867288.917612 rgb/1311867288.917612.png 1311867288.915649 depth/1311867288.915649.png +1311867288.954939 rgb/1311867288.954939.png 1311867288.959948 depth/1311867288.959948.png +1311867288.985592 rgb/1311867288.985592.png 1311867288.984724 depth/1311867288.984724.png +1311867289.017656 rgb/1311867289.017656.png 1311867289.015746 depth/1311867289.015746.png +1311867289.053512 rgb/1311867289.053512.png 1311867289.051995 depth/1311867289.051995.png +1311867289.085511 rgb/1311867289.085511.png 1311867289.084565 depth/1311867289.084565.png +1311867289.117543 rgb/1311867289.117543.png 1311867289.116004 depth/1311867289.116004.png +1311867289.154583 rgb/1311867289.154583.png 1311867289.154593 depth/1311867289.154593.png +1311867289.185640 rgb/1311867289.185640.png 1311867289.184904 depth/1311867289.184904.png +1311867289.218482 rgb/1311867289.218482.png 1311867289.218506 depth/1311867289.218506.png +1311867289.255039 rgb/1311867289.255039.png 1311867289.255048 depth/1311867289.255048.png +1311867289.285387 rgb/1311867289.285387.png 1311867289.284501 depth/1311867289.284501.png +1311867289.317629 rgb/1311867289.317629.png 1311867289.315842 depth/1311867289.315842.png +1311867289.353909 rgb/1311867289.353909.png 1311867289.353917 depth/1311867289.353917.png +1311867289.386185 rgb/1311867289.386185.png 1311867289.386190 depth/1311867289.386190.png +1311867289.417704 rgb/1311867289.417704.png 1311867289.415781 depth/1311867289.415781.png +1311867289.453606 rgb/1311867289.453606.png 1311867289.452549 depth/1311867289.452549.png +1311867289.485961 rgb/1311867289.485961.png 1311867289.485967 depth/1311867289.485967.png +1311867289.518318 rgb/1311867289.518318.png 1311867289.518324 depth/1311867289.518324.png +1311867289.554869 rgb/1311867289.554869.png 1311867289.554882 depth/1311867289.554882.png +1311867289.585613 rgb/1311867289.585613.png 1311867289.584817 depth/1311867289.584817.png +1311867289.617649 rgb/1311867289.617649.png 1311867289.615707 depth/1311867289.615707.png +1311867289.653639 rgb/1311867289.653639.png 1311867289.651631 depth/1311867289.651631.png +1311867289.685685 rgb/1311867289.685685.png 1311867289.683686 depth/1311867289.683686.png +1311867289.720426 rgb/1311867289.720426.png 1311867289.720435 depth/1311867289.720435.png +1311867289.756408 rgb/1311867289.756408.png 1311867289.756418 depth/1311867289.756418.png +1311867289.785568 rgb/1311867289.785568.png 1311867289.783898 depth/1311867289.783898.png +1311867289.824026 rgb/1311867289.824026.png 1311867289.824037 depth/1311867289.824037.png +1311867289.854176 rgb/1311867289.854176.png 1311867289.854187 depth/1311867289.854187.png +1311867289.885568 rgb/1311867289.885568.png 1311867289.884044 depth/1311867289.884044.png +1311867289.920046 rgb/1311867289.920046.png 1311867289.920053 depth/1311867289.920053.png +1311867289.953641 rgb/1311867289.953641.png 1311867289.952577 depth/1311867289.952577.png +1311867289.985528 rgb/1311867289.985528.png 1311867289.984236 depth/1311867289.984236.png +1311867290.020153 rgb/1311867290.020153.png 1311867290.023217 depth/1311867290.023217.png +1311867290.053575 rgb/1311867290.053575.png 1311867290.053591 depth/1311867290.053591.png +1311867290.085474 rgb/1311867290.085474.png 1311867290.083953 depth/1311867290.083953.png +1311867290.124880 rgb/1311867290.124880.png 1311867290.121521 depth/1311867290.121521.png +1311867290.153612 rgb/1311867290.153612.png 1311867290.153221 depth/1311867290.153221.png +1311867290.185638 rgb/1311867290.185638.png 1311867290.184926 depth/1311867290.184926.png +1311867290.222529 rgb/1311867290.222529.png 1311867290.222549 depth/1311867290.222549.png +1311867290.254027 rgb/1311867290.254027.png 1311867290.254032 depth/1311867290.254032.png +1311867290.286994 rgb/1311867290.286994.png 1311867290.289238 depth/1311867290.289238.png +1311867290.322046 rgb/1311867290.322046.png 1311867290.322075 depth/1311867290.322075.png +1311867290.354777 rgb/1311867290.354777.png 1311867290.358779 depth/1311867290.358779.png +1311867290.386415 rgb/1311867290.386415.png 1311867290.386424 depth/1311867290.386424.png +1311867290.421620 rgb/1311867290.421620.png 1311867290.421632 depth/1311867290.421632.png +1311867290.457663 rgb/1311867290.457663.png 1311867290.457839 depth/1311867290.457839.png +1311867290.485984 rgb/1311867290.485984.png 1311867290.485995 depth/1311867290.485995.png +1311867290.522328 rgb/1311867290.522328.png 1311867290.522340 depth/1311867290.522340.png +1311867290.553706 rgb/1311867290.553706.png 1311867290.553428 depth/1311867290.553428.png +1311867290.585554 rgb/1311867290.585554.png 1311867290.585047 depth/1311867290.585047.png +1311867290.620155 rgb/1311867290.620155.png 1311867290.622102 depth/1311867290.622102.png +1311867290.653602 rgb/1311867290.653602.png 1311867290.652320 depth/1311867290.652320.png +1311867290.685718 rgb/1311867290.685718.png 1311867290.685753 depth/1311867290.685753.png +1311867290.725606 rgb/1311867290.725606.png 1311867290.725615 depth/1311867290.725615.png +1311867290.753974 rgb/1311867290.753974.png 1311867290.752306 depth/1311867290.752306.png +1311867290.786574 rgb/1311867290.786574.png 1311867290.786606 depth/1311867290.786606.png +1311867290.823128 rgb/1311867290.823128.png 1311867290.823172 depth/1311867290.823172.png +1311867290.855586 rgb/1311867290.855586.png 1311867290.855604 depth/1311867290.855604.png +1311867290.887678 rgb/1311867290.887678.png 1311867290.887699 depth/1311867290.887699.png +1311867290.922693 rgb/1311867290.922693.png 1311867290.922712 depth/1311867290.922712.png +1311867290.953711 rgb/1311867290.953711.png 1311867290.952067 depth/1311867290.952067.png +1311867290.990676 rgb/1311867290.990676.png 1311867290.990691 depth/1311867290.990691.png +1311867291.023910 rgb/1311867291.023910.png 1311867291.023929 depth/1311867291.023929.png +1311867291.055820 rgb/1311867291.055820.png 1311867291.051871 depth/1311867291.051871.png +1311867291.090338 rgb/1311867291.090338.png 1311867291.093482 depth/1311867291.093482.png +1311867291.120272 rgb/1311867291.120272.png 1311867291.120311 depth/1311867291.120311.png +1311867291.154182 rgb/1311867291.154182.png 1311867291.154189 depth/1311867291.154189.png +1311867291.189179 rgb/1311867291.189179.png 1311867291.189199 depth/1311867291.189199.png +1311867291.221074 rgb/1311867291.221074.png 1311867291.221101 depth/1311867291.221101.png +1311867291.254380 rgb/1311867291.254380.png 1311867291.254391 depth/1311867291.254391.png +1311867291.287791 rgb/1311867291.287791.png 1311867291.287796 depth/1311867291.287796.png +1311867291.321060 rgb/1311867291.321060.png 1311867291.321090 depth/1311867291.321090.png +1311867291.354784 rgb/1311867291.354784.png 1311867291.354796 depth/1311867291.354796.png +1311867291.387834 rgb/1311867291.387834.png 1311867291.387876 depth/1311867291.387876.png +1311867291.422316 rgb/1311867291.422316.png 1311867291.422335 depth/1311867291.422335.png +1311867291.453656 rgb/1311867291.453656.png 1311867291.452372 depth/1311867291.452372.png +1311867291.488381 rgb/1311867291.488381.png 1311867291.488400 depth/1311867291.488400.png +1311867291.520140 rgb/1311867291.520140.png 1311867291.520173 depth/1311867291.520173.png +1311867291.553645 rgb/1311867291.553645.png 1311867291.552383 depth/1311867291.552383.png +1311867291.589498 rgb/1311867291.589498.png 1311867291.589508 depth/1311867291.589508.png +1311867291.620673 rgb/1311867291.620673.png 1311867291.620687 depth/1311867291.620687.png +1311867291.653970 rgb/1311867291.653970.png 1311867291.653978 depth/1311867291.653978.png +1311867291.689647 rgb/1311867291.689647.png 1311867291.689681 depth/1311867291.689681.png +1311867291.720251 rgb/1311867291.720251.png 1311867291.720274 depth/1311867291.720274.png +1311867291.753718 rgb/1311867291.753718.png 1311867291.752562 depth/1311867291.752562.png +1311867291.788985 rgb/1311867291.788985.png 1311867291.789002 depth/1311867291.789002.png +1311867291.821719 rgb/1311867291.821719.png 1311867291.821548 depth/1311867291.821548.png +1311867291.853864 rgb/1311867291.853864.png 1311867291.851921 depth/1311867291.851921.png +1311867291.887943 rgb/1311867291.887943.png 1311867291.887949 depth/1311867291.887949.png +1311867291.920685 rgb/1311867291.920685.png 1311867291.920693 depth/1311867291.920693.png +1311867291.953720 rgb/1311867291.953720.png 1311867291.951900 depth/1311867291.951900.png +1311867291.990091 rgb/1311867291.990091.png 1311867291.990289 depth/1311867291.990289.png +1311867292.022520 rgb/1311867292.022520.png 1311867292.022526 depth/1311867292.022526.png +1311867292.053683 rgb/1311867292.053683.png 1311867292.052577 depth/1311867292.052577.png +1311867292.092254 rgb/1311867292.092254.png 1311867292.092285 depth/1311867292.092285.png +1311867292.124382 rgb/1311867292.124382.png 1311867292.124388 depth/1311867292.124388.png +1311867292.160249 rgb/1311867292.160249.png 1311867292.160265 depth/1311867292.160265.png +1311867292.189973 rgb/1311867292.189973.png 1311867292.189985 depth/1311867292.189985.png +1311867292.220732 rgb/1311867292.220732.png 1311867292.220742 depth/1311867292.220742.png +1311867292.257685 rgb/1311867292.257685.png 1311867292.257691 depth/1311867292.257691.png +1311867292.287816 rgb/1311867292.287816.png 1311867292.287827 depth/1311867292.287827.png +1311867292.321387 rgb/1311867292.321387.png 1311867292.321727 depth/1311867292.321727.png +1311867292.362160 rgb/1311867292.362160.png 1311867292.362171 depth/1311867292.362171.png +1311867292.395350 rgb/1311867292.395350.png 1311867292.395362 depth/1311867292.395362.png +1311867292.425930 rgb/1311867292.425930.png 1311867292.421631 depth/1311867292.421631.png +1311867292.456448 rgb/1311867292.456448.png 1311867292.456521 depth/1311867292.456521.png +1311867292.488351 rgb/1311867292.488351.png 1311867292.488370 depth/1311867292.488370.png +1311867292.522883 rgb/1311867292.522883.png 1311867292.522965 depth/1311867292.522965.png +1311867292.558104 rgb/1311867292.558104.png 1311867292.558115 depth/1311867292.558115.png +1311867292.588222 rgb/1311867292.588222.png 1311867292.588244 depth/1311867292.588244.png +1311867292.623076 rgb/1311867292.623076.png 1311867292.623087 depth/1311867292.623087.png +1311867292.659508 rgb/1311867292.659508.png 1311867292.659521 depth/1311867292.659521.png +1311867292.688015 rgb/1311867292.688015.png 1311867292.688022 depth/1311867292.688022.png +1311867292.720644 rgb/1311867292.720644.png 1311867292.720697 depth/1311867292.720697.png +1311867292.756178 rgb/1311867292.756178.png 1311867292.756188 depth/1311867292.756188.png diff --git a/Examples/RGB-D/associations/fr3_nstr_tex_near.txt b/Examples/RGB-D/associations/fr3_nstr_tex_near.txt new file mode 100644 index 0000000000..a47d7ac019 --- /dev/null +++ b/Examples/RGB-D/associations/fr3_nstr_tex_near.txt @@ -0,0 +1,1639 @@ +1341840083.789974 rgb/1341840083.789974.png 1341840083.790018 depth/1341840083.790018.png +1341840083.821987 rgb/1341840083.821987.png 1341840083.822003 depth/1341840083.822003.png +1341840083.858104 rgb/1341840083.858104.png 1341840083.858138 depth/1341840083.858138.png +1341840083.890155 rgb/1341840083.890155.png 1341840083.890192 depth/1341840083.890192.png +1341840083.926071 rgb/1341840083.926071.png 1341840083.926530 depth/1341840083.926530.png +1341840083.958095 rgb/1341840083.958095.png 1341840083.958118 depth/1341840083.958118.png +1341840083.990000 rgb/1341840083.990000.png 1341840083.990077 depth/1341840083.990077.png +1341840084.026121 rgb/1341840084.026121.png 1341840084.026139 depth/1341840084.026139.png +1341840084.057936 rgb/1341840084.057936.png 1341840084.057949 depth/1341840084.057949.png +1341840084.090022 rgb/1341840084.090022.png 1341840084.090034 depth/1341840084.090034.png +1341840084.126053 rgb/1341840084.126053.png 1341840084.126067 depth/1341840084.126067.png +1341840084.158032 rgb/1341840084.158032.png 1341840084.158058 depth/1341840084.158058.png +1341840084.194127 rgb/1341840084.194127.png 1341840084.194663 depth/1341840084.194663.png +1341840084.226042 rgb/1341840084.226042.png 1341840084.226061 depth/1341840084.226061.png +1341840084.258027 rgb/1341840084.258027.png 1341840084.258043 depth/1341840084.258043.png +1341840084.294117 rgb/1341840084.294117.png 1341840084.294139 depth/1341840084.294139.png +1341840084.325994 rgb/1341840084.325994.png 1341840084.326013 depth/1341840084.326013.png +1341840084.358007 rgb/1341840084.358007.png 1341840084.358030 depth/1341840084.358030.png +1341840084.394092 rgb/1341840084.394092.png 1341840084.394197 depth/1341840084.394197.png +1341840084.425964 rgb/1341840084.425964.png 1341840084.426034 depth/1341840084.426034.png +1341840084.462012 rgb/1341840084.462012.png 1341840084.462028 depth/1341840084.462028.png +1341840084.494007 rgb/1341840084.494007.png 1341840084.494016 depth/1341840084.494016.png +1341840084.525979 rgb/1341840084.525979.png 1341840084.525994 depth/1341840084.525994.png +1341840084.562039 rgb/1341840084.562039.png 1341840084.562045 depth/1341840084.562045.png +1341840084.594095 rgb/1341840084.594095.png 1341840084.594109 depth/1341840084.594109.png +1341840084.626070 rgb/1341840084.626070.png 1341840084.626115 depth/1341840084.626115.png +1341840084.661961 rgb/1341840084.661961.png 1341840084.661999 depth/1341840084.661999.png +1341840084.694181 rgb/1341840084.694181.png 1341840084.694201 depth/1341840084.694201.png +1341840084.729879 rgb/1341840084.729879.png 1341840084.729901 depth/1341840084.729901.png +1341840084.762054 rgb/1341840084.762054.png 1341840084.762071 depth/1341840084.762071.png +1341840084.794567 rgb/1341840084.794567.png 1341840084.794582 depth/1341840084.794582.png +1341840084.829914 rgb/1341840084.829914.png 1341840084.829933 depth/1341840084.829933.png +1341840084.861905 rgb/1341840084.861905.png 1341840084.861922 depth/1341840084.861922.png +1341840084.894025 rgb/1341840084.894025.png 1341840084.894044 depth/1341840084.894044.png +1341840084.929921 rgb/1341840084.929921.png 1341840084.929951 depth/1341840084.929951.png +1341840084.962026 rgb/1341840084.962026.png 1341840084.962051 depth/1341840084.962051.png +1341840084.998375 rgb/1341840084.998375.png 1341840084.998394 depth/1341840084.998394.png +1341840085.030745 rgb/1341840085.030745.png 1341840085.030775 depth/1341840085.030775.png +1341840085.062049 rgb/1341840085.062049.png 1341840085.062066 depth/1341840085.062066.png +1341840085.097991 rgb/1341840085.097991.png 1341840085.098025 depth/1341840085.098025.png +1341840085.130028 rgb/1341840085.130028.png 1341840085.130116 depth/1341840085.130116.png +1341840085.166080 rgb/1341840085.166080.png 1341840085.166127 depth/1341840085.166127.png +1341840085.198124 rgb/1341840085.198124.png 1341840085.198154 depth/1341840085.198154.png +1341840085.230345 rgb/1341840085.230345.png 1341840085.230963 depth/1341840085.230963.png +1341840085.266025 rgb/1341840085.266025.png 1341840085.266044 depth/1341840085.266044.png +1341840085.298250 rgb/1341840085.298250.png 1341840085.298266 depth/1341840085.298266.png +1341840085.330214 rgb/1341840085.330214.png 1341840085.330767 depth/1341840085.330767.png +1341840085.366055 rgb/1341840085.366055.png 1341840085.366076 depth/1341840085.366076.png +1341840085.398022 rgb/1341840085.398022.png 1341840085.398050 depth/1341840085.398050.png +1341840085.433967 rgb/1341840085.433967.png 1341840085.433975 depth/1341840085.433975.png +1341840085.465998 rgb/1341840085.465998.png 1341840085.466036 depth/1341840085.466036.png +1341840085.498029 rgb/1341840085.498029.png 1341840085.498043 depth/1341840085.498043.png +1341840085.533945 rgb/1341840085.533945.png 1341840085.533966 depth/1341840085.533966.png +1341840085.598078 rgb/1341840085.598078.png 1341840085.598105 depth/1341840085.598105.png +1341840085.634035 rgb/1341840085.634035.png 1341840085.634047 depth/1341840085.634047.png +1341840085.666062 rgb/1341840085.666062.png 1341840085.666093 depth/1341840085.666093.png +1341840085.701946 rgb/1341840085.701946.png 1341840085.701981 depth/1341840085.701981.png +1341840085.734314 rgb/1341840085.734314.png 1341840085.734325 depth/1341840085.734325.png +1341840085.773194 rgb/1341840085.773194.png 1341840085.773226 depth/1341840085.773226.png +1341840085.805306 rgb/1341840085.805306.png 1341840085.805955 depth/1341840085.805955.png +1341840085.840976 rgb/1341840085.840976.png 1341840085.840995 depth/1341840085.840995.png +1341840085.873132 rgb/1341840085.873132.png 1341840085.873154 depth/1341840085.873154.png +1341840085.904912 rgb/1341840085.904912.png 1341840085.905360 depth/1341840085.905360.png +1341840085.940930 rgb/1341840085.940930.png 1341840085.940965 depth/1341840085.940965.png +1341840085.972968 rgb/1341840085.972968.png 1341840085.972992 depth/1341840085.972992.png +1341840086.009063 rgb/1341840086.009063.png 1341840086.009089 depth/1341840086.009089.png +1341840086.040942 rgb/1341840086.040942.png 1341840086.040951 depth/1341840086.040951.png +1341840086.073092 rgb/1341840086.073092.png 1341840086.073107 depth/1341840086.073107.png +1341840086.109086 rgb/1341840086.109086.png 1341840086.109111 depth/1341840086.109111.png +1341840086.141084 rgb/1341840086.141084.png 1341840086.141513 depth/1341840086.141513.png +1341840086.177243 rgb/1341840086.177243.png 1341840086.177256 depth/1341840086.177256.png +1341840086.209221 rgb/1341840086.209221.png 1341840086.209241 depth/1341840086.209241.png +1341840086.240929 rgb/1341840086.240929.png 1341840086.240954 depth/1341840086.240954.png +1341840086.277032 rgb/1341840086.277032.png 1341840086.277050 depth/1341840086.277050.png +1341840086.308978 rgb/1341840086.308978.png 1341840086.309003 depth/1341840086.309003.png +1341840086.345100 rgb/1341840086.345100.png 1341840086.345116 depth/1341840086.345116.png +1341840086.377020 rgb/1341840086.377020.png 1341840086.377543 depth/1341840086.377543.png +1341840086.408991 rgb/1341840086.408991.png 1341840086.409007 depth/1341840086.409007.png +1341840086.445193 rgb/1341840086.445193.png 1341840086.445224 depth/1341840086.445224.png +1341840086.476977 rgb/1341840086.476977.png 1341840086.476991 depth/1341840086.476991.png +1341840086.512947 rgb/1341840086.512947.png 1341840086.513525 depth/1341840086.513525.png +1341840086.545033 rgb/1341840086.545033.png 1341840086.545042 depth/1341840086.545042.png +1341840086.577127 rgb/1341840086.577127.png 1341840086.577145 depth/1341840086.577145.png +1341840086.612988 rgb/1341840086.612988.png 1341840086.613003 depth/1341840086.613003.png +1341840086.645038 rgb/1341840086.645038.png 1341840086.645050 depth/1341840086.645050.png +1341840086.680940 rgb/1341840086.680940.png 1341840086.680951 depth/1341840086.680951.png +1341840086.712983 rgb/1341840086.712983.png 1341840086.712996 depth/1341840086.712996.png +1341840086.745031 rgb/1341840086.745031.png 1341840086.745043 depth/1341840086.745043.png +1341840086.781079 rgb/1341840086.781079.png 1341840086.781094 depth/1341840086.781094.png +1341840086.813143 rgb/1341840086.813143.png 1341840086.813160 depth/1341840086.813160.png +1341840086.845112 rgb/1341840086.845112.png 1341840086.845127 depth/1341840086.845127.png +1341840086.880946 rgb/1341840086.880946.png 1341840086.880957 depth/1341840086.880957.png +1341840086.913039 rgb/1341840086.913039.png 1341840086.913832 depth/1341840086.913832.png +1341840086.949088 rgb/1341840086.949088.png 1341840086.949109 depth/1341840086.949109.png +1341840086.981130 rgb/1341840086.981130.png 1341840086.981142 depth/1341840086.981142.png +1341840087.013086 rgb/1341840087.013086.png 1341840087.013094 depth/1341840087.013094.png +1341840087.048951 rgb/1341840087.048951.png 1341840087.048991 depth/1341840087.048991.png +1341840087.080960 rgb/1341840087.080960.png 1341840087.080972 depth/1341840087.080972.png +1341840087.114965 rgb/1341840087.114965.png 1341840087.114991 depth/1341840087.114991.png +1341840087.149068 rgb/1341840087.149068.png 1341840087.149100 depth/1341840087.149100.png +1341840087.210062 rgb/1341840087.210062.png 1341840087.210102 depth/1341840087.210102.png +1341840087.241973 rgb/1341840087.241973.png 1341840087.241986 depth/1341840087.241986.png +1341840087.274056 rgb/1341840087.274056.png 1341840087.275958 depth/1341840087.275958.png +1341840087.310014 rgb/1341840087.310014.png 1341840087.310083 depth/1341840087.310083.png +1341840087.342211 rgb/1341840087.342211.png 1341840087.342221 depth/1341840087.342221.png +1341840087.378005 rgb/1341840087.378005.png 1341840087.378083 depth/1341840087.378083.png +1341840087.410085 rgb/1341840087.410085.png 1341840087.410107 depth/1341840087.410107.png +1341840087.442030 rgb/1341840087.442030.png 1341840087.442092 depth/1341840087.442092.png +1341840087.478092 rgb/1341840087.478092.png 1341840087.478144 depth/1341840087.478144.png +1341840087.510068 rgb/1341840087.510068.png 1341840087.510082 depth/1341840087.510082.png +1341840087.542111 rgb/1341840087.542111.png 1341840087.542141 depth/1341840087.542141.png +1341840087.578022 rgb/1341840087.578022.png 1341840087.578058 depth/1341840087.578058.png +1341840087.609992 rgb/1341840087.609992.png 1341840087.610062 depth/1341840087.610062.png +1341840087.646285 rgb/1341840087.646285.png 1341840087.646292 depth/1341840087.646292.png +1341840087.677989 rgb/1341840087.677989.png 1341840087.678002 depth/1341840087.678002.png +1341840087.710009 rgb/1341840087.710009.png 1341840087.710022 depth/1341840087.710022.png +1341840087.746036 rgb/1341840087.746036.png 1341840087.746050 depth/1341840087.746050.png +1341840087.777950 rgb/1341840087.777950.png 1341840087.777959 depth/1341840087.777959.png +1341840087.809957 rgb/1341840087.809957.png 1341840087.809975 depth/1341840087.809975.png +1341840087.846059 rgb/1341840087.846059.png 1341840087.846080 depth/1341840087.846080.png +1341840087.878039 rgb/1341840087.878039.png 1341840087.878062 depth/1341840087.878062.png +1341840087.914037 rgb/1341840087.914037.png 1341840087.914047 depth/1341840087.914047.png +1341840087.946068 rgb/1341840087.946068.png 1341840087.946621 depth/1341840087.946621.png +1341840087.978064 rgb/1341840087.978064.png 1341840087.978232 depth/1341840087.978232.png +1341840088.013958 rgb/1341840088.013958.png 1341840088.013970 depth/1341840088.013970.png +1341840088.046096 rgb/1341840088.046096.png 1341840088.046923 depth/1341840088.046923.png +1341840088.077959 rgb/1341840088.077959.png 1341840088.077975 depth/1341840088.077975.png +1341840088.114105 rgb/1341840088.114105.png 1341840088.114119 depth/1341840088.114119.png +1341840088.146005 rgb/1341840088.146005.png 1341840088.146015 depth/1341840088.146015.png +1341840088.181986 rgb/1341840088.181986.png 1341840088.182027 depth/1341840088.182027.png +1341840088.214180 rgb/1341840088.214180.png 1341840088.214205 depth/1341840088.214205.png +1341840088.245999 rgb/1341840088.245999.png 1341840088.246064 depth/1341840088.246064.png +1341840088.281993 rgb/1341840088.281993.png 1341840088.282019 depth/1341840088.282019.png +1341840088.313975 rgb/1341840088.313975.png 1341840088.313991 depth/1341840088.313991.png +1341840088.350184 rgb/1341840088.350184.png 1341840088.350371 depth/1341840088.350371.png +1341840088.382124 rgb/1341840088.382124.png 1341840088.382139 depth/1341840088.382139.png +1341840088.414141 rgb/1341840088.414141.png 1341840088.414160 depth/1341840088.414160.png +1341840088.450005 rgb/1341840088.450005.png 1341840088.450023 depth/1341840088.450023.png +1341840088.481951 rgb/1341840088.481951.png 1341840088.481975 depth/1341840088.481975.png +1341840088.514195 rgb/1341840088.514195.png 1341840088.514426 depth/1341840088.514426.png +1341840088.550086 rgb/1341840088.550086.png 1341840088.550109 depth/1341840088.550109.png +1341840088.582210 rgb/1341840088.582210.png 1341840088.582232 depth/1341840088.582232.png +1341840088.618206 rgb/1341840088.618206.png 1341840088.618232 depth/1341840088.618232.png +1341840088.650101 rgb/1341840088.650101.png 1341840088.650115 depth/1341840088.650115.png +1341840088.682767 rgb/1341840088.682767.png 1341840088.682786 depth/1341840088.682786.png +1341840088.717920 rgb/1341840088.717920.png 1341840088.717928 depth/1341840088.717928.png +1341840088.750010 rgb/1341840088.750010.png 1341840088.750201 depth/1341840088.750201.png +1341840088.782091 rgb/1341840088.782091.png 1341840088.782122 depth/1341840088.782122.png +1341840088.818075 rgb/1341840088.818075.png 1341840088.818089 depth/1341840088.818089.png +1341840088.849999 rgb/1341840088.849999.png 1341840088.850007 depth/1341840088.850007.png +1341840088.886343 rgb/1341840088.886343.png 1341840088.886384 depth/1341840088.886384.png +1341840088.917961 rgb/1341840088.917961.png 1341840088.918002 depth/1341840088.918002.png +1341840088.950086 rgb/1341840088.950086.png 1341840088.950114 depth/1341840088.950114.png +1341840088.985936 rgb/1341840088.985936.png 1341840088.985949 depth/1341840088.985949.png +1341840089.018030 rgb/1341840089.018030.png 1341840089.018054 depth/1341840089.018054.png +1341840089.050058 rgb/1341840089.050058.png 1341840089.050079 depth/1341840089.050079.png +1341840089.086377 rgb/1341840089.086377.png 1341840089.086404 depth/1341840089.086404.png +1341840089.118898 rgb/1341840089.118898.png 1341840089.119091 depth/1341840089.119091.png +1341840089.155985 rgb/1341840089.155985.png 1341840089.159592 depth/1341840089.159592.png +1341840089.193015 rgb/1341840089.193015.png 1341840089.193046 depth/1341840089.193046.png +1341840089.225124 rgb/1341840089.225124.png 1341840089.225144 depth/1341840089.225144.png +1341840089.260996 rgb/1341840089.260996.png 1341840089.261019 depth/1341840089.261019.png +1341840089.292904 rgb/1341840089.292904.png 1341840089.292917 depth/1341840089.292917.png +1341840089.325058 rgb/1341840089.325058.png 1341840089.325074 depth/1341840089.325074.png +1341840089.360931 rgb/1341840089.360931.png 1341840089.360942 depth/1341840089.360942.png +1341840089.393209 rgb/1341840089.393209.png 1341840089.393227 depth/1341840089.393227.png +1341840089.428976 rgb/1341840089.428976.png 1341840089.428984 depth/1341840089.428984.png +1341840089.461193 rgb/1341840089.461193.png 1341840089.461206 depth/1341840089.461206.png +1341840089.493053 rgb/1341840089.493053.png 1341840089.493066 depth/1341840089.493066.png +1341840089.529041 rgb/1341840089.529041.png 1341840089.529048 depth/1341840089.529048.png +1341840089.561015 rgb/1341840089.561015.png 1341840089.561044 depth/1341840089.561044.png +1341840089.596989 rgb/1341840089.596989.png 1341840089.597026 depth/1341840089.597026.png +1341840089.629045 rgb/1341840089.629045.png 1341840089.629509 depth/1341840089.629509.png +1341840089.660977 rgb/1341840089.660977.png 1341840089.660987 depth/1341840089.660987.png +1341840089.697180 rgb/1341840089.697180.png 1341840089.697197 depth/1341840089.697197.png +1341840089.728954 rgb/1341840089.728954.png 1341840089.728966 depth/1341840089.728966.png +1341840089.761030 rgb/1341840089.761030.png 1341840089.761044 depth/1341840089.761044.png +1341840089.797194 rgb/1341840089.797194.png 1341840089.797210 depth/1341840089.797210.png +1341840089.828965 rgb/1341840089.828965.png 1341840089.828983 depth/1341840089.828983.png +1341840089.861003 rgb/1341840089.861003.png 1341840089.861015 depth/1341840089.861015.png +1341840089.897123 rgb/1341840089.897123.png 1341840089.897143 depth/1341840089.897143.png +1341840089.929407 rgb/1341840089.929407.png 1341840089.929420 depth/1341840089.929420.png +1341840089.960920 rgb/1341840089.960920.png 1341840089.960932 depth/1341840089.960932.png +1341840089.997889 rgb/1341840089.997889.png 1341840089.997906 depth/1341840089.997906.png +1341840090.029152 rgb/1341840090.029152.png 1341840090.029160 depth/1341840090.029160.png +1341840090.064979 rgb/1341840090.064979.png 1341840090.064993 depth/1341840090.064993.png +1341840090.097503 rgb/1341840090.097503.png 1341840090.097523 depth/1341840090.097523.png +1341840090.128972 rgb/1341840090.128972.png 1341840090.128986 depth/1341840090.128986.png +1341840090.165020 rgb/1341840090.165020.png 1341840090.165053 depth/1341840090.165053.png +1341840090.197048 rgb/1341840090.197048.png 1341840090.197068 depth/1341840090.197068.png +1341840090.229041 rgb/1341840090.229041.png 1341840090.229054 depth/1341840090.229054.png +1341840090.265032 rgb/1341840090.265032.png 1341840090.265054 depth/1341840090.265054.png +1341840090.297153 rgb/1341840090.297153.png 1341840090.297167 depth/1341840090.297167.png +1341840090.365109 rgb/1341840090.365109.png 1341840090.365179 depth/1341840090.365179.png +1341840090.426138 rgb/1341840090.426138.png 1341840090.426152 depth/1341840090.426152.png +1341840090.458131 rgb/1341840090.458131.png 1341840090.458145 depth/1341840090.458145.png +1341840090.494010 rgb/1341840090.494010.png 1341840090.494021 depth/1341840090.494021.png +1341840090.525928 rgb/1341840090.525928.png 1341840090.525942 depth/1341840090.525942.png +1341840090.562011 rgb/1341840090.562011.png 1341840090.562024 depth/1341840090.562024.png +1341840090.594146 rgb/1341840090.594146.png 1341840090.594158 depth/1341840090.594158.png +1341840090.625976 rgb/1341840090.625976.png 1341840090.625985 depth/1341840090.625985.png +1341840090.662197 rgb/1341840090.662197.png 1341840090.662243 depth/1341840090.662243.png +1341840090.694336 rgb/1341840090.694336.png 1341840090.694355 depth/1341840090.694355.png +1341840090.726017 rgb/1341840090.726017.png 1341840090.726035 depth/1341840090.726035.png +1341840090.762086 rgb/1341840090.762086.png 1341840090.762124 depth/1341840090.762124.png +1341840090.794081 rgb/1341840090.794081.png 1341840090.794103 depth/1341840090.794103.png +1341840090.830060 rgb/1341840090.830060.png 1341840090.830068 depth/1341840090.830068.png +1341840090.861960 rgb/1341840090.861960.png 1341840090.861972 depth/1341840090.861972.png +1341840090.894052 rgb/1341840090.894052.png 1341840090.894065 depth/1341840090.894065.png +1341840090.930027 rgb/1341840090.930027.png 1341840090.930046 depth/1341840090.930046.png +1341840090.962159 rgb/1341840090.962159.png 1341840090.962174 depth/1341840090.962174.png +1341840090.994115 rgb/1341840090.994115.png 1341840090.994127 depth/1341840090.994127.png +1341840091.030295 rgb/1341840091.030295.png 1341840091.030350 depth/1341840091.030350.png +1341840091.061986 rgb/1341840091.061986.png 1341840091.061998 depth/1341840091.061998.png +1341840091.097971 rgb/1341840091.097971.png 1341840091.097979 depth/1341840091.097979.png +1341840091.129998 rgb/1341840091.129998.png 1341840091.130012 depth/1341840091.130012.png +1341840091.162125 rgb/1341840091.162125.png 1341840091.162143 depth/1341840091.162143.png +1341840091.198103 rgb/1341840091.198103.png 1341840091.198712 depth/1341840091.198712.png +1341840091.230330 rgb/1341840091.230330.png 1341840091.230343 depth/1341840091.230343.png +1341840091.262411 rgb/1341840091.262411.png 1341840091.262432 depth/1341840091.262432.png +1341840091.298027 rgb/1341840091.298027.png 1341840091.298086 depth/1341840091.298086.png +1341840091.330057 rgb/1341840091.330057.png 1341840091.330074 depth/1341840091.330074.png +1341840091.366166 rgb/1341840091.366166.png 1341840091.366183 depth/1341840091.366183.png +1341840091.397935 rgb/1341840091.397935.png 1341840091.397951 depth/1341840091.397951.png +1341840091.430154 rgb/1341840091.430154.png 1341840091.430166 depth/1341840091.430166.png +1341840091.466058 rgb/1341840091.466058.png 1341840091.466080 depth/1341840091.466080.png +1341840091.498556 rgb/1341840091.498556.png 1341840091.498572 depth/1341840091.498572.png +1341840091.530216 rgb/1341840091.530216.png 1341840091.530229 depth/1341840091.530229.png +1341840091.566121 rgb/1341840091.566121.png 1341840091.566238 depth/1341840091.566238.png +1341840091.598358 rgb/1341840091.598358.png 1341840091.598372 depth/1341840091.598372.png +1341840091.634045 rgb/1341840091.634045.png 1341840091.634059 depth/1341840091.634059.png +1341840091.666147 rgb/1341840091.666147.png 1341840091.666167 depth/1341840091.666167.png +1341840091.698112 rgb/1341840091.698112.png 1341840091.699242 depth/1341840091.699242.png +1341840091.734036 rgb/1341840091.734036.png 1341840091.734051 depth/1341840091.734051.png +1341840091.766000 rgb/1341840091.766000.png 1341840091.766015 depth/1341840091.766015.png +1341840091.801977 rgb/1341840091.801977.png 1341840091.801995 depth/1341840091.801995.png +1341840091.834055 rgb/1341840091.834055.png 1341840091.834069 depth/1341840091.834069.png +1341840091.866167 rgb/1341840091.866167.png 1341840091.866182 depth/1341840091.866182.png +1341840091.902016 rgb/1341840091.902016.png 1341840091.902032 depth/1341840091.902032.png +1341840091.933960 rgb/1341840091.933960.png 1341840091.933976 depth/1341840091.933976.png +1341840091.965991 rgb/1341840091.965991.png 1341840091.966052 depth/1341840091.966052.png +1341840092.002090 rgb/1341840092.002090.png 1341840092.002101 depth/1341840092.002101.png +1341840092.034037 rgb/1341840092.034037.png 1341840092.034052 depth/1341840092.034052.png +1341840092.069963 rgb/1341840092.069963.png 1341840092.069974 depth/1341840092.069974.png +1341840092.102060 rgb/1341840092.102060.png 1341840092.102072 depth/1341840092.102072.png +1341840092.133897 rgb/1341840092.133897.png 1341840092.133911 depth/1341840092.133911.png +1341840092.169986 rgb/1341840092.169986.png 1341840092.169998 depth/1341840092.169998.png +1341840092.202031 rgb/1341840092.202031.png 1341840092.202054 depth/1341840092.202054.png +1341840092.234005 rgb/1341840092.234005.png 1341840092.234021 depth/1341840092.234021.png +1341840092.269975 rgb/1341840092.269975.png 1341840092.269985 depth/1341840092.269985.png +1341840092.302076 rgb/1341840092.302076.png 1341840092.302121 depth/1341840092.302121.png +1341840092.338133 rgb/1341840092.338133.png 1341840092.338192 depth/1341840092.338192.png +1341840092.370097 rgb/1341840092.370097.png 1341840092.370114 depth/1341840092.370114.png +1341840092.401970 rgb/1341840092.401970.png 1341840092.402177 depth/1341840092.402177.png +1341840092.437934 rgb/1341840092.437934.png 1341840092.437951 depth/1341840092.437951.png +1341840092.469968 rgb/1341840092.469968.png 1341840092.469979 depth/1341840092.469979.png +1341840092.501965 rgb/1341840092.501965.png 1341840092.501977 depth/1341840092.501977.png +1341840092.538065 rgb/1341840092.538065.png 1341840092.538074 depth/1341840092.538074.png +1341840092.570615 rgb/1341840092.570615.png 1341840092.570719 depth/1341840092.570719.png +1341840092.606041 rgb/1341840092.606041.png 1341840092.606052 depth/1341840092.606052.png +1341840092.638035 rgb/1341840092.638035.png 1341840092.638059 depth/1341840092.638059.png +1341840092.670218 rgb/1341840092.670218.png 1341840092.671634 depth/1341840092.671634.png +1341840092.707285 rgb/1341840092.707285.png 1341840092.707855 depth/1341840092.707855.png +1341840092.738009 rgb/1341840092.738009.png 1341840092.738587 depth/1341840092.738587.png +1341840092.774020 rgb/1341840092.774020.png 1341840092.774028 depth/1341840092.774028.png +1341840092.806419 rgb/1341840092.806419.png 1341840092.806436 depth/1341840092.806436.png +1341840092.838581 rgb/1341840092.838581.png 1341840092.838596 depth/1341840092.838596.png +1341840092.874105 rgb/1341840092.874105.png 1341840092.874114 depth/1341840092.874114.png +1341840092.906168 rgb/1341840092.906168.png 1341840092.906186 depth/1341840092.906186.png +1341840092.938208 rgb/1341840092.938208.png 1341840092.938231 depth/1341840092.938231.png +1341840092.974015 rgb/1341840092.974015.png 1341840092.974036 depth/1341840092.974036.png +1341840093.005964 rgb/1341840093.005964.png 1341840093.005985 depth/1341840093.005985.png +1341840093.041963 rgb/1341840093.041963.png 1341840093.041974 depth/1341840093.041974.png +1341840093.074068 rgb/1341840093.074068.png 1341840093.074683 depth/1341840093.074683.png +1341840093.105999 rgb/1341840093.105999.png 1341840093.106011 depth/1341840093.106011.png +1341840093.142176 rgb/1341840093.142176.png 1341840093.142189 depth/1341840093.142189.png +1341840093.174102 rgb/1341840093.174102.png 1341840093.174777 depth/1341840093.174777.png +1341840093.205980 rgb/1341840093.205980.png 1341840093.205988 depth/1341840093.205988.png +1341840093.241963 rgb/1341840093.241963.png 1341840093.241988 depth/1341840093.241988.png +1341840093.274028 rgb/1341840093.274028.png 1341840093.274036 depth/1341840093.274036.png +1341840093.310076 rgb/1341840093.310076.png 1341840093.310093 depth/1341840093.310093.png +1341840093.342068 rgb/1341840093.342068.png 1341840093.342081 depth/1341840093.342081.png +1341840093.374183 rgb/1341840093.374183.png 1341840093.374197 depth/1341840093.374197.png +1341840093.410028 rgb/1341840093.410028.png 1341840093.410042 depth/1341840093.410042.png +1341840093.442035 rgb/1341840093.442035.png 1341840093.442046 depth/1341840093.442046.png +1341840093.474124 rgb/1341840093.474124.png 1341840093.474136 depth/1341840093.474136.png +1341840093.510180 rgb/1341840093.510180.png 1341840093.510242 depth/1341840093.510242.png +1341840093.542037 rgb/1341840093.542037.png 1341840093.542052 depth/1341840093.542052.png +1341840093.578056 rgb/1341840093.578056.png 1341840093.578126 depth/1341840093.578126.png +1341840093.609967 rgb/1341840093.609967.png 1341840093.610020 depth/1341840093.610020.png +1341840093.642118 rgb/1341840093.642118.png 1341840093.642128 depth/1341840093.642128.png +1341840093.678248 rgb/1341840093.678248.png 1341840093.678313 depth/1341840093.678313.png +1341840093.709940 rgb/1341840093.709940.png 1341840093.709969 depth/1341840093.709969.png +1341840093.742135 rgb/1341840093.742135.png 1341840093.742153 depth/1341840093.742153.png +1341840093.778128 rgb/1341840093.778128.png 1341840093.778148 depth/1341840093.778148.png +1341840093.810107 rgb/1341840093.810107.png 1341840093.810127 depth/1341840093.810127.png +1341840093.846050 rgb/1341840093.846050.png 1341840093.846072 depth/1341840093.846072.png +1341840093.910211 rgb/1341840093.910211.png 1341840093.910224 depth/1341840093.910224.png +1341840093.946162 rgb/1341840093.946162.png 1341840093.946171 depth/1341840093.946171.png +1341840093.978106 rgb/1341840093.978106.png 1341840093.978157 depth/1341840093.978157.png +1341840094.014200 rgb/1341840094.014200.png 1341840094.014218 depth/1341840094.014218.png +1341840094.045955 rgb/1341840094.045955.png 1341840094.045969 depth/1341840094.045969.png +1341840094.078220 rgb/1341840094.078220.png 1341840094.078296 depth/1341840094.078296.png +1341840094.114075 rgb/1341840094.114075.png 1341840094.114089 depth/1341840094.114089.png +1341840094.145961 rgb/1341840094.145961.png 1341840094.146013 depth/1341840094.146013.png +1341840094.177988 rgb/1341840094.177988.png 1341840094.178004 depth/1341840094.178004.png +1341840094.213995 rgb/1341840094.213995.png 1341840094.214006 depth/1341840094.214006.png +1341840094.245995 rgb/1341840094.245995.png 1341840094.246029 depth/1341840094.246029.png +1341840094.282114 rgb/1341840094.282114.png 1341840094.282127 depth/1341840094.282127.png +1341840094.314003 rgb/1341840094.314003.png 1341840094.314011 depth/1341840094.314011.png +1341840094.346025 rgb/1341840094.346025.png 1341840094.346053 depth/1341840094.346053.png +1341840094.382137 rgb/1341840094.382137.png 1341840094.382153 depth/1341840094.382153.png +1341840094.414276 rgb/1341840094.414276.png 1341840094.414305 depth/1341840094.414305.png +1341840094.446017 rgb/1341840094.446017.png 1341840094.446030 depth/1341840094.446030.png +1341840094.481962 rgb/1341840094.481962.png 1341840094.482013 depth/1341840094.482013.png +1341840094.514223 rgb/1341840094.514223.png 1341840094.514266 depth/1341840094.514266.png +1341840094.550073 rgb/1341840094.550073.png 1341840094.550086 depth/1341840094.550086.png +1341840094.582272 rgb/1341840094.582272.png 1341840094.583134 depth/1341840094.583134.png +1341840094.615563 rgb/1341840094.615563.png 1341840094.615579 depth/1341840094.615579.png +1341840094.682271 rgb/1341840094.682271.png 1341840094.682299 depth/1341840094.682299.png +1341840094.715723 rgb/1341840094.715723.png 1341840094.715741 depth/1341840094.715741.png +1341840094.752733 rgb/1341840094.752733.png 1341840094.753976 depth/1341840094.753976.png +1341840094.782622 rgb/1341840094.782622.png 1341840094.783242 depth/1341840094.783242.png +1341840094.818366 rgb/1341840094.818366.png 1341840094.818957 depth/1341840094.818957.png +1341840094.850069 rgb/1341840094.850069.png 1341840094.850087 depth/1341840094.850087.png +1341840094.882000 rgb/1341840094.882000.png 1341840094.882748 depth/1341840094.882748.png +1341840094.918054 rgb/1341840094.918054.png 1341840094.918073 depth/1341840094.918073.png +1341840094.949944 rgb/1341840094.949944.png 1341840094.950025 depth/1341840094.950025.png +1341840094.985953 rgb/1341840094.985953.png 1341840094.985975 depth/1341840094.985975.png +1341840095.017986 rgb/1341840095.017986.png 1341840095.018094 depth/1341840095.018094.png +1341840095.050029 rgb/1341840095.050029.png 1341840095.050044 depth/1341840095.050044.png +1341840095.086058 rgb/1341840095.086058.png 1341840095.086070 depth/1341840095.086070.png +1341840095.118044 rgb/1341840095.118044.png 1341840095.118063 depth/1341840095.118063.png +1341840095.150110 rgb/1341840095.150110.png 1341840095.150130 depth/1341840095.150130.png +1341840095.186169 rgb/1341840095.186169.png 1341840095.186180 depth/1341840095.186180.png +1341840095.218041 rgb/1341840095.218041.png 1341840095.218053 depth/1341840095.218053.png +1341840095.254017 rgb/1341840095.254017.png 1341840095.254034 depth/1341840095.254034.png +1341840095.285981 rgb/1341840095.285981.png 1341840095.285993 depth/1341840095.285993.png +1341840095.318140 rgb/1341840095.318140.png 1341840095.318156 depth/1341840095.318156.png +1341840095.354079 rgb/1341840095.354079.png 1341840095.354097 depth/1341840095.354097.png +1341840095.385974 rgb/1341840095.385974.png 1341840095.385988 depth/1341840095.385988.png +1341840095.417958 rgb/1341840095.417958.png 1341840095.417990 depth/1341840095.417990.png +1341840095.454028 rgb/1341840095.454028.png 1341840095.454044 depth/1341840095.454044.png +1341840095.486008 rgb/1341840095.486008.png 1341840095.486027 depth/1341840095.486027.png +1341840095.522111 rgb/1341840095.522111.png 1341840095.522143 depth/1341840095.522143.png +1341840095.554366 rgb/1341840095.554366.png 1341840095.554376 depth/1341840095.554376.png +1341840095.586122 rgb/1341840095.586122.png 1341840095.586148 depth/1341840095.586148.png +1341840095.621980 rgb/1341840095.621980.png 1341840095.621993 depth/1341840095.621993.png +1341840095.653945 rgb/1341840095.653945.png 1341840095.653994 depth/1341840095.653994.png +1341840095.686009 rgb/1341840095.686009.png 1341840095.686021 depth/1341840095.686021.png +1341840095.721971 rgb/1341840095.721971.png 1341840095.721997 depth/1341840095.721997.png +1341840095.753967 rgb/1341840095.753967.png 1341840095.753976 depth/1341840095.753976.png +1341840095.789981 rgb/1341840095.789981.png 1341840095.789996 depth/1341840095.789996.png +1341840095.821991 rgb/1341840095.821991.png 1341840095.822005 depth/1341840095.822005.png +1341840095.853993 rgb/1341840095.853993.png 1341840095.854012 depth/1341840095.854012.png +1341840095.890167 rgb/1341840095.890167.png 1341840095.890184 depth/1341840095.890184.png +1341840095.922043 rgb/1341840095.922043.png 1341840095.922065 depth/1341840095.922065.png +1341840095.953986 rgb/1341840095.953986.png 1341840095.954011 depth/1341840095.954011.png +1341840095.990074 rgb/1341840095.990074.png 1341840095.990091 depth/1341840095.990091.png +1341840096.022067 rgb/1341840096.022067.png 1341840096.022106 depth/1341840096.022106.png +1341840096.058118 rgb/1341840096.058118.png 1341840096.058155 depth/1341840096.058155.png +1341840096.090098 rgb/1341840096.090098.png 1341840096.090125 depth/1341840096.090125.png +1341840096.122246 rgb/1341840096.122246.png 1341840096.122266 depth/1341840096.122266.png +1341840096.157960 rgb/1341840096.157960.png 1341840096.157987 depth/1341840096.157987.png +1341840096.190067 rgb/1341840096.190067.png 1341840096.190087 depth/1341840096.190087.png +1341840096.226024 rgb/1341840096.226024.png 1341840096.226045 depth/1341840096.226045.png +1341840096.258026 rgb/1341840096.258026.png 1341840096.258050 depth/1341840096.258050.png +1341840096.290017 rgb/1341840096.290017.png 1341840096.290048 depth/1341840096.290048.png +1341840096.326010 rgb/1341840096.326010.png 1341840096.326031 depth/1341840096.326031.png +1341840096.365135 rgb/1341840096.365135.png 1341840096.365180 depth/1341840096.365180.png +1341840096.426063 rgb/1341840096.426063.png 1341840096.426074 depth/1341840096.426074.png +1341840096.458130 rgb/1341840096.458130.png 1341840096.458145 depth/1341840096.458145.png +1341840096.493964 rgb/1341840096.493964.png 1341840096.493977 depth/1341840096.493977.png +1341840096.557989 rgb/1341840096.557989.png 1341840096.558022 depth/1341840096.558022.png +1341840096.594051 rgb/1341840096.594051.png 1341840096.594066 depth/1341840096.594066.png +1341840096.625905 rgb/1341840096.625905.png 1341840096.625939 depth/1341840096.625939.png +1341840096.658100 rgb/1341840096.658100.png 1341840096.658123 depth/1341840096.658123.png +1341840096.694102 rgb/1341840096.694102.png 1341840096.694138 depth/1341840096.694138.png +1341840096.726051 rgb/1341840096.726051.png 1341840096.726064 depth/1341840096.726064.png +1341840096.762093 rgb/1341840096.762093.png 1341840096.762101 depth/1341840096.762101.png +1341840096.793991 rgb/1341840096.793991.png 1341840096.794009 depth/1341840096.794009.png +1341840096.825964 rgb/1341840096.825964.png 1341840096.825990 depth/1341840096.825990.png +1341840096.862107 rgb/1341840096.862107.png 1341840096.862123 depth/1341840096.862123.png +1341840096.893996 rgb/1341840096.893996.png 1341840096.894017 depth/1341840096.894017.png +1341840096.926123 rgb/1341840096.926123.png 1341840096.926145 depth/1341840096.926145.png +1341840096.962109 rgb/1341840096.962109.png 1341840096.962146 depth/1341840096.962146.png +1341840096.994381 rgb/1341840096.994381.png 1341840096.994428 depth/1341840096.994428.png +1341840097.030022 rgb/1341840097.030022.png 1341840097.030045 depth/1341840097.030045.png +1341840097.062043 rgb/1341840097.062043.png 1341840097.062063 depth/1341840097.062063.png +1341840097.094113 rgb/1341840097.094113.png 1341840097.094124 depth/1341840097.094124.png +1341840097.130197 rgb/1341840097.130197.png 1341840097.130835 depth/1341840097.130835.png +1341840097.162122 rgb/1341840097.162122.png 1341840097.162137 depth/1341840097.162137.png +1341840097.198273 rgb/1341840097.198273.png 1341840097.198292 depth/1341840097.198292.png +1341840097.230163 rgb/1341840097.230163.png 1341840097.230185 depth/1341840097.230185.png +1341840097.262128 rgb/1341840097.262128.png 1341840097.262646 depth/1341840097.262646.png +1341840097.298060 rgb/1341840097.298060.png 1341840097.298081 depth/1341840097.298081.png +1341840097.330044 rgb/1341840097.330044.png 1341840097.330081 depth/1341840097.330081.png +1341840097.398069 rgb/1341840097.398069.png 1341840097.398078 depth/1341840097.398078.png +1341840097.430211 rgb/1341840097.430211.png 1341840097.430228 depth/1341840097.430228.png +1341840097.465939 rgb/1341840097.465939.png 1341840097.466443 depth/1341840097.466443.png +1341840097.498027 rgb/1341840097.498027.png 1341840097.498071 depth/1341840097.498071.png +1341840097.530195 rgb/1341840097.530195.png 1341840097.530217 depth/1341840097.530217.png +1341840097.566099 rgb/1341840097.566099.png 1341840097.566510 depth/1341840097.566510.png +1341840097.598108 rgb/1341840097.598108.png 1341840097.598143 depth/1341840097.598143.png +1341840097.630355 rgb/1341840097.630355.png 1341840097.630382 depth/1341840097.630382.png +1341840097.665927 rgb/1341840097.665927.png 1341840097.665944 depth/1341840097.665944.png +1341840097.698115 rgb/1341840097.698115.png 1341840097.698126 depth/1341840097.698126.png +1341840097.734100 rgb/1341840097.734100.png 1341840097.734130 depth/1341840097.734130.png +1341840097.766062 rgb/1341840097.766062.png 1341840097.766100 depth/1341840097.766100.png +1341840097.799766 rgb/1341840097.799766.png 1341840097.799793 depth/1341840097.799793.png +1341840097.834458 rgb/1341840097.834458.png 1341840097.834483 depth/1341840097.834483.png +1341840097.866563 rgb/1341840097.866563.png 1341840097.866577 depth/1341840097.866577.png +1341840097.897960 rgb/1341840097.897960.png 1341840097.897978 depth/1341840097.897978.png +1341840097.933958 rgb/1341840097.933958.png 1341840097.933978 depth/1341840097.933978.png +1341840097.965962 rgb/1341840097.965962.png 1341840097.965986 depth/1341840097.965986.png +1341840098.002067 rgb/1341840098.002067.png 1341840098.002087 depth/1341840098.002087.png +1341840098.033966 rgb/1341840098.033966.png 1341840098.033986 depth/1341840098.033986.png +1341840098.066017 rgb/1341840098.066017.png 1341840098.066026 depth/1341840098.066026.png +1341840098.102112 rgb/1341840098.102112.png 1341840098.102122 depth/1341840098.102122.png +1341840098.133988 rgb/1341840098.133988.png 1341840098.134056 depth/1341840098.134056.png +1341840098.166085 rgb/1341840098.166085.png 1341840098.166110 depth/1341840098.166110.png +1341840098.202060 rgb/1341840098.202060.png 1341840098.202074 depth/1341840098.202074.png +1341840098.233997 rgb/1341840098.233997.png 1341840098.234004 depth/1341840098.234004.png +1341840098.269976 rgb/1341840098.269976.png 1341840098.269992 depth/1341840098.269992.png +1341840098.302041 rgb/1341840098.302041.png 1341840098.302103 depth/1341840098.302103.png +1341840098.333999 rgb/1341840098.333999.png 1341840098.334010 depth/1341840098.334010.png +1341840098.369946 rgb/1341840098.369946.png 1341840098.369957 depth/1341840098.369957.png +1341840098.401992 rgb/1341840098.401992.png 1341840098.402007 depth/1341840098.402007.png +1341840098.438538 rgb/1341840098.438538.png 1341840098.438553 depth/1341840098.438553.png +1341840098.470049 rgb/1341840098.470049.png 1341840098.470063 depth/1341840098.470063.png +1341840098.502216 rgb/1341840098.502216.png 1341840098.502743 depth/1341840098.502743.png +1341840098.538046 rgb/1341840098.538046.png 1341840098.538321 depth/1341840098.538321.png +1341840098.569979 rgb/1341840098.569979.png 1341840098.569992 depth/1341840098.569992.png +1341840098.601991 rgb/1341840098.601991.png 1341840098.602061 depth/1341840098.602061.png +1341840098.638011 rgb/1341840098.638011.png 1341840098.638022 depth/1341840098.638022.png +1341840098.669979 rgb/1341840098.669979.png 1341840098.670000 depth/1341840098.670000.png +1341840098.706035 rgb/1341840098.706035.png 1341840098.706062 depth/1341840098.706062.png +1341840098.737998 rgb/1341840098.737998.png 1341840098.738008 depth/1341840098.738008.png +1341840098.770012 rgb/1341840098.770012.png 1341840098.770061 depth/1341840098.770061.png +1341840098.806004 rgb/1341840098.806004.png 1341840098.806043 depth/1341840098.806043.png +1341840098.838054 rgb/1341840098.838054.png 1341840098.838574 depth/1341840098.838574.png +1341840098.870018 rgb/1341840098.870018.png 1341840098.870060 depth/1341840098.870060.png +1341840098.905941 rgb/1341840098.905941.png 1341840098.905985 depth/1341840098.905985.png +1341840098.937995 rgb/1341840098.937995.png 1341840098.938021 depth/1341840098.938021.png +1341840098.974247 rgb/1341840098.974247.png 1341840098.974264 depth/1341840098.974264.png +1341840099.005991 rgb/1341840099.005991.png 1341840099.006034 depth/1341840099.006034.png +1341840099.038009 rgb/1341840099.038009.png 1341840099.038033 depth/1341840099.038033.png +1341840099.074065 rgb/1341840099.074065.png 1341840099.074074 depth/1341840099.074074.png +1341840099.106137 rgb/1341840099.106137.png 1341840099.106197 depth/1341840099.106197.png +1341840099.138052 rgb/1341840099.138052.png 1341840099.138083 depth/1341840099.138083.png +1341840099.174134 rgb/1341840099.174134.png 1341840099.174147 depth/1341840099.174147.png +1341840099.206089 rgb/1341840099.206089.png 1341840099.206106 depth/1341840099.206106.png +1341840099.242010 rgb/1341840099.242010.png 1341840099.242026 depth/1341840099.242026.png +1341840099.274189 rgb/1341840099.274189.png 1341840099.274198 depth/1341840099.274198.png +1341840099.313480 rgb/1341840099.313480.png 1341840099.313529 depth/1341840099.313529.png +1341840099.374131 rgb/1341840099.374131.png 1341840099.374173 depth/1341840099.374173.png +1341840099.410022 rgb/1341840099.410022.png 1341840099.410043 depth/1341840099.410043.png +1341840099.441968 rgb/1341840099.441968.png 1341840099.441995 depth/1341840099.441995.png +1341840099.474148 rgb/1341840099.474148.png 1341840099.474161 depth/1341840099.474161.png +1341840099.509932 rgb/1341840099.509932.png 1341840099.509953 depth/1341840099.509953.png +1341840099.542031 rgb/1341840099.542031.png 1341840099.542044 depth/1341840099.542044.png +1341840099.610204 rgb/1341840099.610204.png 1341840099.610263 depth/1341840099.610263.png +1341840099.641985 rgb/1341840099.641985.png 1341840099.641994 depth/1341840099.641994.png +1341840099.678015 rgb/1341840099.678015.png 1341840099.678114 depth/1341840099.678114.png +1341840099.710201 rgb/1341840099.710201.png 1341840099.710816 depth/1341840099.710816.png +1341840099.742027 rgb/1341840099.742027.png 1341840099.742046 depth/1341840099.742046.png +1341840099.777936 rgb/1341840099.777936.png 1341840099.777948 depth/1341840099.777948.png +1341840099.810002 rgb/1341840099.810002.png 1341840099.810011 depth/1341840099.810011.png +1341840099.842110 rgb/1341840099.842110.png 1341840099.842724 depth/1341840099.842724.png +1341840099.878109 rgb/1341840099.878109.png 1341840099.878695 depth/1341840099.878695.png +1341840099.909941 rgb/1341840099.909941.png 1341840099.909983 depth/1341840099.909983.png +1341840099.946242 rgb/1341840099.946242.png 1341840099.946260 depth/1341840099.946260.png +1341840099.977991 rgb/1341840099.977991.png 1341840099.978006 depth/1341840099.978006.png +1341840100.010063 rgb/1341840100.010063.png 1341840100.010072 depth/1341840100.010072.png +1341840100.046198 rgb/1341840100.046198.png 1341840100.046243 depth/1341840100.046243.png +1341840100.077944 rgb/1341840100.077944.png 1341840100.077981 depth/1341840100.077981.png +1341840100.110081 rgb/1341840100.110081.png 1341840100.110101 depth/1341840100.110101.png +1341840100.146035 rgb/1341840100.146035.png 1341840100.146177 depth/1341840100.146177.png +1341840100.178200 rgb/1341840100.178200.png 1341840100.178222 depth/1341840100.178222.png +1341840100.215238 rgb/1341840100.215238.png 1341840100.215353 depth/1341840100.215353.png +1341840100.278200 rgb/1341840100.278200.png 1341840100.278206 depth/1341840100.278206.png +1341840100.314468 rgb/1341840100.314468.png 1341840100.314511 depth/1341840100.314511.png +1341840100.345946 rgb/1341840100.345946.png 1341840100.346221 depth/1341840100.346221.png +1341840100.378127 rgb/1341840100.378127.png 1341840100.378139 depth/1341840100.378139.png +1341840100.414163 rgb/1341840100.414163.png 1341840100.414176 depth/1341840100.414176.png +1341840100.446292 rgb/1341840100.446292.png 1341840100.446318 depth/1341840100.446318.png +1341840100.482170 rgb/1341840100.482170.png 1341840100.482352 depth/1341840100.482352.png +1341840100.513929 rgb/1341840100.513929.png 1341840100.513978 depth/1341840100.513978.png +1341840100.546213 rgb/1341840100.546213.png 1341840100.546229 depth/1341840100.546229.png +1341840100.582002 rgb/1341840100.582002.png 1341840100.582028 depth/1341840100.582028.png +1341840100.614097 rgb/1341840100.614097.png 1341840100.614147 depth/1341840100.614147.png +1341840100.649997 rgb/1341840100.649997.png 1341840100.650017 depth/1341840100.650017.png +1341840100.682252 rgb/1341840100.682252.png 1341840100.682272 depth/1341840100.682272.png +1341840100.714000 rgb/1341840100.714000.png 1341840100.714013 depth/1341840100.714013.png +1341840100.749993 rgb/1341840100.749993.png 1341840100.750006 depth/1341840100.750006.png +1341840100.782007 rgb/1341840100.782007.png 1341840100.782031 depth/1341840100.782031.png +1341840100.814025 rgb/1341840100.814025.png 1341840100.814063 depth/1341840100.814063.png +1341840100.850129 rgb/1341840100.850129.png 1341840100.850154 depth/1341840100.850154.png +1341840100.881983 rgb/1341840100.881983.png 1341840100.882003 depth/1341840100.882003.png +1341840100.918146 rgb/1341840100.918146.png 1341840100.918223 depth/1341840100.918223.png +1341840100.950032 rgb/1341840100.950032.png 1341840100.950043 depth/1341840100.950043.png +1341840100.982020 rgb/1341840100.982020.png 1341840100.982031 depth/1341840100.982031.png +1341840101.018061 rgb/1341840101.018061.png 1341840101.018086 depth/1341840101.018086.png +1341840101.050199 rgb/1341840101.050199.png 1341840101.050306 depth/1341840101.050306.png +1341840101.081947 rgb/1341840101.081947.png 1341840101.081964 depth/1341840101.081964.png +1341840101.118070 rgb/1341840101.118070.png 1341840101.118081 depth/1341840101.118081.png +1341840101.150042 rgb/1341840101.150042.png 1341840101.150065 depth/1341840101.150065.png +1341840101.185930 rgb/1341840101.185930.png 1341840101.185947 depth/1341840101.185947.png +1341840101.218045 rgb/1341840101.218045.png 1341840101.218080 depth/1341840101.218080.png +1341840101.253078 rgb/1341840101.253078.png 1341840101.253148 depth/1341840101.253148.png +1341840101.286158 rgb/1341840101.286158.png 1341840101.286174 depth/1341840101.286174.png +1341840101.318064 rgb/1341840101.318064.png 1341840101.318499 depth/1341840101.318499.png +1341840101.349978 rgb/1341840101.349978.png 1341840101.349991 depth/1341840101.349991.png +1341840101.386236 rgb/1341840101.386236.png 1341840101.386245 depth/1341840101.386245.png +1341840101.418064 rgb/1341840101.418064.png 1341840101.418071 depth/1341840101.418071.png +1341840101.454068 rgb/1341840101.454068.png 1341840101.454096 depth/1341840101.454096.png +1341840101.486162 rgb/1341840101.486162.png 1341840101.486940 depth/1341840101.486940.png +1341840101.518024 rgb/1341840101.518024.png 1341840101.518061 depth/1341840101.518061.png +1341840101.554371 rgb/1341840101.554371.png 1341840101.554434 depth/1341840101.554434.png +1341840101.585933 rgb/1341840101.585933.png 1341840101.585970 depth/1341840101.585970.png +1341840101.621943 rgb/1341840101.621943.png 1341840101.621982 depth/1341840101.621982.png +1341840101.654039 rgb/1341840101.654039.png 1341840101.654056 depth/1341840101.654056.png +1341840101.686008 rgb/1341840101.686008.png 1341840101.686052 depth/1341840101.686052.png +1341840101.721937 rgb/1341840101.721937.png 1341840101.721973 depth/1341840101.721973.png +1341840101.753999 rgb/1341840101.753999.png 1341840101.754035 depth/1341840101.754035.png +1341840101.786021 rgb/1341840101.786021.png 1341840101.786108 depth/1341840101.786108.png +1341840101.821978 rgb/1341840101.821978.png 1341840101.822034 depth/1341840101.822034.png +1341840101.854032 rgb/1341840101.854032.png 1341840101.854052 depth/1341840101.854052.png +1341840101.890071 rgb/1341840101.890071.png 1341840101.890104 depth/1341840101.890104.png +1341840101.921957 rgb/1341840101.921957.png 1341840101.921995 depth/1341840101.921995.png +1341840101.953985 rgb/1341840101.953985.png 1341840101.954051 depth/1341840101.954051.png +1341840101.990056 rgb/1341840101.990056.png 1341840101.990099 depth/1341840101.990099.png +1341840102.022239 rgb/1341840102.022239.png 1341840102.022306 depth/1341840102.022306.png +1341840102.054164 rgb/1341840102.054164.png 1341840102.054198 depth/1341840102.054198.png +1341840102.089965 rgb/1341840102.089965.png 1341840102.090016 depth/1341840102.090016.png +1341840102.122063 rgb/1341840102.122063.png 1341840102.122090 depth/1341840102.122090.png +1341840102.158709 rgb/1341840102.158709.png 1341840102.158245 depth/1341840102.158245.png +1341840102.190046 rgb/1341840102.190046.png 1341840102.190083 depth/1341840102.190083.png +1341840102.221963 rgb/1341840102.221963.png 1341840102.221992 depth/1341840102.221992.png +1341840102.258028 rgb/1341840102.258028.png 1341840102.258040 depth/1341840102.258040.png +1341840102.289992 rgb/1341840102.289992.png 1341840102.290004 depth/1341840102.290004.png +1341840102.322004 rgb/1341840102.322004.png 1341840102.322019 depth/1341840102.322019.png +1341840102.357985 rgb/1341840102.357985.png 1341840102.357993 depth/1341840102.357993.png +1341840102.389994 rgb/1341840102.389994.png 1341840102.390006 depth/1341840102.390006.png +1341840102.426192 rgb/1341840102.426192.png 1341840102.426209 depth/1341840102.426209.png +1341840102.457974 rgb/1341840102.457974.png 1341840102.457985 depth/1341840102.457985.png +1341840102.489909 rgb/1341840102.489909.png 1341840102.489942 depth/1341840102.489942.png +1341840102.525928 rgb/1341840102.525928.png 1341840102.525941 depth/1341840102.525941.png +1341840102.558042 rgb/1341840102.558042.png 1341840102.558064 depth/1341840102.558064.png +1341840102.589964 rgb/1341840102.589964.png 1341840102.589974 depth/1341840102.589974.png +1341840102.625930 rgb/1341840102.625930.png 1341840102.625937 depth/1341840102.625937.png +1341840102.658156 rgb/1341840102.658156.png 1341840102.658198 depth/1341840102.658198.png +1341840102.694450 rgb/1341840102.694450.png 1341840102.694466 depth/1341840102.694466.png +1341840102.725995 rgb/1341840102.725995.png 1341840102.726013 depth/1341840102.726013.png +1341840102.758299 rgb/1341840102.758299.png 1341840102.758320 depth/1341840102.758320.png +1341840102.794279 rgb/1341840102.794279.png 1341840102.794551 depth/1341840102.794551.png +1341840102.826150 rgb/1341840102.826150.png 1341840102.826165 depth/1341840102.826165.png +1341840102.894146 rgb/1341840102.894146.png 1341840102.894163 depth/1341840102.894163.png +1341840102.933073 rgb/1341840102.933073.png 1341840102.933092 depth/1341840102.933092.png +1341840102.969086 rgb/1341840102.969086.png 1341840102.969815 depth/1341840102.969815.png +1341840103.001248 rgb/1341840103.001248.png 1341840103.001933 depth/1341840103.001933.png +1341840103.033319 rgb/1341840103.033319.png 1341840103.033337 depth/1341840103.033337.png +1341840103.068955 rgb/1341840103.068955.png 1341840103.068997 depth/1341840103.068997.png +1341840103.100979 rgb/1341840103.100979.png 1341840103.101450 depth/1341840103.101450.png +1341840103.133214 rgb/1341840103.133214.png 1341840103.133233 depth/1341840103.133233.png +1341840103.169178 rgb/1341840103.169178.png 1341840103.169193 depth/1341840103.169193.png +1341840103.200997 rgb/1341840103.200997.png 1341840103.201030 depth/1341840103.201030.png +1341840103.236975 rgb/1341840103.236975.png 1341840103.237023 depth/1341840103.237023.png +1341840103.269372 rgb/1341840103.269372.png 1341840103.269387 depth/1341840103.269387.png +1341840103.301138 rgb/1341840103.301138.png 1341840103.301150 depth/1341840103.301150.png +1341840103.337120 rgb/1341840103.337120.png 1341840103.337146 depth/1341840103.337146.png +1341840103.369061 rgb/1341840103.369061.png 1341840103.369072 depth/1341840103.369072.png +1341840103.401053 rgb/1341840103.401053.png 1341840103.401068 depth/1341840103.401068.png +1341840103.437062 rgb/1341840103.437062.png 1341840103.437071 depth/1341840103.437071.png +1341840103.469037 rgb/1341840103.469037.png 1341840103.470082 depth/1341840103.470082.png +1341840103.505180 rgb/1341840103.505180.png 1341840103.505189 depth/1341840103.505189.png +1341840103.537086 rgb/1341840103.537086.png 1341840103.537094 depth/1341840103.537094.png +1341840103.569032 rgb/1341840103.569032.png 1341840103.569045 depth/1341840103.569045.png +1341840103.606036 rgb/1341840103.606036.png 1341840103.606046 depth/1341840103.606046.png +1341840103.637674 rgb/1341840103.637674.png 1341840103.637702 depth/1341840103.637702.png +1341840103.669007 rgb/1341840103.669007.png 1341840103.669022 depth/1341840103.669022.png +1341840103.705253 rgb/1341840103.705253.png 1341840103.705277 depth/1341840103.705277.png +1341840103.737091 rgb/1341840103.737091.png 1341840103.737100 depth/1341840103.737100.png +1341840103.769171 rgb/1341840103.769171.png 1341840103.769789 depth/1341840103.769789.png +1341840103.805228 rgb/1341840103.805228.png 1341840103.805244 depth/1341840103.805244.png +1341840103.837157 rgb/1341840103.837157.png 1341840103.837179 depth/1341840103.837179.png +1341840103.873084 rgb/1341840103.873084.png 1341840103.873097 depth/1341840103.873097.png +1341840103.906706 rgb/1341840103.906706.png 1341840103.907164 depth/1341840103.907164.png +1341840103.937494 rgb/1341840103.937494.png 1341840103.937521 depth/1341840103.937521.png +1341840103.973092 rgb/1341840103.973092.png 1341840103.973110 depth/1341840103.973110.png +1341840104.005167 rgb/1341840104.005167.png 1341840104.005190 depth/1341840104.005190.png +1341840104.036982 rgb/1341840104.036982.png 1341840104.037008 depth/1341840104.037008.png +1341840104.073174 rgb/1341840104.073174.png 1341840104.073182 depth/1341840104.073182.png +1341840104.105028 rgb/1341840104.105028.png 1341840104.105060 depth/1341840104.105060.png +1341840104.137083 rgb/1341840104.137083.png 1341840104.137094 depth/1341840104.137094.png +1341840104.173061 rgb/1341840104.173061.png 1341840104.173072 depth/1341840104.173072.png +1341840104.205031 rgb/1341840104.205031.png 1341840104.205111 depth/1341840104.205111.png +1341840104.241049 rgb/1341840104.241049.png 1341840104.241057 depth/1341840104.241057.png +1341840104.273043 rgb/1341840104.273043.png 1341840104.273062 depth/1341840104.273062.png +1341840104.305085 rgb/1341840104.305085.png 1341840104.305899 depth/1341840104.305899.png +1341840104.341064 rgb/1341840104.341064.png 1341840104.341940 depth/1341840104.341940.png +1341840104.372984 rgb/1341840104.372984.png 1341840104.373003 depth/1341840104.373003.png +1341840104.404928 rgb/1341840104.404928.png 1341840104.404948 depth/1341840104.404948.png +1341840104.441139 rgb/1341840104.441139.png 1341840104.441166 depth/1341840104.441166.png +1341840104.472949 rgb/1341840104.472949.png 1341840104.473061 depth/1341840104.473061.png +1341840104.505075 rgb/1341840104.505075.png 1341840104.505136 depth/1341840104.505136.png +1341840104.540989 rgb/1341840104.540989.png 1341840104.540997 depth/1341840104.540997.png +1341840104.572927 rgb/1341840104.572927.png 1341840104.572939 depth/1341840104.572939.png +1341840104.609074 rgb/1341840104.609074.png 1341840104.609100 depth/1341840104.609100.png +1341840104.640948 rgb/1341840104.640948.png 1341840104.640969 depth/1341840104.640969.png +1341840104.673069 rgb/1341840104.673069.png 1341840104.673097 depth/1341840104.673097.png +1341840104.709087 rgb/1341840104.709087.png 1341840104.709109 depth/1341840104.709109.png +1341840104.740940 rgb/1341840104.740940.png 1341840104.740966 depth/1341840104.740966.png +1341840104.777040 rgb/1341840104.777040.png 1341840104.777059 depth/1341840104.777059.png +1341840104.809199 rgb/1341840104.809199.png 1341840104.809227 depth/1341840104.809227.png +1341840104.840918 rgb/1341840104.840918.png 1341840104.840943 depth/1341840104.840943.png +1341840104.877040 rgb/1341840104.877040.png 1341840104.877200 depth/1341840104.877200.png +1341840104.908967 rgb/1341840104.908967.png 1341840104.908983 depth/1341840104.908983.png +1341840104.945200 rgb/1341840104.945200.png 1341840104.945242 depth/1341840104.945242.png +1341840104.976967 rgb/1341840104.976967.png 1341840104.976987 depth/1341840104.976987.png +1341840105.009091 rgb/1341840105.009091.png 1341840105.009102 depth/1341840105.009102.png +1341840105.044912 rgb/1341840105.044912.png 1341840105.044953 depth/1341840105.044953.png +1341840105.076982 rgb/1341840105.076982.png 1341840105.076993 depth/1341840105.076993.png +1341840105.112963 rgb/1341840105.112963.png 1341840105.113438 depth/1341840105.113438.png +1341840105.145078 rgb/1341840105.145078.png 1341840105.145087 depth/1341840105.145087.png +1341840105.176904 rgb/1341840105.176904.png 1341840105.176925 depth/1341840105.176925.png +1341840105.213036 rgb/1341840105.213036.png 1341840105.213052 depth/1341840105.213052.png +1341840105.245160 rgb/1341840105.245160.png 1341840105.245170 depth/1341840105.245170.png +1341840105.281007 rgb/1341840105.281007.png 1341840105.281045 depth/1341840105.281045.png +1341840105.313107 rgb/1341840105.313107.png 1341840105.313132 depth/1341840105.313132.png +1341840105.345000 rgb/1341840105.345000.png 1341840105.345009 depth/1341840105.345009.png +1341840105.381032 rgb/1341840105.381032.png 1341840105.381047 depth/1341840105.381047.png +1341840105.413121 rgb/1341840105.413121.png 1341840105.413147 depth/1341840105.413147.png +1341840105.449115 rgb/1341840105.449115.png 1341840105.449688 depth/1341840105.449688.png +1341840105.481450 rgb/1341840105.481450.png 1341840105.481464 depth/1341840105.481464.png +1341840105.514575 rgb/1341840105.514575.png 1341840105.514584 depth/1341840105.514584.png +1341840105.548981 rgb/1341840105.548981.png 1341840105.548995 depth/1341840105.548995.png +1341840105.581060 rgb/1341840105.581060.png 1341840105.581079 depth/1341840105.581079.png +1341840105.617086 rgb/1341840105.617086.png 1341840105.617109 depth/1341840105.617109.png +1341840105.649066 rgb/1341840105.649066.png 1341840105.649099 depth/1341840105.649099.png +1341840105.681012 rgb/1341840105.681012.png 1341840105.681020 depth/1341840105.681020.png +1341840105.717030 rgb/1341840105.717030.png 1341840105.717826 depth/1341840105.717826.png +1341840105.749001 rgb/1341840105.749001.png 1341840105.749086 depth/1341840105.749086.png +1341840105.785122 rgb/1341840105.785122.png 1341840105.785152 depth/1341840105.785152.png +1341840105.817039 rgb/1341840105.817039.png 1341840105.817054 depth/1341840105.817054.png +1341840105.849027 rgb/1341840105.849027.png 1341840105.849040 depth/1341840105.849040.png +1341840105.885061 rgb/1341840105.885061.png 1341840105.885078 depth/1341840105.885078.png +1341840105.917087 rgb/1341840105.917087.png 1341840105.917154 depth/1341840105.917154.png +1341840105.949293 rgb/1341840105.949293.png 1341840105.950717 depth/1341840105.950717.png +1341840105.985293 rgb/1341840105.985293.png 1341840105.986378 depth/1341840105.986378.png +1341840106.018209 rgb/1341840106.018209.png 1341840106.018243 depth/1341840106.018243.png +1341840106.049368 rgb/1341840106.049368.png 1341840106.049384 depth/1341840106.049384.png +1341840106.086360 rgb/1341840106.086360.png 1341840106.085629 depth/1341840106.085629.png +1341840106.146556 rgb/1341840106.146556.png 1341840106.147575 depth/1341840106.147575.png +1341840106.178238 rgb/1341840106.178238.png 1341840106.179426 depth/1341840106.179426.png +1341840106.210613 rgb/1341840106.210613.png 1341840106.211882 depth/1341840106.211882.png +1341840106.247122 rgb/1341840106.247122.png 1341840106.247283 depth/1341840106.247283.png +1341840106.317396 rgb/1341840106.317396.png 1341840106.319151 depth/1341840106.319151.png +1341840106.378203 rgb/1341840106.378203.png 1341840106.378218 depth/1341840106.378218.png +1341840106.414296 rgb/1341840106.414296.png 1341840106.414976 depth/1341840106.414976.png +1341840106.453839 rgb/1341840106.453839.png 1341840106.454299 depth/1341840106.454299.png +1341840106.486326 rgb/1341840106.486326.png 1341840106.487571 depth/1341840106.487571.png +1341840106.546500 rgb/1341840106.546500.png 1341840106.546514 depth/1341840106.546514.png +1341840106.582042 rgb/1341840106.582042.png 1341840106.582062 depth/1341840106.582062.png +1341840106.614595 rgb/1341840106.614595.png 1341840106.614612 depth/1341840106.614612.png +1341840106.653161 rgb/1341840106.653161.png 1341840106.646162 depth/1341840106.646162.png +1341840106.714118 rgb/1341840106.714118.png 1341840106.714142 depth/1341840106.714142.png +1341840106.746220 rgb/1341840106.746220.png 1341840106.746247 depth/1341840106.746247.png +1341840106.782115 rgb/1341840106.782115.png 1341840106.782124 depth/1341840106.782124.png +1341840106.850141 rgb/1341840106.850141.png 1341840106.850154 depth/1341840106.850154.png +1341840106.882047 rgb/1341840106.882047.png 1341840106.882070 depth/1341840106.882070.png +1341840106.914130 rgb/1341840106.914130.png 1341840106.914158 depth/1341840106.914158.png +1341840106.950035 rgb/1341840106.950035.png 1341840106.950094 depth/1341840106.950094.png +1341840106.982620 rgb/1341840106.982620.png 1341840106.982646 depth/1341840106.982646.png +1341840107.014116 rgb/1341840107.014116.png 1341840107.014127 depth/1341840107.014127.png +1341840107.050043 rgb/1341840107.050043.png 1341840107.050122 depth/1341840107.050122.png +1341840107.082017 rgb/1341840107.082017.png 1341840107.082034 depth/1341840107.082034.png +1341840107.118150 rgb/1341840107.118150.png 1341840107.118166 depth/1341840107.118166.png +1341840107.150055 rgb/1341840107.150055.png 1341840107.150091 depth/1341840107.150091.png +1341840107.182063 rgb/1341840107.182063.png 1341840107.182075 depth/1341840107.182075.png +1341840107.218011 rgb/1341840107.218011.png 1341840107.218027 depth/1341840107.218027.png +1341840107.250000 rgb/1341840107.250000.png 1341840107.250013 depth/1341840107.250013.png +1341840107.285924 rgb/1341840107.285924.png 1341840107.285937 depth/1341840107.285937.png +1341840107.318019 rgb/1341840107.318019.png 1341840107.318611 depth/1341840107.318611.png +1341840107.350008 rgb/1341840107.350008.png 1341840107.350020 depth/1341840107.350020.png +1341840107.386092 rgb/1341840107.386092.png 1341840107.386114 depth/1341840107.386114.png +1341840107.417975 rgb/1341840107.417975.png 1341840107.417982 depth/1341840107.417982.png +1341840107.449982 rgb/1341840107.449982.png 1341840107.449991 depth/1341840107.449991.png +1341840107.486069 rgb/1341840107.486069.png 1341840107.486084 depth/1341840107.486084.png +1341840107.518019 rgb/1341840107.518019.png 1341840107.518034 depth/1341840107.518034.png +1341840107.554169 rgb/1341840107.554169.png 1341840107.554183 depth/1341840107.554183.png +1341840107.586166 rgb/1341840107.586166.png 1341840107.586184 depth/1341840107.586184.png +1341840107.617978 rgb/1341840107.617978.png 1341840107.617986 depth/1341840107.617986.png +1341840107.653971 rgb/1341840107.653971.png 1341840107.653995 depth/1341840107.653995.png +1341840107.686007 rgb/1341840107.686007.png 1341840107.686017 depth/1341840107.686017.png +1341840107.729301 rgb/1341840107.729301.png 1341840107.729356 depth/1341840107.729356.png +1341840107.786076 rgb/1341840107.786076.png 1341840107.786087 depth/1341840107.786087.png +1341840107.821949 rgb/1341840107.821949.png 1341840107.821956 depth/1341840107.821956.png +1341840107.854138 rgb/1341840107.854138.png 1341840107.854153 depth/1341840107.854153.png +1341840107.886102 rgb/1341840107.886102.png 1341840107.886106 depth/1341840107.886106.png +1341840107.922085 rgb/1341840107.922085.png 1341840107.922094 depth/1341840107.922094.png +1341840107.954044 rgb/1341840107.954044.png 1341840107.954056 depth/1341840107.954056.png +1341840107.986084 rgb/1341840107.986084.png 1341840107.986114 depth/1341840107.986114.png +1341840108.022288 rgb/1341840108.022288.png 1341840108.022344 depth/1341840108.022344.png +1341840108.053986 rgb/1341840108.053986.png 1341840108.054035 depth/1341840108.054035.png +1341840108.090178 rgb/1341840108.090178.png 1341840108.090194 depth/1341840108.090194.png +1341840108.121965 rgb/1341840108.121965.png 1341840108.121987 depth/1341840108.121987.png +1341840108.154224 rgb/1341840108.154224.png 1341840108.154238 depth/1341840108.154238.png +1341840108.190019 rgb/1341840108.190019.png 1341840108.190038 depth/1341840108.190038.png +1341840108.261441 rgb/1341840108.261441.png 1341840108.261025 depth/1341840108.261025.png +1341840108.322086 rgb/1341840108.322086.png 1341840108.322125 depth/1341840108.322125.png +1341840108.357889 rgb/1341840108.357889.png 1341840108.358002 depth/1341840108.358002.png +1341840108.390032 rgb/1341840108.390032.png 1341840108.390113 depth/1341840108.390113.png +1341840108.421993 rgb/1341840108.421993.png 1341840108.422033 depth/1341840108.422033.png +1341840108.457962 rgb/1341840108.457962.png 1341840108.458413 depth/1341840108.458413.png +1341840108.490057 rgb/1341840108.490057.png 1341840108.490082 depth/1341840108.490082.png +1341840108.526066 rgb/1341840108.526066.png 1341840108.526639 depth/1341840108.526639.png +1341840108.557923 rgb/1341840108.557923.png 1341840108.558246 depth/1341840108.558246.png +1341840108.590163 rgb/1341840108.590163.png 1341840108.590179 depth/1341840108.590179.png +1341840108.626046 rgb/1341840108.626046.png 1341840108.626062 depth/1341840108.626062.png +1341840108.658238 rgb/1341840108.658238.png 1341840108.658271 depth/1341840108.658271.png +1341840108.690101 rgb/1341840108.690101.png 1341840108.690117 depth/1341840108.690117.png +1341840108.726162 rgb/1341840108.726162.png 1341840108.726181 depth/1341840108.726181.png +1341840108.758020 rgb/1341840108.758020.png 1341840108.758036 depth/1341840108.758036.png +1341840108.794146 rgb/1341840108.794146.png 1341840108.794164 depth/1341840108.794164.png +1341840108.826126 rgb/1341840108.826126.png 1341840108.826190 depth/1341840108.826190.png +1341840108.858063 rgb/1341840108.858063.png 1341840108.858083 depth/1341840108.858083.png +1341840108.894068 rgb/1341840108.894068.png 1341840108.894124 depth/1341840108.894124.png +1341840108.926397 rgb/1341840108.926397.png 1341840108.926413 depth/1341840108.926413.png +1341840108.958169 rgb/1341840108.958169.png 1341840108.958823 depth/1341840108.958823.png +1341840108.994061 rgb/1341840108.994061.png 1341840108.994089 depth/1341840108.994089.png +1341840109.026028 rgb/1341840109.026028.png 1341840109.026041 depth/1341840109.026041.png +1341840109.062055 rgb/1341840109.062055.png 1341840109.062328 depth/1341840109.062328.png +1341840109.094102 rgb/1341840109.094102.png 1341840109.094119 depth/1341840109.094119.png +1341840109.126125 rgb/1341840109.126125.png 1341840109.126711 depth/1341840109.126711.png +1341840109.162091 rgb/1341840109.162091.png 1341840109.162308 depth/1341840109.162308.png +1341840109.194070 rgb/1341840109.194070.png 1341840109.194094 depth/1341840109.194094.png +1341840109.226207 rgb/1341840109.226207.png 1341840109.226255 depth/1341840109.226255.png +1341840109.261949 rgb/1341840109.261949.png 1341840109.261966 depth/1341840109.261966.png +1341840109.294245 rgb/1341840109.294245.png 1341840109.294307 depth/1341840109.294307.png +1341840109.330048 rgb/1341840109.330048.png 1341840109.330064 depth/1341840109.330064.png +1341840109.361934 rgb/1341840109.361934.png 1341840109.362040 depth/1341840109.362040.png +1341840109.394174 rgb/1341840109.394174.png 1341840109.394201 depth/1341840109.394201.png +1341840109.430078 rgb/1341840109.430078.png 1341840109.430157 depth/1341840109.430157.png +1341840109.469199 rgb/1341840109.469199.png 1341840109.462169 depth/1341840109.462169.png +1341840109.530025 rgb/1341840109.530025.png 1341840109.530055 depth/1341840109.530055.png +1341840109.562227 rgb/1341840109.562227.png 1341840109.562279 depth/1341840109.562279.png +1341840109.598096 rgb/1341840109.598096.png 1341840109.598170 depth/1341840109.598170.png +1341840109.630157 rgb/1341840109.630157.png 1341840109.630179 depth/1341840109.630179.png +1341840109.662301 rgb/1341840109.662301.png 1341840109.662969 depth/1341840109.662969.png +1341840109.698028 rgb/1341840109.698028.png 1341840109.698631 depth/1341840109.698631.png +1341840109.730942 rgb/1341840109.730942.png 1341840109.731228 depth/1341840109.731228.png +1341840109.765996 rgb/1341840109.765996.png 1341840109.766007 depth/1341840109.766007.png +1341840109.797984 rgb/1341840109.797984.png 1341840109.798067 depth/1341840109.798067.png +1341840109.830020 rgb/1341840109.830020.png 1341840109.830035 depth/1341840109.830035.png +1341840109.866117 rgb/1341840109.866117.png 1341840109.866161 depth/1341840109.866161.png +1341840109.898432 rgb/1341840109.898432.png 1341840109.898450 depth/1341840109.898450.png +1341840109.930018 rgb/1341840109.930018.png 1341840109.930029 depth/1341840109.930029.png +1341840109.966093 rgb/1341840109.966093.png 1341840109.966125 depth/1341840109.966125.png +1341840109.998090 rgb/1341840109.998090.png 1341840109.998101 depth/1341840109.998101.png +1341840110.033947 rgb/1341840110.033947.png 1341840110.034074 depth/1341840110.034074.png +1341840110.066047 rgb/1341840110.066047.png 1341840110.066138 depth/1341840110.066138.png +1341840110.097995 rgb/1341840110.097995.png 1341840110.098013 depth/1341840110.098013.png +1341840110.134023 rgb/1341840110.134023.png 1341840110.134041 depth/1341840110.134041.png +1341840110.166206 rgb/1341840110.166206.png 1341840110.166222 depth/1341840110.166222.png +1341840110.198574 rgb/1341840110.198574.png 1341840110.198590 depth/1341840110.198590.png +1341840110.234162 rgb/1341840110.234162.png 1341840110.234667 depth/1341840110.234667.png +1341840110.266480 rgb/1341840110.266480.png 1341840110.266678 depth/1341840110.266678.png +1341840110.302180 rgb/1341840110.302180.png 1341840110.302244 depth/1341840110.302244.png +1341840110.334151 rgb/1341840110.334151.png 1341840110.334615 depth/1341840110.334615.png +1341840110.366041 rgb/1341840110.366041.png 1341840110.366053 depth/1341840110.366053.png +1341840110.402014 rgb/1341840110.402014.png 1341840110.402031 depth/1341840110.402031.png +1341840110.470485 rgb/1341840110.470485.png 1341840110.472693 depth/1341840110.472693.png +1341840110.502611 rgb/1341840110.502611.png 1341840110.503531 depth/1341840110.503531.png +1341840110.534716 rgb/1341840110.534716.png 1341840110.536123 depth/1341840110.536123.png +1341840110.570160 rgb/1341840110.570160.png 1341840110.570919 depth/1341840110.570919.png +1341840110.602152 rgb/1341840110.602152.png 1341840110.602365 depth/1341840110.602365.png +1341840110.634164 rgb/1341840110.634164.png 1341840110.634751 depth/1341840110.634751.png +1341840110.670463 rgb/1341840110.670463.png 1341840110.670637 depth/1341840110.670637.png +1341840110.702156 rgb/1341840110.702156.png 1341840110.702179 depth/1341840110.702179.png +1341840110.770055 rgb/1341840110.770055.png 1341840110.770092 depth/1341840110.770092.png +1341840110.802298 rgb/1341840110.802298.png 1341840110.802309 depth/1341840110.802309.png +1341840110.838159 rgb/1341840110.838159.png 1341840110.838176 depth/1341840110.838176.png +1341840110.870149 rgb/1341840110.870149.png 1341840110.870187 depth/1341840110.870187.png +1341840110.902063 rgb/1341840110.902063.png 1341840110.902118 depth/1341840110.902118.png +1341840110.938225 rgb/1341840110.938225.png 1341840110.938260 depth/1341840110.938260.png +1341840110.970039 rgb/1341840110.970039.png 1341840110.970062 depth/1341840110.970062.png +1341840111.005980 rgb/1341840111.005980.png 1341840111.006001 depth/1341840111.006001.png +1341840111.038080 rgb/1341840111.038080.png 1341840111.038096 depth/1341840111.038096.png +1341840111.070094 rgb/1341840111.070094.png 1341840111.070109 depth/1341840111.070109.png +1341840111.106101 rgb/1341840111.106101.png 1341840111.106139 depth/1341840111.106139.png +1341840111.138254 rgb/1341840111.138254.png 1341840111.138295 depth/1341840111.138295.png +1341840111.170017 rgb/1341840111.170017.png 1341840111.170029 depth/1341840111.170029.png +1341840111.206027 rgb/1341840111.206027.png 1341840111.206039 depth/1341840111.206039.png +1341840111.238002 rgb/1341840111.238002.png 1341840111.238557 depth/1341840111.238557.png +1341840111.273886 rgb/1341840111.273886.png 1341840111.273894 depth/1341840111.273894.png +1341840111.306061 rgb/1341840111.306061.png 1341840111.306112 depth/1341840111.306112.png +1341840111.338594 rgb/1341840111.338594.png 1341840111.338609 depth/1341840111.338609.png +1341840111.374364 rgb/1341840111.374364.png 1341840111.374382 depth/1341840111.374382.png +1341840111.406608 rgb/1341840111.406608.png 1341840111.407733 depth/1341840111.407733.png +1341840111.438543 rgb/1341840111.438543.png 1341840111.439296 depth/1341840111.439296.png +1341840111.474308 rgb/1341840111.474308.png 1341840111.474993 depth/1341840111.474993.png +1341840111.506766 rgb/1341840111.506766.png 1341840111.507751 depth/1341840111.507751.png +1341840111.542350 rgb/1341840111.542350.png 1341840111.542391 depth/1341840111.542391.png +1341840111.574318 rgb/1341840111.574318.png 1341840111.574347 depth/1341840111.574347.png +1341840111.613190 rgb/1341840111.613190.png 1341840111.613256 depth/1341840111.613256.png +1341840111.674414 rgb/1341840111.674414.png 1341840111.674437 depth/1341840111.674437.png +1341840111.709993 rgb/1341840111.709993.png 1341840111.710021 depth/1341840111.710021.png +1341840111.742130 rgb/1341840111.742130.png 1341840111.742144 depth/1341840111.742144.png +1341840111.773977 rgb/1341840111.773977.png 1341840111.773991 depth/1341840111.773991.png +1341840111.810090 rgb/1341840111.810090.png 1341840111.810108 depth/1341840111.810108.png +1341840111.842092 rgb/1341840111.842092.png 1341840111.842134 depth/1341840111.842134.png +1341840111.873912 rgb/1341840111.873912.png 1341840111.873921 depth/1341840111.873921.png +1341840111.910077 rgb/1341840111.910077.png 1341840111.910090 depth/1341840111.910090.png +1341840111.942341 rgb/1341840111.942341.png 1341840111.942369 depth/1341840111.942369.png +1341840111.978065 rgb/1341840111.978065.png 1341840111.978106 depth/1341840111.978106.png +1341840112.010079 rgb/1341840112.010079.png 1341840112.010095 depth/1341840112.010095.png +1341840112.042150 rgb/1341840112.042150.png 1341840112.042218 depth/1341840112.042218.png +1341840112.078049 rgb/1341840112.078049.png 1341840112.078058 depth/1341840112.078058.png +1341840112.110041 rgb/1341840112.110041.png 1341840112.110157 depth/1341840112.110157.png +1341840112.142067 rgb/1341840112.142067.png 1341840112.142076 depth/1341840112.142076.png +1341840112.178152 rgb/1341840112.178152.png 1341840112.178164 depth/1341840112.178164.png +1341840112.210048 rgb/1341840112.210048.png 1341840112.210086 depth/1341840112.210086.png +1341840112.246294 rgb/1341840112.246294.png 1341840112.246301 depth/1341840112.246301.png +1341840112.277978 rgb/1341840112.277978.png 1341840112.278021 depth/1341840112.278021.png +1341840112.309992 rgb/1341840112.309992.png 1341840112.310053 depth/1341840112.310053.png +1341840112.346126 rgb/1341840112.346126.png 1341840112.346171 depth/1341840112.346171.png +1341840112.378084 rgb/1341840112.378084.png 1341840112.378130 depth/1341840112.378130.png +1341840112.410156 rgb/1341840112.410156.png 1341840112.410164 depth/1341840112.410164.png +1341840112.445961 rgb/1341840112.445961.png 1341840112.445989 depth/1341840112.445989.png +1341840112.478095 rgb/1341840112.478095.png 1341840112.478125 depth/1341840112.478125.png +1341840112.513947 rgb/1341840112.513947.png 1341840112.513958 depth/1341840112.513958.png +1341840112.545959 rgb/1341840112.545959.png 1341840112.545974 depth/1341840112.545974.png +1341840112.578001 rgb/1341840112.578001.png 1341840112.578013 depth/1341840112.578013.png +1341840112.614023 rgb/1341840112.614023.png 1341840112.614038 depth/1341840112.614038.png +1341840112.646225 rgb/1341840112.646225.png 1341840112.646240 depth/1341840112.646240.png +1341840112.681967 rgb/1341840112.681967.png 1341840112.681983 depth/1341840112.681983.png +1341840112.714010 rgb/1341840112.714010.png 1341840112.714023 depth/1341840112.714023.png +1341840112.746326 rgb/1341840112.746326.png 1341840112.746338 depth/1341840112.746338.png +1341840112.782069 rgb/1341840112.782069.png 1341840112.782089 depth/1341840112.782089.png +1341840112.814160 rgb/1341840112.814160.png 1341840112.814206 depth/1341840112.814206.png +1341840112.846100 rgb/1341840112.846100.png 1341840112.846112 depth/1341840112.846112.png +1341840112.881998 rgb/1341840112.881998.png 1341840112.882008 depth/1341840112.882008.png +1341840112.915647 rgb/1341840112.915647.png 1341840112.917185 depth/1341840112.917185.png +1341840112.950108 rgb/1341840112.950108.png 1341840112.950126 depth/1341840112.950126.png +1341840112.982027 rgb/1341840112.982027.png 1341840112.982051 depth/1341840112.982051.png +1341840113.014038 rgb/1341840113.014038.png 1341840113.014050 depth/1341840113.014050.png +1341840113.050041 rgb/1341840113.050041.png 1341840113.050068 depth/1341840113.050068.png +1341840113.083545 rgb/1341840113.083545.png 1341840113.083560 depth/1341840113.083560.png +1341840113.114465 rgb/1341840113.114465.png 1341840113.114477 depth/1341840113.114477.png +1341840113.149964 rgb/1341840113.149964.png 1341840113.149974 depth/1341840113.149974.png +1341840113.182423 rgb/1341840113.182423.png 1341840113.182446 depth/1341840113.182446.png +1341840113.218045 rgb/1341840113.218045.png 1341840113.218066 depth/1341840113.218066.png +1341840113.250148 rgb/1341840113.250148.png 1341840113.250165 depth/1341840113.250165.png +1341840113.318091 rgb/1341840113.318091.png 1341840113.318111 depth/1341840113.318111.png +1341840113.350264 rgb/1341840113.350264.png 1341840113.350683 depth/1341840113.350683.png +1341840113.382237 rgb/1341840113.382237.png 1341840113.382278 depth/1341840113.382278.png +1341840113.418402 rgb/1341840113.418402.png 1341840113.419275 depth/1341840113.419275.png +1341840113.450286 rgb/1341840113.450286.png 1341840113.450963 depth/1341840113.450963.png +1341840113.486223 rgb/1341840113.486223.png 1341840113.486239 depth/1341840113.486239.png +1341840113.518124 rgb/1341840113.518124.png 1341840113.518650 depth/1341840113.518650.png +1341840113.549959 rgb/1341840113.549959.png 1341840113.550067 depth/1341840113.550067.png +1341840113.586112 rgb/1341840113.586112.png 1341840113.586131 depth/1341840113.586131.png +1341840113.618061 rgb/1341840113.618061.png 1341840113.618088 depth/1341840113.618088.png +1341840113.650118 rgb/1341840113.650118.png 1341840113.650140 depth/1341840113.650140.png +1341840113.686008 rgb/1341840113.686008.png 1341840113.686022 depth/1341840113.686022.png +1341840113.718115 rgb/1341840113.718115.png 1341840113.718800 depth/1341840113.718800.png +1341840113.754016 rgb/1341840113.754016.png 1341840113.754030 depth/1341840113.754030.png +1341840113.786025 rgb/1341840113.786025.png 1341840113.786057 depth/1341840113.786057.png +1341840113.817959 rgb/1341840113.817959.png 1341840113.817982 depth/1341840113.817982.png +1341840113.854018 rgb/1341840113.854018.png 1341840113.854029 depth/1341840113.854029.png +1341840113.886031 rgb/1341840113.886031.png 1341840113.886217 depth/1341840113.886217.png +1341840113.922094 rgb/1341840113.922094.png 1341840113.922108 depth/1341840113.922108.png +1341840113.954013 rgb/1341840113.954013.png 1341840113.954028 depth/1341840113.954028.png +1341840113.986274 rgb/1341840113.986274.png 1341840113.986297 depth/1341840113.986297.png +1341840114.022005 rgb/1341840114.022005.png 1341840114.022449 depth/1341840114.022449.png +1341840114.053984 rgb/1341840114.053984.png 1341840114.054054 depth/1341840114.054054.png +1341840114.086023 rgb/1341840114.086023.png 1341840114.086039 depth/1341840114.086039.png +1341840114.121956 rgb/1341840114.121956.png 1341840114.121978 depth/1341840114.121978.png +1341840114.154055 rgb/1341840114.154055.png 1341840114.154076 depth/1341840114.154076.png +1341840114.190000 rgb/1341840114.190000.png 1341840114.190040 depth/1341840114.190040.png +1341840114.221986 rgb/1341840114.221986.png 1341840114.222013 depth/1341840114.222013.png +1341840114.254034 rgb/1341840114.254034.png 1341840114.254048 depth/1341840114.254048.png +1341840114.290001 rgb/1341840114.290001.png 1341840114.290014 depth/1341840114.290014.png +1341840114.321974 rgb/1341840114.321974.png 1341840114.321983 depth/1341840114.321983.png +1341840114.354115 rgb/1341840114.354115.png 1341840114.354147 depth/1341840114.354147.png +1341840114.390037 rgb/1341840114.390037.png 1341840114.390050 depth/1341840114.390050.png +1341840114.422302 rgb/1341840114.422302.png 1341840114.422416 depth/1341840114.422416.png +1341840114.460071 rgb/1341840114.460071.png 1341840114.460211 depth/1341840114.460211.png +1341840114.490552 rgb/1341840114.490552.png 1341840114.495978 depth/1341840114.495978.png +1341840114.558044 rgb/1341840114.558044.png 1341840114.558075 depth/1341840114.558075.png +1341840114.590103 rgb/1341840114.590103.png 1341840114.590583 depth/1341840114.590583.png +1341840114.622076 rgb/1341840114.622076.png 1341840114.622561 depth/1341840114.622561.png +1341840114.658030 rgb/1341840114.658030.png 1341840114.658054 depth/1341840114.658054.png +1341840114.690158 rgb/1341840114.690158.png 1341840114.690203 depth/1341840114.690203.png +1341840114.726177 rgb/1341840114.726177.png 1341840114.726217 depth/1341840114.726217.png +1341840114.758034 rgb/1341840114.758034.png 1341840114.758058 depth/1341840114.758058.png +1341840114.790483 rgb/1341840114.790483.png 1341840114.790507 depth/1341840114.790507.png +1341840114.826102 rgb/1341840114.826102.png 1341840114.826121 depth/1341840114.826121.png +1341840114.858111 rgb/1341840114.858111.png 1341840114.858135 depth/1341840114.858135.png +1341840114.894167 rgb/1341840114.894167.png 1341840114.894191 depth/1341840114.894191.png +1341840114.926009 rgb/1341840114.926009.png 1341840114.926018 depth/1341840114.926018.png +1341840114.958011 rgb/1341840114.958011.png 1341840114.958019 depth/1341840114.958019.png +1341840114.994015 rgb/1341840114.994015.png 1341840114.994056 depth/1341840114.994056.png +1341840115.026016 rgb/1341840115.026016.png 1341840115.026049 depth/1341840115.026049.png +1341840115.058084 rgb/1341840115.058084.png 1341840115.058112 depth/1341840115.058112.png +1341840115.094064 rgb/1341840115.094064.png 1341840115.094107 depth/1341840115.094107.png +1341840115.126175 rgb/1341840115.126175.png 1341840115.126725 depth/1341840115.126725.png +1341840115.194102 rgb/1341840115.194102.png 1341840115.194156 depth/1341840115.194156.png +1341840115.226005 rgb/1341840115.226005.png 1341840115.226023 depth/1341840115.226023.png +1341840115.262383 rgb/1341840115.262383.png 1341840115.262402 depth/1341840115.262402.png +1341840115.293961 rgb/1341840115.293961.png 1341840115.293975 depth/1341840115.293975.png +1341840115.326039 rgb/1341840115.326039.png 1341840115.326062 depth/1341840115.326062.png +1341840115.362147 rgb/1341840115.362147.png 1341840115.362161 depth/1341840115.362161.png +1341840115.394572 rgb/1341840115.394572.png 1341840115.394598 depth/1341840115.394598.png +1341840115.430115 rgb/1341840115.430115.png 1341840115.430137 depth/1341840115.430137.png +1341840115.462047 rgb/1341840115.462047.png 1341840115.462065 depth/1341840115.462065.png +1341840115.494015 rgb/1341840115.494015.png 1341840115.494032 depth/1341840115.494032.png +1341840115.530138 rgb/1341840115.530138.png 1341840115.530149 depth/1341840115.530149.png +1341840115.562218 rgb/1341840115.562218.png 1341840115.562235 depth/1341840115.562235.png +1341840115.594030 rgb/1341840115.594030.png 1341840115.594042 depth/1341840115.594042.png +1341840115.630134 rgb/1341840115.630134.png 1341840115.630154 depth/1341840115.630154.png +1341840115.662297 rgb/1341840115.662297.png 1341840115.662353 depth/1341840115.662353.png +1341840115.697947 rgb/1341840115.697947.png 1341840115.697958 depth/1341840115.697958.png +1341840115.730048 rgb/1341840115.730048.png 1341840115.730139 depth/1341840115.730139.png +1341840115.762284 rgb/1341840115.762284.png 1341840115.762298 depth/1341840115.762298.png +1341840115.798161 rgb/1341840115.798161.png 1341840115.798198 depth/1341840115.798198.png +1341840115.830276 rgb/1341840115.830276.png 1341840115.830366 depth/1341840115.830366.png +1341840115.862429 rgb/1341840115.862429.png 1341840115.863042 depth/1341840115.863042.png +1341840115.898043 rgb/1341840115.898043.png 1341840115.898066 depth/1341840115.898066.png +1341840115.930014 rgb/1341840115.930014.png 1341840115.930493 depth/1341840115.930493.png +1341840115.966039 rgb/1341840115.966039.png 1341840115.966058 depth/1341840115.966058.png +1341840115.998143 rgb/1341840115.998143.png 1341840115.998912 depth/1341840115.998912.png +1341840116.030797 rgb/1341840116.030797.png 1341840116.030817 depth/1341840116.030817.png +1341840116.066094 rgb/1341840116.066094.png 1341840116.066113 depth/1341840116.066113.png +1341840116.098144 rgb/1341840116.098144.png 1341840116.098169 depth/1341840116.098169.png +1341840116.134127 rgb/1341840116.134127.png 1341840116.134153 depth/1341840116.134153.png +1341840116.166268 rgb/1341840116.166268.png 1341840116.166278 depth/1341840116.166278.png +1341840116.198124 rgb/1341840116.198124.png 1341840116.198152 depth/1341840116.198152.png +1341840116.233931 rgb/1341840116.233931.png 1341840116.233949 depth/1341840116.233949.png +1341840116.266106 rgb/1341840116.266106.png 1341840116.266124 depth/1341840116.266124.png +1341840116.298071 rgb/1341840116.298071.png 1341840116.298105 depth/1341840116.298105.png +1341840116.334029 rgb/1341840116.334029.png 1341840116.334046 depth/1341840116.334046.png +1341840116.366242 rgb/1341840116.366242.png 1341840116.366580 depth/1341840116.366580.png +1341840116.402086 rgb/1341840116.402086.png 1341840116.402630 depth/1341840116.402630.png +1341840116.434026 rgb/1341840116.434026.png 1341840116.434041 depth/1341840116.434041.png +1341840116.466551 rgb/1341840116.466551.png 1341840116.466574 depth/1341840116.466574.png +1341840116.502967 rgb/1341840116.502967.png 1341840116.503008 depth/1341840116.503008.png +1341840116.533901 rgb/1341840116.533901.png 1341840116.533922 depth/1341840116.533922.png +1341840116.566375 rgb/1341840116.566375.png 1341840116.566386 depth/1341840116.566386.png +1341840116.602212 rgb/1341840116.602212.png 1341840116.602848 depth/1341840116.602848.png +1341840116.633966 rgb/1341840116.633966.png 1341840116.633992 depth/1341840116.633992.png +1341840116.670108 rgb/1341840116.670108.png 1341840116.670388 depth/1341840116.670388.png +1341840116.702082 rgb/1341840116.702082.png 1341840116.702097 depth/1341840116.702097.png +1341840116.734125 rgb/1341840116.734125.png 1341840116.734166 depth/1341840116.734166.png +1341840116.770235 rgb/1341840116.770235.png 1341840116.770248 depth/1341840116.770248.png +1341840116.801991 rgb/1341840116.801991.png 1341840116.802014 depth/1341840116.802014.png +1341840116.833908 rgb/1341840116.833908.png 1341840116.833922 depth/1341840116.833922.png +1341840116.870683 rgb/1341840116.870683.png 1341840116.871096 depth/1341840116.871096.png +1341840116.902041 rgb/1341840116.902041.png 1341840116.902061 depth/1341840116.902061.png +1341840116.938059 rgb/1341840116.938059.png 1341840116.938101 depth/1341840116.938101.png +1341840116.970263 rgb/1341840116.970263.png 1341840116.970662 depth/1341840116.970662.png +1341840117.002191 rgb/1341840117.002191.png 1341840117.002207 depth/1341840117.002207.png +1341840117.037960 rgb/1341840117.037960.png 1341840117.037967 depth/1341840117.037967.png +1341840117.070071 rgb/1341840117.070071.png 1341840117.070096 depth/1341840117.070096.png +1341840117.106010 rgb/1341840117.106010.png 1341840117.106024 depth/1341840117.106024.png +1341840117.137909 rgb/1341840117.137909.png 1341840117.137958 depth/1341840117.137958.png +1341840117.170059 rgb/1341840117.170059.png 1341840117.170091 depth/1341840117.170091.png +1341840117.206013 rgb/1341840117.206013.png 1341840117.206026 depth/1341840117.206026.png +1341840117.238051 rgb/1341840117.238051.png 1341840117.238075 depth/1341840117.238075.png +1341840117.270206 rgb/1341840117.270206.png 1341840117.270354 depth/1341840117.270354.png +1341840117.305935 rgb/1341840117.305935.png 1341840117.305972 depth/1341840117.305972.png +1341840117.338033 rgb/1341840117.338033.png 1341840117.338052 depth/1341840117.338052.png +1341840117.374113 rgb/1341840117.374113.png 1341840117.374135 depth/1341840117.374135.png +1341840117.406128 rgb/1341840117.406128.png 1341840117.406387 depth/1341840117.406387.png +1341840117.438051 rgb/1341840117.438051.png 1341840117.438071 depth/1341840117.438071.png +1341840117.474143 rgb/1341840117.474143.png 1341840117.474611 depth/1341840117.474611.png +1341840117.505963 rgb/1341840117.505963.png 1341840117.505989 depth/1341840117.505989.png +1341840117.538068 rgb/1341840117.538068.png 1341840117.538092 depth/1341840117.538092.png +1341840117.574066 rgb/1341840117.574066.png 1341840117.574087 depth/1341840117.574087.png +1341840117.606013 rgb/1341840117.606013.png 1341840117.606029 depth/1341840117.606029.png +1341840117.674073 rgb/1341840117.674073.png 1341840117.674105 depth/1341840117.674105.png +1341840117.706154 rgb/1341840117.706154.png 1341840117.706177 depth/1341840117.706177.png +1341840117.741982 rgb/1341840117.741982.png 1341840117.742013 depth/1341840117.742013.png +1341840117.774097 rgb/1341840117.774097.png 1341840117.774113 depth/1341840117.774113.png +1341840117.806044 rgb/1341840117.806044.png 1341840117.806432 depth/1341840117.806432.png +1341840117.842093 rgb/1341840117.842093.png 1341840117.842112 depth/1341840117.842112.png +1341840117.874196 rgb/1341840117.874196.png 1341840117.874761 depth/1341840117.874761.png +1341840117.910030 rgb/1341840117.910030.png 1341840117.910164 depth/1341840117.910164.png +1341840117.942079 rgb/1341840117.942079.png 1341840117.942099 depth/1341840117.942099.png +1341840117.974032 rgb/1341840117.974032.png 1341840117.974076 depth/1341840117.974076.png +1341840118.010490 rgb/1341840118.010490.png 1341840118.010519 depth/1341840118.010519.png +1341840118.042067 rgb/1341840118.042067.png 1341840118.042081 depth/1341840118.042081.png +1341840118.074033 rgb/1341840118.074033.png 1341840118.074047 depth/1341840118.074047.png +1341840118.110207 rgb/1341840118.110207.png 1341840118.110221 depth/1341840118.110221.png +1341840118.141981 rgb/1341840118.141981.png 1341840118.141994 depth/1341840118.141994.png +1341840118.177996 rgb/1341840118.177996.png 1341840118.178010 depth/1341840118.178010.png +1341840118.210011 rgb/1341840118.210011.png 1341840118.210024 depth/1341840118.210024.png +1341840118.242035 rgb/1341840118.242035.png 1341840118.242049 depth/1341840118.242049.png +1341840118.277926 rgb/1341840118.277926.png 1341840118.277958 depth/1341840118.277958.png +1341840118.310137 rgb/1341840118.310137.png 1341840118.310156 depth/1341840118.310156.png +1341840118.345974 rgb/1341840118.345974.png 1341840118.345988 depth/1341840118.345988.png +1341840118.378027 rgb/1341840118.378027.png 1341840118.378048 depth/1341840118.378048.png +1341840118.410576 rgb/1341840118.410576.png 1341840118.410599 depth/1341840118.410599.png +1341840118.445989 rgb/1341840118.445989.png 1341840118.446042 depth/1341840118.446042.png +1341840118.478134 rgb/1341840118.478134.png 1341840118.478688 depth/1341840118.478688.png +1341840118.509967 rgb/1341840118.509967.png 1341840118.509981 depth/1341840118.509981.png +1341840118.546004 rgb/1341840118.546004.png 1341840118.546016 depth/1341840118.546016.png +1341840118.578056 rgb/1341840118.578056.png 1341840118.578073 depth/1341840118.578073.png +1341840118.614294 rgb/1341840118.614294.png 1341840118.614306 depth/1341840118.614306.png +1341840118.646073 rgb/1341840118.646073.png 1341840118.646095 depth/1341840118.646095.png +1341840118.678010 rgb/1341840118.678010.png 1341840118.678029 depth/1341840118.678029.png +1341840118.714097 rgb/1341840118.714097.png 1341840118.714133 depth/1341840118.714133.png +1341840118.745958 rgb/1341840118.745958.png 1341840118.745980 depth/1341840118.745980.png +1341840118.778020 rgb/1341840118.778020.png 1341840118.778084 depth/1341840118.778084.png +1341840118.814024 rgb/1341840118.814024.png 1341840118.814061 depth/1341840118.814061.png +1341840118.846076 rgb/1341840118.846076.png 1341840118.846088 depth/1341840118.846088.png +1341840118.881984 rgb/1341840118.881984.png 1341840118.881994 depth/1341840118.881994.png +1341840118.914072 rgb/1341840118.914072.png 1341840118.914090 depth/1341840118.914090.png +1341840118.946098 rgb/1341840118.946098.png 1341840118.946110 depth/1341840118.946110.png +1341840118.981987 rgb/1341840118.981987.png 1341840118.982009 depth/1341840118.982009.png +1341840119.014028 rgb/1341840119.014028.png 1341840119.014077 depth/1341840119.014077.png +1341840119.047541 rgb/1341840119.047541.png 1341840119.047554 depth/1341840119.047554.png +1341840119.081995 rgb/1341840119.081995.png 1341840119.082005 depth/1341840119.082005.png +1341840119.114032 rgb/1341840119.114032.png 1341840119.114044 depth/1341840119.114044.png +1341840119.150161 rgb/1341840119.150161.png 1341840119.150181 depth/1341840119.150181.png +1341840119.182054 rgb/1341840119.182054.png 1341840119.182066 depth/1341840119.182066.png +1341840119.214175 rgb/1341840119.214175.png 1341840119.214190 depth/1341840119.214190.png +1341840119.250205 rgb/1341840119.250205.png 1341840119.250217 depth/1341840119.250217.png +1341840119.282047 rgb/1341840119.282047.png 1341840119.282093 depth/1341840119.282093.png +1341840119.318007 rgb/1341840119.318007.png 1341840119.318047 depth/1341840119.318047.png +1341840119.350004 rgb/1341840119.350004.png 1341840119.350146 depth/1341840119.350146.png +1341840119.382084 rgb/1341840119.382084.png 1341840119.382117 depth/1341840119.382117.png +1341840119.418013 rgb/1341840119.418013.png 1341840119.418027 depth/1341840119.418027.png +1341840119.450007 rgb/1341840119.450007.png 1341840119.450087 depth/1341840119.450087.png +1341840119.482124 rgb/1341840119.482124.png 1341840119.482130 depth/1341840119.482130.png +1341840119.517882 rgb/1341840119.517882.png 1341840119.517895 depth/1341840119.517895.png +1341840119.550445 rgb/1341840119.550445.png 1341840119.550679 depth/1341840119.550679.png +1341840119.585989 rgb/1341840119.585989.png 1341840119.586001 depth/1341840119.586001.png +1341840119.618119 rgb/1341840119.618119.png 1341840119.618134 depth/1341840119.618134.png +1341840119.650029 rgb/1341840119.650029.png 1341840119.650052 depth/1341840119.650052.png +1341840119.685955 rgb/1341840119.685955.png 1341840119.685992 depth/1341840119.685992.png +1341840119.717993 rgb/1341840119.717993.png 1341840119.718151 depth/1341840119.718151.png +1341840119.749971 rgb/1341840119.749971.png 1341840119.750486 depth/1341840119.750486.png +1341840119.785854 rgb/1341840119.785854.png 1341840119.785870 depth/1341840119.785870.png +1341840119.818057 rgb/1341840119.818057.png 1341840119.818075 depth/1341840119.818075.png +1341840119.854072 rgb/1341840119.854072.png 1341840119.854090 depth/1341840119.854090.png +1341840119.886031 rgb/1341840119.886031.png 1341840119.886047 depth/1341840119.886047.png +1341840119.918128 rgb/1341840119.918128.png 1341840119.918637 depth/1341840119.918637.png +1341840119.954060 rgb/1341840119.954060.png 1341840119.954093 depth/1341840119.954093.png +1341840119.985974 rgb/1341840119.985974.png 1341840119.986001 depth/1341840119.986001.png +1341840120.018010 rgb/1341840120.018010.png 1341840120.018024 depth/1341840120.018024.png +1341840120.054119 rgb/1341840120.054119.png 1341840120.054132 depth/1341840120.054132.png +1341840120.086075 rgb/1341840120.086075.png 1341840120.086103 depth/1341840120.086103.png +1341840120.122064 rgb/1341840120.122064.png 1341840120.122092 depth/1341840120.122092.png +1341840120.154113 rgb/1341840120.154113.png 1341840120.154169 depth/1341840120.154169.png +1341840120.186050 rgb/1341840120.186050.png 1341840120.186098 depth/1341840120.186098.png +1341840120.221992 rgb/1341840120.221992.png 1341840120.222004 depth/1341840120.222004.png +1341840120.253972 rgb/1341840120.253972.png 1341840120.254426 depth/1341840120.254426.png +1341840120.321993 rgb/1341840120.321993.png 1341840120.322026 depth/1341840120.322026.png +1341840120.354024 rgb/1341840120.354024.png 1341840120.354267 depth/1341840120.354267.png +1341840120.390099 rgb/1341840120.390099.png 1341840120.390141 depth/1341840120.390141.png +1341840120.422028 rgb/1341840120.422028.png 1341840120.422038 depth/1341840120.422038.png +1341840120.454080 rgb/1341840120.454080.png 1341840120.454155 depth/1341840120.454155.png +1341840120.490276 rgb/1341840120.490276.png 1341840120.490299 depth/1341840120.490299.png +1341840120.521961 rgb/1341840120.521961.png 1341840120.521976 depth/1341840120.521976.png +1341840120.558156 rgb/1341840120.558156.png 1341840120.558171 depth/1341840120.558171.png +1341840120.590257 rgb/1341840120.590257.png 1341840120.591136 depth/1341840120.591136.png +1341840120.622049 rgb/1341840120.622049.png 1341840120.622059 depth/1341840120.622059.png +1341840120.658127 rgb/1341840120.658127.png 1341840120.658161 depth/1341840120.658161.png +1341840120.690052 rgb/1341840120.690052.png 1341840120.690072 depth/1341840120.690072.png +1341840120.721967 rgb/1341840120.721967.png 1341840120.721976 depth/1341840120.721976.png +1341840120.758000 rgb/1341840120.758000.png 1341840120.758014 depth/1341840120.758014.png +1341840120.790096 rgb/1341840120.790096.png 1341840120.790119 depth/1341840120.790119.png +1341840120.826121 rgb/1341840120.826121.png 1341840120.826577 depth/1341840120.826577.png +1341840120.858069 rgb/1341840120.858069.png 1341840120.858672 depth/1341840120.858672.png +1341840120.890145 rgb/1341840120.890145.png 1341840120.890395 depth/1341840120.890395.png +1341840120.926172 rgb/1341840120.926172.png 1341840120.926196 depth/1341840120.926196.png +1341840120.958656 rgb/1341840120.958656.png 1341840120.958677 depth/1341840120.958677.png +1341840120.990146 rgb/1341840120.990146.png 1341840120.990247 depth/1341840120.990247.png +1341840121.026124 rgb/1341840121.026124.png 1341840121.026564 depth/1341840121.026564.png +1341840121.058185 rgb/1341840121.058185.png 1341840121.058219 depth/1341840121.058219.png +1341840121.093963 rgb/1341840121.093963.png 1341840121.093980 depth/1341840121.093980.png +1341840121.126130 rgb/1341840121.126130.png 1341840121.126157 depth/1341840121.126157.png +1341840121.158223 rgb/1341840121.158223.png 1341840121.158265 depth/1341840121.158265.png +1341840121.194041 rgb/1341840121.194041.png 1341840121.194533 depth/1341840121.194533.png +1341840121.226164 rgb/1341840121.226164.png 1341840121.226180 depth/1341840121.226180.png +1341840121.258000 rgb/1341840121.258000.png 1341840121.258057 depth/1341840121.258057.png +1341840121.294019 rgb/1341840121.294019.png 1341840121.294402 depth/1341840121.294402.png +1341840121.326012 rgb/1341840121.326012.png 1341840121.326029 depth/1341840121.326029.png +1341840121.362069 rgb/1341840121.362069.png 1341840121.362087 depth/1341840121.362087.png +1341840121.394009 rgb/1341840121.394009.png 1341840121.394022 depth/1341840121.394022.png +1341840121.426047 rgb/1341840121.426047.png 1341840121.426064 depth/1341840121.426064.png +1341840121.461957 rgb/1341840121.461957.png 1341840121.461975 depth/1341840121.461975.png +1341840121.494017 rgb/1341840121.494017.png 1341840121.494027 depth/1341840121.494027.png +1341840121.529928 rgb/1341840121.529928.png 1341840121.529946 depth/1341840121.529946.png +1341840121.562141 rgb/1341840121.562141.png 1341840121.562592 depth/1341840121.562592.png +1341840121.594033 rgb/1341840121.594033.png 1341840121.594046 depth/1341840121.594046.png +1341840121.630041 rgb/1341840121.630041.png 1341840121.630056 depth/1341840121.630056.png +1341840121.661977 rgb/1341840121.661977.png 1341840121.661994 depth/1341840121.661994.png +1341840121.694095 rgb/1341840121.694095.png 1341840121.694120 depth/1341840121.694120.png +1341840121.730237 rgb/1341840121.730237.png 1341840121.730299 depth/1341840121.730299.png +1341840121.761997 rgb/1341840121.761997.png 1341840121.762013 depth/1341840121.762013.png +1341840121.797965 rgb/1341840121.797965.png 1341840121.797981 depth/1341840121.797981.png +1341840121.830074 rgb/1341840121.830074.png 1341840121.830131 depth/1341840121.830131.png +1341840121.862165 rgb/1341840121.862165.png 1341840121.862194 depth/1341840121.862194.png +1341840121.898013 rgb/1341840121.898013.png 1341840121.898031 depth/1341840121.898031.png +1341840121.929981 rgb/1341840121.929981.png 1341840121.929989 depth/1341840121.929989.png +1341840121.962086 rgb/1341840121.962086.png 1341840121.962099 depth/1341840121.962099.png +1341840121.998043 rgb/1341840121.998043.png 1341840121.998062 depth/1341840121.998062.png +1341840122.030127 rgb/1341840122.030127.png 1341840122.030150 depth/1341840122.030150.png +1341840122.066171 rgb/1341840122.066171.png 1341840122.066222 depth/1341840122.066222.png +1341840122.098009 rgb/1341840122.098009.png 1341840122.098035 depth/1341840122.098035.png +1341840122.130073 rgb/1341840122.130073.png 1341840122.130115 depth/1341840122.130115.png +1341840122.166332 rgb/1341840122.166332.png 1341840122.167639 depth/1341840122.167639.png +1341840122.198075 rgb/1341840122.198075.png 1341840122.198694 depth/1341840122.198694.png +1341840122.230015 rgb/1341840122.230015.png 1341840122.230053 depth/1341840122.230053.png +1341840122.266316 rgb/1341840122.266316.png 1341840122.266343 depth/1341840122.266343.png +1341840122.298110 rgb/1341840122.298110.png 1341840122.298128 depth/1341840122.298128.png +1341840122.333997 rgb/1341840122.333997.png 1341840122.334010 depth/1341840122.334010.png +1341840122.366219 rgb/1341840122.366219.png 1341840122.366241 depth/1341840122.366241.png +1341840122.398010 rgb/1341840122.398010.png 1341840122.398019 depth/1341840122.398019.png +1341840122.434144 rgb/1341840122.434144.png 1341840122.434167 depth/1341840122.434167.png +1341840122.466042 rgb/1341840122.466042.png 1341840122.466070 depth/1341840122.466070.png +1341840122.498098 rgb/1341840122.498098.png 1341840122.498115 depth/1341840122.498115.png +1341840122.534119 rgb/1341840122.534119.png 1341840122.534572 depth/1341840122.534572.png +1341840122.565936 rgb/1341840122.565936.png 1341840122.565950 depth/1341840122.565950.png +1341840122.602018 rgb/1341840122.602018.png 1341840122.602035 depth/1341840122.602035.png +1341840122.633950 rgb/1341840122.633950.png 1341840122.633966 depth/1341840122.633966.png +1341840122.665956 rgb/1341840122.665956.png 1341840122.665969 depth/1341840122.665969.png +1341840122.701957 rgb/1341840122.701957.png 1341840122.701967 depth/1341840122.701967.png +1341840122.734093 rgb/1341840122.734093.png 1341840122.734104 depth/1341840122.734104.png +1341840122.770044 rgb/1341840122.770044.png 1341840122.770082 depth/1341840122.770082.png +1341840122.801953 rgb/1341840122.801953.png 1341840122.801979 depth/1341840122.801979.png +1341840122.834016 rgb/1341840122.834016.png 1341840122.834281 depth/1341840122.834281.png +1341840122.870087 rgb/1341840122.870087.png 1341840122.870126 depth/1341840122.870126.png +1341840122.902065 rgb/1341840122.902065.png 1341840122.902090 depth/1341840122.902090.png +1341840122.934003 rgb/1341840122.934003.png 1341840122.934037 depth/1341840122.934037.png +1341840122.970017 rgb/1341840122.970017.png 1341840122.970042 depth/1341840122.970042.png +1341840123.002030 rgb/1341840123.002030.png 1341840123.002045 depth/1341840123.002045.png +1341840123.038065 rgb/1341840123.038065.png 1341840123.038492 depth/1341840123.038492.png +1341840123.070067 rgb/1341840123.070067.png 1341840123.070091 depth/1341840123.070091.png +1341840123.101997 rgb/1341840123.101997.png 1341840123.102017 depth/1341840123.102017.png +1341840123.138121 rgb/1341840123.138121.png 1341840123.138131 depth/1341840123.138131.png +1341840123.169973 rgb/1341840123.169973.png 1341840123.170014 depth/1341840123.170014.png +1341840123.202032 rgb/1341840123.202032.png 1341840123.202068 depth/1341840123.202068.png +1341840123.238122 rgb/1341840123.238122.png 1341840123.238144 depth/1341840123.238144.png +1341840123.269980 rgb/1341840123.269980.png 1341840123.270016 depth/1341840123.270016.png +1341840123.306046 rgb/1341840123.306046.png 1341840123.306136 depth/1341840123.306136.png +1341840123.338004 rgb/1341840123.338004.png 1341840123.338039 depth/1341840123.338039.png +1341840123.371486 rgb/1341840123.371486.png 1341840123.371531 depth/1341840123.371531.png +1341840123.405986 rgb/1341840123.405986.png 1341840123.406012 depth/1341840123.406012.png +1341840123.438009 rgb/1341840123.438009.png 1341840123.438079 depth/1341840123.438079.png +1341840123.470306 rgb/1341840123.470306.png 1341840123.470780 depth/1341840123.470780.png +1341840123.506015 rgb/1341840123.506015.png 1341840123.506039 depth/1341840123.506039.png +1341840123.538113 rgb/1341840123.538113.png 1341840123.538135 depth/1341840123.538135.png +1341840123.574039 rgb/1341840123.574039.png 1341840123.574128 depth/1341840123.574128.png +1341840123.606067 rgb/1341840123.606067.png 1341840123.606087 depth/1341840123.606087.png +1341840123.638023 rgb/1341840123.638023.png 1341840123.638057 depth/1341840123.638057.png +1341840123.673974 rgb/1341840123.673974.png 1341840123.673996 depth/1341840123.673996.png +1341840123.706010 rgb/1341840123.706010.png 1341840123.706032 depth/1341840123.706032.png +1341840123.742381 rgb/1341840123.742381.png 1341840123.742403 depth/1341840123.742403.png +1341840123.774005 rgb/1341840123.774005.png 1341840123.774086 depth/1341840123.774086.png +1341840123.806031 rgb/1341840123.806031.png 1341840123.806045 depth/1341840123.806045.png +1341840123.842043 rgb/1341840123.842043.png 1341840123.842090 depth/1341840123.842090.png +1341840123.874145 rgb/1341840123.874145.png 1341840123.874161 depth/1341840123.874161.png +1341840123.906504 rgb/1341840123.906504.png 1341840123.906514 depth/1341840123.906514.png +1341840123.942274 rgb/1341840123.942274.png 1341840123.942291 depth/1341840123.942291.png +1341840124.010110 rgb/1341840124.010110.png 1341840124.010160 depth/1341840124.010160.png +1341840124.042464 rgb/1341840124.042464.png 1341840124.043010 depth/1341840124.043010.png +1341840124.074278 rgb/1341840124.074278.png 1341840124.074296 depth/1341840124.074296.png +1341840124.109993 rgb/1341840124.109993.png 1341840124.110008 depth/1341840124.110008.png +1341840124.142030 rgb/1341840124.142030.png 1341840124.142044 depth/1341840124.142044.png +1341840124.174717 rgb/1341840124.174717.png 1341840124.174740 depth/1341840124.174740.png +1341840124.210207 rgb/1341840124.210207.png 1341840124.210236 depth/1341840124.210236.png +1341840124.242266 rgb/1341840124.242266.png 1341840124.242301 depth/1341840124.242301.png +1341840124.285051 rgb/1341840124.285051.png 1341840124.278228 depth/1341840124.278228.png +1341840124.342019 rgb/1341840124.342019.png 1341840124.342031 depth/1341840124.342031.png +1341840124.378312 rgb/1341840124.378312.png 1341840124.378334 depth/1341840124.378334.png +1341840124.409939 rgb/1341840124.409939.png 1341840124.409962 depth/1341840124.409962.png +1341840124.442443 rgb/1341840124.442443.png 1341840124.442467 depth/1341840124.442467.png +1341840124.478293 rgb/1341840124.478293.png 1341840124.478323 depth/1341840124.478323.png +1341840124.510263 rgb/1341840124.510263.png 1341840124.510280 depth/1341840124.510280.png +1341840124.546077 rgb/1341840124.546077.png 1341840124.546097 depth/1341840124.546097.png +1341840124.578141 rgb/1341840124.578141.png 1341840124.578153 depth/1341840124.578153.png +1341840124.610089 rgb/1341840124.610089.png 1341840124.610107 depth/1341840124.610107.png +1341840124.646060 rgb/1341840124.646060.png 1341840124.646074 depth/1341840124.646074.png +1341840124.678361 rgb/1341840124.678361.png 1341840124.678376 depth/1341840124.678376.png +1341840124.709971 rgb/1341840124.709971.png 1341840124.709981 depth/1341840124.709981.png +1341840124.745938 rgb/1341840124.745938.png 1341840124.745975 depth/1341840124.745975.png +1341840124.778181 rgb/1341840124.778181.png 1341840124.778194 depth/1341840124.778194.png +1341840124.814087 rgb/1341840124.814087.png 1341840124.814103 depth/1341840124.814103.png +1341840124.846010 rgb/1341840124.846010.png 1341840124.846022 depth/1341840124.846022.png +1341840124.878017 rgb/1341840124.878017.png 1341840124.878573 depth/1341840124.878573.png +1341840124.914181 rgb/1341840124.914181.png 1341840124.914192 depth/1341840124.914192.png +1341840124.946027 rgb/1341840124.946027.png 1341840124.946049 depth/1341840124.946049.png +1341840124.982274 rgb/1341840124.982274.png 1341840124.982298 depth/1341840124.982298.png +1341840125.014063 rgb/1341840125.014063.png 1341840125.014076 depth/1341840125.014076.png +1341840125.046039 rgb/1341840125.046039.png 1341840125.046047 depth/1341840125.046047.png +1341840125.082081 rgb/1341840125.082081.png 1341840125.082097 depth/1341840125.082097.png +1341840125.114038 rgb/1341840125.114038.png 1341840125.114059 depth/1341840125.114059.png +1341840125.146055 rgb/1341840125.146055.png 1341840125.146068 depth/1341840125.146068.png +1341840125.182012 rgb/1341840125.182012.png 1341840125.182027 depth/1341840125.182027.png +1341840125.213996 rgb/1341840125.213996.png 1341840125.214020 depth/1341840125.214020.png +1341840125.250210 rgb/1341840125.250210.png 1341840125.250727 depth/1341840125.250727.png +1341840125.282000 rgb/1341840125.282000.png 1341840125.282014 depth/1341840125.282014.png +1341840125.314051 rgb/1341840125.314051.png 1341840125.314062 depth/1341840125.314062.png +1341840125.349953 rgb/1341840125.349953.png 1341840125.349998 depth/1341840125.349998.png +1341840125.382384 rgb/1341840125.382384.png 1341840125.382396 depth/1341840125.382396.png +1341840125.414021 rgb/1341840125.414021.png 1341840125.414067 depth/1341840125.414067.png +1341840125.450150 rgb/1341840125.450150.png 1341840125.450391 depth/1341840125.450391.png +1341840125.481998 rgb/1341840125.481998.png 1341840125.482040 depth/1341840125.482040.png +1341840125.518104 rgb/1341840125.518104.png 1341840125.518141 depth/1341840125.518141.png +1341840125.549972 rgb/1341840125.549972.png 1341840125.549984 depth/1341840125.549984.png +1341840125.582199 rgb/1341840125.582199.png 1341840125.582983 depth/1341840125.582983.png +1341840125.618068 rgb/1341840125.618068.png 1341840125.618112 depth/1341840125.618112.png +1341840125.650128 rgb/1341840125.650128.png 1341840125.650147 depth/1341840125.650147.png +1341840125.682126 rgb/1341840125.682126.png 1341840125.682134 depth/1341840125.682134.png +1341840125.718114 rgb/1341840125.718114.png 1341840125.718135 depth/1341840125.718135.png +1341840125.750311 rgb/1341840125.750311.png 1341840125.750822 depth/1341840125.750822.png +1341840125.786063 rgb/1341840125.786063.png 1341840125.786077 depth/1341840125.786077.png +1341840125.818005 rgb/1341840125.818005.png 1341840125.818087 depth/1341840125.818087.png +1341840125.849992 rgb/1341840125.849992.png 1341840125.850680 depth/1341840125.850680.png +1341840125.886078 rgb/1341840125.886078.png 1341840125.886652 depth/1341840125.886652.png +1341840125.918028 rgb/1341840125.918028.png 1341840125.918081 depth/1341840125.918081.png +1341840125.954159 rgb/1341840125.954159.png 1341840125.954419 depth/1341840125.954419.png +1341840125.986005 rgb/1341840125.986005.png 1341840125.986014 depth/1341840125.986014.png +1341840126.017980 rgb/1341840126.017980.png 1341840126.017999 depth/1341840126.017999.png +1341840126.054159 rgb/1341840126.054159.png 1341840126.054224 depth/1341840126.054224.png +1341840126.086020 rgb/1341840126.086020.png 1341840126.086035 depth/1341840126.086035.png +1341840126.118088 rgb/1341840126.118088.png 1341840126.118113 depth/1341840126.118113.png +1341840126.154120 rgb/1341840126.154120.png 1341840126.154128 depth/1341840126.154128.png +1341840126.185970 rgb/1341840126.185970.png 1341840126.186028 depth/1341840126.186028.png +1341840126.222058 rgb/1341840126.222058.png 1341840126.222084 depth/1341840126.222084.png +1341840126.254004 rgb/1341840126.254004.png 1341840126.254026 depth/1341840126.254026.png +1341840126.286071 rgb/1341840126.286071.png 1341840126.286083 depth/1341840126.286083.png +1341840126.322149 rgb/1341840126.322149.png 1341840126.322175 depth/1341840126.322175.png +1341840126.386310 rgb/1341840126.386310.png 1341840126.386326 depth/1341840126.386326.png +1341840126.422058 rgb/1341840126.422058.png 1341840126.422081 depth/1341840126.422081.png +1341840126.454093 rgb/1341840126.454093.png 1341840126.454106 depth/1341840126.454106.png +1341840126.490075 rgb/1341840126.490075.png 1341840126.490164 depth/1341840126.490164.png +1341840126.522184 rgb/1341840126.522184.png 1341840126.522642 depth/1341840126.522642.png +1341840126.554439 rgb/1341840126.554439.png 1341840126.555196 depth/1341840126.555196.png +1341840126.590101 rgb/1341840126.590101.png 1341840126.590147 depth/1341840126.590147.png +1341840126.621967 rgb/1341840126.621967.png 1341840126.621994 depth/1341840126.621994.png +1341840126.654071 rgb/1341840126.654071.png 1341840126.654166 depth/1341840126.654166.png +1341840126.690108 rgb/1341840126.690108.png 1341840126.690146 depth/1341840126.690146.png +1341840126.722067 rgb/1341840126.722067.png 1341840126.722077 depth/1341840126.722077.png +1341840126.757975 rgb/1341840126.757975.png 1341840126.758022 depth/1341840126.758022.png +1341840126.789990 rgb/1341840126.789990.png 1341840126.790020 depth/1341840126.790020.png +1341840126.822091 rgb/1341840126.822091.png 1341840126.822110 depth/1341840126.822110.png +1341840126.858075 rgb/1341840126.858075.png 1341840126.858103 depth/1341840126.858103.png +1341840126.890140 rgb/1341840126.890140.png 1341840126.890162 depth/1341840126.890162.png +1341840126.922034 rgb/1341840126.922034.png 1341840126.922068 depth/1341840126.922068.png +1341840126.958061 rgb/1341840126.958061.png 1341840126.958085 depth/1341840126.958085.png +1341840126.990151 rgb/1341840126.990151.png 1341840126.990173 depth/1341840126.990173.png +1341840127.026266 rgb/1341840127.026266.png 1341840127.026290 depth/1341840127.026290.png +1341840127.057963 rgb/1341840127.057963.png 1341840127.058012 depth/1341840127.058012.png +1341840127.089960 rgb/1341840127.089960.png 1341840127.089983 depth/1341840127.089983.png +1341840127.126022 rgb/1341840127.126022.png 1341840127.126130 depth/1341840127.126130.png +1341840127.158030 rgb/1341840127.158030.png 1341840127.158042 depth/1341840127.158042.png +1341840127.194126 rgb/1341840127.194126.png 1341840127.194970 depth/1341840127.194970.png +1341840127.226060 rgb/1341840127.226060.png 1341840127.226089 depth/1341840127.226089.png +1341840127.258260 rgb/1341840127.258260.png 1341840127.258283 depth/1341840127.258283.png +1341840127.293947 rgb/1341840127.293947.png 1341840127.293974 depth/1341840127.293974.png +1341840127.326145 rgb/1341840127.326145.png 1341840127.326164 depth/1341840127.326164.png +1341840127.358234 rgb/1341840127.358234.png 1341840127.358245 depth/1341840127.358245.png +1341840127.394084 rgb/1341840127.394084.png 1341840127.394113 depth/1341840127.394113.png +1341840127.425972 rgb/1341840127.425972.png 1341840127.425999 depth/1341840127.425999.png +1341840127.462026 rgb/1341840127.462026.png 1341840127.462038 depth/1341840127.462038.png +1341840127.494010 rgb/1341840127.494010.png 1341840127.494031 depth/1341840127.494031.png +1341840127.525963 rgb/1341840127.525963.png 1341840127.526030 depth/1341840127.526030.png +1341840127.561982 rgb/1341840127.561982.png 1341840127.561995 depth/1341840127.561995.png +1341840127.594043 rgb/1341840127.594043.png 1341840127.594063 depth/1341840127.594063.png +1341840127.633074 rgb/1341840127.633074.png 1341840127.633089 depth/1341840127.633089.png +1341840127.669383 rgb/1341840127.669383.png 1341840127.670306 depth/1341840127.670306.png +1341840127.730023 rgb/1341840127.730023.png 1341840127.730060 depth/1341840127.730060.png +1341840127.761906 rgb/1341840127.761906.png 1341840127.761919 depth/1341840127.761919.png +1341840127.794112 rgb/1341840127.794112.png 1341840127.794176 depth/1341840127.794176.png +1341840127.830032 rgb/1341840127.830032.png 1341840127.830025 depth/1341840127.830025.png +1341840127.862267 rgb/1341840127.862267.png 1341840127.862782 depth/1341840127.862782.png +1341840127.894060 rgb/1341840127.894060.png 1341840127.894080 depth/1341840127.894080.png +1341840127.930010 rgb/1341840127.930010.png 1341840127.930028 depth/1341840127.930028.png +1341840127.962986 rgb/1341840127.962986.png 1341840127.963035 depth/1341840127.963035.png +1341840127.997999 rgb/1341840127.997999.png 1341840127.998008 depth/1341840127.998008.png +1341840128.030080 rgb/1341840128.030080.png 1341840128.030110 depth/1341840128.030110.png +1341840128.062052 rgb/1341840128.062052.png 1341840128.062062 depth/1341840128.062062.png +1341840128.098032 rgb/1341840128.098032.png 1341840128.098045 depth/1341840128.098045.png +1341840128.130013 rgb/1341840128.130013.png 1341840128.130022 depth/1341840128.130022.png +1341840128.165962 rgb/1341840128.165962.png 1341840128.165992 depth/1341840128.165992.png +1341840128.197950 rgb/1341840128.197950.png 1341840128.197965 depth/1341840128.197965.png +1341840128.230140 rgb/1341840128.230140.png 1341840128.230472 depth/1341840128.230472.png +1341840128.266032 rgb/1341840128.266032.png 1341840128.266045 depth/1341840128.266045.png +1341840128.298015 rgb/1341840128.298015.png 1341840128.298040 depth/1341840128.298040.png +1341840128.330055 rgb/1341840128.330055.png 1341840128.330076 depth/1341840128.330076.png +1341840128.366047 rgb/1341840128.366047.png 1341840128.366061 depth/1341840128.366061.png +1341840128.398051 rgb/1341840128.398051.png 1341840128.398089 depth/1341840128.398089.png +1341840128.434020 rgb/1341840128.434020.png 1341840128.434036 depth/1341840128.434036.png +1341840128.465958 rgb/1341840128.465958.png 1341840128.465974 depth/1341840128.465974.png +1341840128.498139 rgb/1341840128.498139.png 1341840128.498157 depth/1341840128.498157.png +1341840128.534077 rgb/1341840128.534077.png 1341840128.534594 depth/1341840128.534594.png +1341840128.565980 rgb/1341840128.565980.png 1341840128.566009 depth/1341840128.566009.png +1341840128.598334 rgb/1341840128.598334.png 1341840128.598351 depth/1341840128.598351.png +1341840128.634021 rgb/1341840128.634021.png 1341840128.634037 depth/1341840128.634037.png +1341840128.665994 rgb/1341840128.665994.png 1341840128.666029 depth/1341840128.666029.png +1341840128.702088 rgb/1341840128.702088.png 1341840128.702115 depth/1341840128.702115.png +1341840128.734647 rgb/1341840128.734647.png 1341840128.735108 depth/1341840128.735108.png +1341840128.766215 rgb/1341840128.766215.png 1341840128.766958 depth/1341840128.766958.png +1341840128.802328 rgb/1341840128.802328.png 1341840128.802350 depth/1341840128.802350.png +1341840128.834264 rgb/1341840128.834264.png 1341840128.834274 depth/1341840128.834274.png +1341840128.866076 rgb/1341840128.866076.png 1341840128.866101 depth/1341840128.866101.png +1341840128.902014 rgb/1341840128.902014.png 1341840128.902049 depth/1341840128.902049.png +1341840128.934198 rgb/1341840128.934198.png 1341840128.934221 depth/1341840128.934221.png +1341840128.973034 rgb/1341840128.973034.png 1341840128.973048 depth/1341840128.973048.png +1341840129.005075 rgb/1341840129.005075.png 1341840129.005172 depth/1341840129.005172.png +1341840129.041015 rgb/1341840129.041015.png 1341840129.041032 depth/1341840129.041032.png +1341840129.073071 rgb/1341840129.073071.png 1341840129.073096 depth/1341840129.073096.png +1341840129.109000 rgb/1341840129.109000.png 1341840129.109014 depth/1341840129.109014.png +1341840129.141032 rgb/1341840129.141032.png 1341840129.141083 depth/1341840129.141083.png +1341840129.173175 rgb/1341840129.173175.png 1341840129.173202 depth/1341840129.173202.png +1341840129.209154 rgb/1341840129.209154.png 1341840129.209650 depth/1341840129.209650.png +1341840129.240931 rgb/1341840129.240931.png 1341840129.241099 depth/1341840129.241099.png +1341840129.277050 rgb/1341840129.277050.png 1341840129.277063 depth/1341840129.277063.png +1341840129.309035 rgb/1341840129.309035.png 1341840129.309059 depth/1341840129.309059.png +1341840129.340958 rgb/1341840129.340958.png 1341840129.340979 depth/1341840129.340979.png +1341840129.377126 rgb/1341840129.377126.png 1341840129.377929 depth/1341840129.377929.png +1341840129.408991 rgb/1341840129.408991.png 1341840129.409020 depth/1341840129.409020.png +1341840129.445079 rgb/1341840129.445079.png 1341840129.445095 depth/1341840129.445095.png +1341840129.477129 rgb/1341840129.477129.png 1341840129.477146 depth/1341840129.477146.png +1341840129.508931 rgb/1341840129.508931.png 1341840129.508946 depth/1341840129.508946.png +1341840129.545077 rgb/1341840129.545077.png 1341840129.545093 depth/1341840129.545093.png +1341840129.577028 rgb/1341840129.577028.png 1341840129.577466 depth/1341840129.577466.png +1341840129.613105 rgb/1341840129.613105.png 1341840129.613167 depth/1341840129.613167.png +1341840129.645181 rgb/1341840129.645181.png 1341840129.645205 depth/1341840129.645205.png +1341840129.677060 rgb/1341840129.677060.png 1341840129.677076 depth/1341840129.677076.png +1341840129.713150 rgb/1341840129.713150.png 1341840129.713668 depth/1341840129.713668.png +1341840129.781126 rgb/1341840129.781126.png 1341840129.781166 depth/1341840129.781166.png +1341840129.838137 rgb/1341840129.838137.png 1341840129.838163 depth/1341840129.838163.png +1341840129.874190 rgb/1341840129.874190.png 1341840129.874224 depth/1341840129.874224.png +1341840129.905955 rgb/1341840129.905955.png 1341840129.905968 depth/1341840129.905968.png +1341840129.942047 rgb/1341840129.942047.png 1341840129.942070 depth/1341840129.942070.png +1341840129.973973 rgb/1341840129.973973.png 1341840129.973988 depth/1341840129.973988.png +1341840130.042126 rgb/1341840130.042126.png 1341840130.042218 depth/1341840130.042218.png +1341840130.074782 rgb/1341840130.074782.png 1341840130.074828 depth/1341840130.074828.png +1341840130.106036 rgb/1341840130.106036.png 1341840130.106065 depth/1341840130.106065.png +1341840130.142043 rgb/1341840130.142043.png 1341840130.142065 depth/1341840130.142065.png +1341840130.174006 rgb/1341840130.174006.png 1341840130.174019 depth/1341840130.174019.png +1341840130.210173 rgb/1341840130.210173.png 1341840130.210229 depth/1341840130.210229.png +1341840130.241993 rgb/1341840130.241993.png 1341840130.242023 depth/1341840130.242023.png +1341840130.274086 rgb/1341840130.274086.png 1341840130.274120 depth/1341840130.274120.png +1341840130.309975 rgb/1341840130.309975.png 1341840130.310709 depth/1341840130.310709.png +1341840130.349159 rgb/1341840130.349159.png 1341840130.349186 depth/1341840130.349186.png +1341840130.381240 rgb/1341840130.381240.png 1341840130.381851 depth/1341840130.381851.png +1341840130.417035 rgb/1341840130.417035.png 1341840130.417062 depth/1341840130.417062.png +1341840130.449123 rgb/1341840130.449123.png 1341840130.449195 depth/1341840130.449195.png +1341840130.480958 rgb/1341840130.480958.png 1341840130.480976 depth/1341840130.480976.png +1341840130.517090 rgb/1341840130.517090.png 1341840130.517114 depth/1341840130.517114.png +1341840130.549069 rgb/1341840130.549069.png 1341840130.549088 depth/1341840130.549088.png +1341840130.587796 rgb/1341840130.587796.png 1341840130.588274 depth/1341840130.588274.png +1341840130.617146 rgb/1341840130.617146.png 1341840130.617174 depth/1341840130.617174.png +1341840130.649137 rgb/1341840130.649137.png 1341840130.649157 depth/1341840130.649157.png +1341840130.717135 rgb/1341840130.717135.png 1341840130.717190 depth/1341840130.717190.png +1341840130.778114 rgb/1341840130.778114.png 1341840130.778123 depth/1341840130.778123.png +1341840130.810115 rgb/1341840130.810115.png 1341840130.810134 depth/1341840130.810134.png +1341840130.878493 rgb/1341840130.878493.png 1341840130.878509 depth/1341840130.878509.png +1341840130.914115 rgb/1341840130.914115.png 1341840130.914135 depth/1341840130.914135.png +1341840130.946089 rgb/1341840130.946089.png 1341840130.946107 depth/1341840130.946107.png +1341840130.978153 rgb/1341840130.978153.png 1341840130.978179 depth/1341840130.978179.png +1341840131.014063 rgb/1341840131.014063.png 1341840131.014075 depth/1341840131.014075.png +1341840131.046245 rgb/1341840131.046245.png 1341840131.046253 depth/1341840131.046253.png +1341840131.078388 rgb/1341840131.078388.png 1341840131.078422 depth/1341840131.078422.png +1341840131.114122 rgb/1341840131.114122.png 1341840131.114153 depth/1341840131.114153.png +1341840131.146166 rgb/1341840131.146166.png 1341840131.146179 depth/1341840131.146179.png +1341840131.182300 rgb/1341840131.182300.png 1341840131.182321 depth/1341840131.182321.png +1341840131.218982 rgb/1341840131.218982.png 1341840131.219857 depth/1341840131.219857.png +1341840131.282164 rgb/1341840131.282164.png 1341840131.282193 depth/1341840131.282193.png +1341840131.316303 rgb/1341840131.316303.png 1341840131.316324 depth/1341840131.316324.png +1341840131.345970 rgb/1341840131.345970.png 1341840131.346515 depth/1341840131.346515.png +1341840131.382022 rgb/1341840131.382022.png 1341840131.382499 depth/1341840131.382499.png +1341840131.413965 rgb/1341840131.413965.png 1341840131.413983 depth/1341840131.413983.png +1341840131.450200 rgb/1341840131.450200.png 1341840131.450630 depth/1341840131.450630.png +1341840131.482205 rgb/1341840131.482205.png 1341840131.482221 depth/1341840131.482221.png +1341840131.514024 rgb/1341840131.514024.png 1341840131.514122 depth/1341840131.514122.png +1341840131.550027 rgb/1341840131.550027.png 1341840131.550155 depth/1341840131.550155.png +1341840131.582475 rgb/1341840131.582475.png 1341840131.582511 depth/1341840131.582511.png +1341840131.618131 rgb/1341840131.618131.png 1341840131.618150 depth/1341840131.618150.png +1341840131.651356 rgb/1341840131.651356.png 1341840131.651393 depth/1341840131.651393.png +1341840131.682093 rgb/1341840131.682093.png 1341840131.682105 depth/1341840131.682105.png +1341840131.717991 rgb/1341840131.717991.png 1341840131.718033 depth/1341840131.718033.png +1341840131.750781 rgb/1341840131.750781.png 1341840131.751590 depth/1341840131.751590.png +1341840131.781959 rgb/1341840131.781959.png 1341840131.781982 depth/1341840131.781982.png +1341840131.818008 rgb/1341840131.818008.png 1341840131.818034 depth/1341840131.818034.png +1341840131.849988 rgb/1341840131.849988.png 1341840131.850016 depth/1341840131.850016.png +1341840131.886021 rgb/1341840131.886021.png 1341840131.886034 depth/1341840131.886034.png +1341840131.918209 rgb/1341840131.918209.png 1341840131.918254 depth/1341840131.918254.png +1341840131.950157 rgb/1341840131.950157.png 1341840131.950181 depth/1341840131.950181.png +1341840131.986149 rgb/1341840131.986149.png 1341840131.986168 depth/1341840131.986168.png +1341840132.018152 rgb/1341840132.018152.png 1341840132.018168 depth/1341840132.018168.png +1341840132.050105 rgb/1341840132.050105.png 1341840132.050123 depth/1341840132.050123.png +1341840132.086201 rgb/1341840132.086201.png 1341840132.086230 depth/1341840132.086230.png +1341840132.118096 rgb/1341840132.118096.png 1341840132.118108 depth/1341840132.118108.png +1341840132.154105 rgb/1341840132.154105.png 1341840132.154133 depth/1341840132.154133.png +1341840132.186168 rgb/1341840132.186168.png 1341840132.186366 depth/1341840132.186366.png +1341840132.218011 rgb/1341840132.218011.png 1341840132.218021 depth/1341840132.218021.png +1341840132.254237 rgb/1341840132.254237.png 1341840132.254249 depth/1341840132.254249.png +1341840132.285962 rgb/1341840132.285962.png 1341840132.286002 depth/1341840132.286002.png +1341840132.318122 rgb/1341840132.318122.png 1341840132.318135 depth/1341840132.318135.png +1341840132.354146 rgb/1341840132.354146.png 1341840132.354201 depth/1341840132.354201.png +1341840132.386067 rgb/1341840132.386067.png 1341840132.386084 depth/1341840132.386084.png +1341840132.422003 rgb/1341840132.422003.png 1341840132.422433 depth/1341840132.422433.png +1341840132.454101 rgb/1341840132.454101.png 1341840132.454568 depth/1341840132.454568.png +1341840132.486012 rgb/1341840132.486012.png 1341840132.486032 depth/1341840132.486032.png +1341840132.522171 rgb/1341840132.522171.png 1341840132.522201 depth/1341840132.522201.png +1341840132.554000 rgb/1341840132.554000.png 1341840132.554033 depth/1341840132.554033.png +1341840132.590191 rgb/1341840132.590191.png 1341840132.590210 depth/1341840132.590210.png +1341840132.621972 rgb/1341840132.621972.png 1341840132.621987 depth/1341840132.621987.png +1341840132.654055 rgb/1341840132.654055.png 1341840132.654074 depth/1341840132.654074.png +1341840132.690063 rgb/1341840132.690063.png 1341840132.690077 depth/1341840132.690077.png +1341840132.722060 rgb/1341840132.722060.png 1341840132.722148 depth/1341840132.722148.png +1341840132.754009 rgb/1341840132.754009.png 1341840132.754032 depth/1341840132.754032.png +1341840132.790126 rgb/1341840132.790126.png 1341840132.790141 depth/1341840132.790141.png +1341840132.822165 rgb/1341840132.822165.png 1341840132.822179 depth/1341840132.822179.png +1341840132.858128 rgb/1341840132.858128.png 1341840132.858135 depth/1341840132.858135.png +1341840132.890074 rgb/1341840132.890074.png 1341840132.890103 depth/1341840132.890103.png +1341840132.922331 rgb/1341840132.922331.png 1341840132.922355 depth/1341840132.922355.png +1341840132.958143 rgb/1341840132.958143.png 1341840132.958161 depth/1341840132.958161.png +1341840132.990011 rgb/1341840132.990011.png 1341840132.990591 depth/1341840132.990591.png +1341840133.022123 rgb/1341840133.022123.png 1341840133.022177 depth/1341840133.022177.png +1341840133.058116 rgb/1341840133.058116.png 1341840133.058125 depth/1341840133.058125.png +1341840133.089991 rgb/1341840133.089991.png 1341840133.090022 depth/1341840133.090022.png +1341840133.126100 rgb/1341840133.126100.png 1341840133.126162 depth/1341840133.126162.png +1341840133.158041 rgb/1341840133.158041.png 1341840133.158072 depth/1341840133.158072.png +1341840133.190165 rgb/1341840133.190165.png 1341840133.190179 depth/1341840133.190179.png +1341840133.226039 rgb/1341840133.226039.png 1341840133.226058 depth/1341840133.226058.png +1341840133.258020 rgb/1341840133.258020.png 1341840133.258090 depth/1341840133.258090.png +1341840133.290010 rgb/1341840133.290010.png 1341840133.290036 depth/1341840133.290036.png +1341840133.326121 rgb/1341840133.326121.png 1341840133.326132 depth/1341840133.326132.png +1341840133.357973 rgb/1341840133.357973.png 1341840133.357984 depth/1341840133.357984.png +1341840133.394143 rgb/1341840133.394143.png 1341840133.394710 depth/1341840133.394710.png +1341840133.426653 rgb/1341840133.426653.png 1341840133.426668 depth/1341840133.426668.png +1341840133.458017 rgb/1341840133.458017.png 1341840133.458039 depth/1341840133.458039.png +1341840133.494056 rgb/1341840133.494056.png 1341840133.494150 depth/1341840133.494150.png +1341840133.526138 rgb/1341840133.526138.png 1341840133.526146 depth/1341840133.526146.png +1341840133.558093 rgb/1341840133.558093.png 1341840133.558130 depth/1341840133.558130.png +1341840133.596989 rgb/1341840133.596989.png 1341840133.594145 depth/1341840133.594145.png +1341840133.662163 rgb/1341840133.662163.png 1341840133.662190 depth/1341840133.662190.png +1341840133.694287 rgb/1341840133.694287.png 1341840133.694320 depth/1341840133.694320.png +1341840133.725972 rgb/1341840133.725972.png 1341840133.726028 depth/1341840133.726028.png +1341840133.762031 rgb/1341840133.762031.png 1341840133.762039 depth/1341840133.762039.png +1341840133.794303 rgb/1341840133.794303.png 1341840133.794324 depth/1341840133.794324.png +1341840133.830078 rgb/1341840133.830078.png 1341840133.830093 depth/1341840133.830093.png +1341840133.862082 rgb/1341840133.862082.png 1341840133.862122 depth/1341840133.862122.png +1341840133.895671 rgb/1341840133.895671.png 1341840133.896407 depth/1341840133.896407.png +1341840133.962170 rgb/1341840133.962170.png 1341840133.962189 depth/1341840133.962189.png +1341840133.994096 rgb/1341840133.994096.png 1341840133.994150 depth/1341840133.994150.png +1341840134.030081 rgb/1341840134.030081.png 1341840134.030176 depth/1341840134.030176.png +1341840134.062064 rgb/1341840134.062064.png 1341840134.062089 depth/1341840134.062089.png +1341840134.098505 rgb/1341840134.098505.png 1341840134.098539 depth/1341840134.098539.png +1341840134.130096 rgb/1341840134.130096.png 1341840134.130230 depth/1341840134.130230.png +1341840134.162042 rgb/1341840134.162042.png 1341840134.162111 depth/1341840134.162111.png +1341840134.198214 rgb/1341840134.198214.png 1341840134.198229 depth/1341840134.198229.png +1341840134.230132 rgb/1341840134.230132.png 1341840134.230987 depth/1341840134.230987.png +1341840134.262049 rgb/1341840134.262049.png 1341840134.262088 depth/1341840134.262088.png +1341840134.297987 rgb/1341840134.297987.png 1341840134.298003 depth/1341840134.298003.png +1341840134.330137 rgb/1341840134.330137.png 1341840134.331272 depth/1341840134.331272.png +1341840134.366116 rgb/1341840134.366116.png 1341840134.366131 depth/1341840134.366131.png +1341840134.430407 rgb/1341840134.430407.png 1341840134.430483 depth/1341840134.430483.png +1341840134.466088 rgb/1341840134.466088.png 1341840134.466829 depth/1341840134.466829.png +1341840134.498028 rgb/1341840134.498028.png 1341840134.498043 depth/1341840134.498043.png +1341840134.530063 rgb/1341840134.530063.png 1341840134.530084 depth/1341840134.530084.png +1341840134.565976 rgb/1341840134.565976.png 1341840134.566006 depth/1341840134.566006.png +1341840134.598132 rgb/1341840134.598132.png 1341840134.598150 depth/1341840134.598150.png +1341840134.634118 rgb/1341840134.634118.png 1341840134.634125 depth/1341840134.634125.png +1341840134.666094 rgb/1341840134.666094.png 1341840134.666601 depth/1341840134.666601.png +1341840134.698325 rgb/1341840134.698325.png 1341840134.698366 depth/1341840134.698366.png +1341840134.733994 rgb/1341840134.733994.png 1341840134.734009 depth/1341840134.734009.png +1341840134.766613 rgb/1341840134.766613.png 1341840134.766622 depth/1341840134.766622.png +1341840134.802097 rgb/1341840134.802097.png 1341840134.802131 depth/1341840134.802131.png +1341840134.833989 rgb/1341840134.833989.png 1341840134.834005 depth/1341840134.834005.png +1341840134.866184 rgb/1341840134.866184.png 1341840134.866193 depth/1341840134.866193.png +1341840134.902070 rgb/1341840134.902070.png 1341840134.902084 depth/1341840134.902084.png +1341840134.933969 rgb/1341840134.933969.png 1341840134.933980 depth/1341840134.933980.png +1341840134.966029 rgb/1341840134.966029.png 1341840134.966063 depth/1341840134.966063.png +1341840135.001944 rgb/1341840135.001944.png 1341840135.001953 depth/1341840135.001953.png +1341840135.034464 rgb/1341840135.034464.png 1341840135.034490 depth/1341840135.034490.png +1341840135.069989 rgb/1341840135.069989.png 1341840135.070007 depth/1341840135.070007.png +1341840135.102037 rgb/1341840135.102037.png 1341840135.102085 depth/1341840135.102085.png +1341840135.133985 rgb/1341840135.133985.png 1341840135.134008 depth/1341840135.134008.png +1341840135.170148 rgb/1341840135.170148.png 1341840135.170187 depth/1341840135.170187.png +1341840135.202073 rgb/1341840135.202073.png 1341840135.202155 depth/1341840135.202155.png +1341840135.234309 rgb/1341840135.234309.png 1341840135.234351 depth/1341840135.234351.png +1341840135.270093 rgb/1341840135.270093.png 1341840135.270108 depth/1341840135.270108.png +1341840135.302100 rgb/1341840135.302100.png 1341840135.302118 depth/1341840135.302118.png +1341840135.338325 rgb/1341840135.338325.png 1341840135.338355 depth/1341840135.338355.png +1341840135.370144 rgb/1341840135.370144.png 1341840135.370170 depth/1341840135.370170.png +1341840135.402042 rgb/1341840135.402042.png 1341840135.402659 depth/1341840135.402659.png +1341840135.437978 rgb/1341840135.437978.png 1341840135.437993 depth/1341840135.437993.png +1341840135.470019 rgb/1341840135.470019.png 1341840135.470040 depth/1341840135.470040.png +1341840135.502169 rgb/1341840135.502169.png 1341840135.502734 depth/1341840135.502734.png +1341840135.538089 rgb/1341840135.538089.png 1341840135.538102 depth/1341840135.538102.png +1341840135.570157 rgb/1341840135.570157.png 1341840135.570173 depth/1341840135.570173.png +1341840135.606052 rgb/1341840135.606052.png 1341840135.606062 depth/1341840135.606062.png +1341840135.638227 rgb/1341840135.638227.png 1341840135.638241 depth/1341840135.638241.png +1341840135.670239 rgb/1341840135.670239.png 1341840135.670311 depth/1341840135.670311.png +1341840135.706052 rgb/1341840135.706052.png 1341840135.706516 depth/1341840135.706516.png +1341840135.738137 rgb/1341840135.738137.png 1341840135.738161 depth/1341840135.738161.png +1341840135.774040 rgb/1341840135.774040.png 1341840135.774050 depth/1341840135.774050.png +1341840135.806028 rgb/1341840135.806028.png 1341840135.806051 depth/1341840135.806051.png +1341840135.838206 rgb/1341840135.838206.png 1341840135.838217 depth/1341840135.838217.png +1341840135.874119 rgb/1341840135.874119.png 1341840135.874132 depth/1341840135.874132.png +1341840135.906010 rgb/1341840135.906010.png 1341840135.906030 depth/1341840135.906030.png +1341840135.938279 rgb/1341840135.938279.png 1341840135.938292 depth/1341840135.938292.png +1341840135.974129 rgb/1341840135.974129.png 1341840135.974151 depth/1341840135.974151.png +1341840136.006161 rgb/1341840136.006161.png 1341840136.006195 depth/1341840136.006195.png +1341840136.042013 rgb/1341840136.042013.png 1341840136.042143 depth/1341840136.042143.png +1341840136.074071 rgb/1341840136.074071.png 1341840136.074085 depth/1341840136.074085.png +1341840136.106147 rgb/1341840136.106147.png 1341840136.106212 depth/1341840136.106212.png +1341840136.142085 rgb/1341840136.142085.png 1341840136.142129 depth/1341840136.142129.png +1341840136.174142 rgb/1341840136.174142.png 1341840136.174163 depth/1341840136.174163.png +1341840136.206178 rgb/1341840136.206178.png 1341840136.206233 depth/1341840136.206233.png +1341840136.242129 rgb/1341840136.242129.png 1341840136.242172 depth/1341840136.242172.png +1341840136.274146 rgb/1341840136.274146.png 1341840136.274191 depth/1341840136.274191.png +1341840136.310044 rgb/1341840136.310044.png 1341840136.310234 depth/1341840136.310234.png +1341840136.342103 rgb/1341840136.342103.png 1341840136.342117 depth/1341840136.342117.png +1341840136.374144 rgb/1341840136.374144.png 1341840136.374202 depth/1341840136.374202.png +1341840136.410181 rgb/1341840136.410181.png 1341840136.410200 depth/1341840136.410200.png +1341840136.442000 rgb/1341840136.442000.png 1341840136.442059 depth/1341840136.442059.png +1341840136.474110 rgb/1341840136.474110.png 1341840136.474124 depth/1341840136.474124.png +1341840136.510086 rgb/1341840136.510086.png 1341840136.510106 depth/1341840136.510106.png +1341840136.542096 rgb/1341840136.542096.png 1341840136.542112 depth/1341840136.542112.png +1341840136.578053 rgb/1341840136.578053.png 1341840136.578068 depth/1341840136.578068.png +1341840136.609971 rgb/1341840136.609971.png 1341840136.609979 depth/1341840136.609979.png +1341840136.642106 rgb/1341840136.642106.png 1341840136.642125 depth/1341840136.642125.png +1341840136.678116 rgb/1341840136.678116.png 1341840136.678127 depth/1341840136.678127.png +1341840136.709984 rgb/1341840136.709984.png 1341840136.709994 depth/1341840136.709994.png +1341840136.742055 rgb/1341840136.742055.png 1341840136.742064 depth/1341840136.742064.png +1341840136.778016 rgb/1341840136.778016.png 1341840136.778035 depth/1341840136.778035.png +1341840136.810073 rgb/1341840136.810073.png 1341840136.810965 depth/1341840136.810965.png +1341840136.846014 rgb/1341840136.846014.png 1341840136.846034 depth/1341840136.846034.png +1341840136.878703 rgb/1341840136.878703.png 1341840136.878714 depth/1341840136.878714.png +1341840136.910068 rgb/1341840136.910068.png 1341840136.910089 depth/1341840136.910089.png +1341840136.946101 rgb/1341840136.946101.png 1341840136.946121 depth/1341840136.946121.png +1341840136.978140 rgb/1341840136.978140.png 1341840136.978157 depth/1341840136.978157.png +1341840137.013946 rgb/1341840137.013946.png 1341840137.013963 depth/1341840137.013963.png +1341840137.046197 rgb/1341840137.046197.png 1341840137.046216 depth/1341840137.046216.png +1341840137.078105 rgb/1341840137.078105.png 1341840137.078117 depth/1341840137.078117.png +1341840137.114118 rgb/1341840137.114118.png 1341840137.114202 depth/1341840137.114202.png +1341840137.146012 rgb/1341840137.146012.png 1341840137.146037 depth/1341840137.146037.png +1341840137.178130 rgb/1341840137.178130.png 1341840137.178154 depth/1341840137.178154.png +1341840137.213973 rgb/1341840137.213973.png 1341840137.213980 depth/1341840137.213980.png +1341840137.246123 rgb/1341840137.246123.png 1341840137.246146 depth/1341840137.246146.png +1341840137.282211 rgb/1341840137.282211.png 1341840137.282226 depth/1341840137.282226.png +1341840137.350557 rgb/1341840137.350557.png 1341840137.350605 depth/1341840137.350605.png +1341840137.389297 rgb/1341840137.389297.png 1341840137.389313 depth/1341840137.389313.png +1341840137.421483 rgb/1341840137.421483.png 1341840137.423346 depth/1341840137.423346.png +1341840137.453379 rgb/1341840137.453379.png 1341840137.453391 depth/1341840137.453391.png +1341840137.489294 rgb/1341840137.489294.png 1341840137.490706 depth/1341840137.490706.png +1341840137.523409 rgb/1341840137.523409.png 1341840137.524388 depth/1341840137.524388.png +1341840137.553325 rgb/1341840137.553325.png 1341840137.554086 depth/1341840137.554086.png +1341840137.589470 rgb/1341840137.589470.png 1341840137.590698 depth/1341840137.590698.png +1341840137.624008 rgb/1341840137.624008.png 1341840137.627245 depth/1341840137.627245.png +1341840137.657522 rgb/1341840137.657522.png 1341840137.658733 depth/1341840137.658733.png +1341840137.689342 rgb/1341840137.689342.png 1341840137.694598 depth/1341840137.694598.png +1341840137.721926 rgb/1341840137.721926.png 1341840137.722404 depth/1341840137.722404.png +1341840137.759587 rgb/1341840137.759587.png 1341840137.761018 depth/1341840137.761018.png +1341840137.790775 rgb/1341840137.790775.png 1341840137.791879 depth/1341840137.791879.png +1341840137.821916 rgb/1341840137.821916.png 1341840137.823316 depth/1341840137.823316.png +1341840137.861516 rgb/1341840137.861516.png 1341840137.862810 depth/1341840137.862810.png +1341840137.893812 rgb/1341840137.893812.png 1341840137.893950 depth/1341840137.893950.png +1341840137.925612 rgb/1341840137.925612.png 1341840137.926839 depth/1341840137.926839.png +1341840137.956989 rgb/1341840137.956989.png 1341840137.957020 depth/1341840137.957020.png +1341840137.989242 rgb/1341840137.989242.png 1341840137.989251 depth/1341840137.989251.png +1341840138.025120 rgb/1341840138.025120.png 1341840138.025135 depth/1341840138.025135.png +1341840138.058067 rgb/1341840138.058067.png 1341840138.058115 depth/1341840138.058115.png +1341840138.089228 rgb/1341840138.089228.png 1341840138.090752 depth/1341840138.090752.png +1341840138.125193 rgb/1341840138.125193.png 1341840138.125208 depth/1341840138.125208.png +1341840138.157187 rgb/1341840138.157187.png 1341840138.157207 depth/1341840138.157207.png +1341840138.189146 rgb/1341840138.189146.png 1341840138.189169 depth/1341840138.189169.png +1341840138.224979 rgb/1341840138.224979.png 1341840138.224998 depth/1341840138.224998.png +1341840138.257038 rgb/1341840138.257038.png 1341840138.257049 depth/1341840138.257049.png +1341840138.293190 rgb/1341840138.293190.png 1341840138.293207 depth/1341840138.293207.png +1341840138.325109 rgb/1341840138.325109.png 1341840138.325141 depth/1341840138.325141.png +1341840138.356973 rgb/1341840138.356973.png 1341840138.356994 depth/1341840138.356994.png +1341840138.392961 rgb/1341840138.392961.png 1341840138.392974 depth/1341840138.392974.png +1341840138.425035 rgb/1341840138.425035.png 1341840138.425650 depth/1341840138.425650.png +1341840138.457058 rgb/1341840138.457058.png 1341840138.457077 depth/1341840138.457077.png +1341840138.493018 rgb/1341840138.493018.png 1341840138.493028 depth/1341840138.493028.png +1341840138.524956 rgb/1341840138.524956.png 1341840138.524964 depth/1341840138.524964.png +1341840138.557167 rgb/1341840138.557167.png 1341840138.557180 depth/1341840138.557180.png +1341840138.593089 rgb/1341840138.593089.png 1341840138.593102 depth/1341840138.593102.png +1341840138.624938 rgb/1341840138.624938.png 1341840138.624972 depth/1341840138.624972.png +1341840138.661032 rgb/1341840138.661032.png 1341840138.661046 depth/1341840138.661046.png +1341840138.693089 rgb/1341840138.693089.png 1341840138.693109 depth/1341840138.693109.png +1341840138.725002 rgb/1341840138.725002.png 1341840138.725059 depth/1341840138.725059.png +1341840138.761074 rgb/1341840138.761074.png 1341840138.761086 depth/1341840138.761086.png +1341840138.793033 rgb/1341840138.793033.png 1341840138.793053 depth/1341840138.793053.png +1341840138.825178 rgb/1341840138.825178.png 1341840138.825198 depth/1341840138.825198.png +1341840138.861281 rgb/1341840138.861281.png 1341840138.861291 depth/1341840138.861291.png +1341840138.893162 rgb/1341840138.893162.png 1341840138.893821 depth/1341840138.893821.png +1341840138.929074 rgb/1341840138.929074.png 1341840138.929087 depth/1341840138.929087.png +1341840138.961069 rgb/1341840138.961069.png 1341840138.961079 depth/1341840138.961079.png +1341840138.993385 rgb/1341840138.993385.png 1341840138.993418 depth/1341840138.993418.png +1341840139.028984 rgb/1341840139.028984.png 1341840139.028993 depth/1341840139.028993.png +1341840139.061014 rgb/1341840139.061014.png 1341840139.061027 depth/1341840139.061027.png +1341840139.097254 rgb/1341840139.097254.png 1341840139.097274 depth/1341840139.097274.png +1341840139.129091 rgb/1341840139.129091.png 1341840139.129099 depth/1341840139.129099.png +1341840139.160945 rgb/1341840139.160945.png 1341840139.160955 depth/1341840139.160955.png +1341840139.196990 rgb/1341840139.196990.png 1341840139.196998 depth/1341840139.196998.png +1341840139.228998 rgb/1341840139.228998.png 1341840139.229010 depth/1341840139.229010.png +1341840139.265069 rgb/1341840139.265069.png 1341840139.265081 depth/1341840139.265081.png +1341840139.297244 rgb/1341840139.297244.png 1341840139.297259 depth/1341840139.297259.png +1341840139.334563 rgb/1341840139.334563.png 1341840139.335398 depth/1341840139.335398.png +1341840139.365300 rgb/1341840139.365300.png 1341840139.365330 depth/1341840139.365330.png +1341840139.433146 rgb/1341840139.433146.png 1341840139.433184 depth/1341840139.433184.png +1341840139.494120 rgb/1341840139.494120.png 1341840139.494169 depth/1341840139.494169.png +1341840139.525955 rgb/1341840139.525955.png 1341840139.526012 depth/1341840139.526012.png +1341840139.557968 rgb/1341840139.557968.png 1341840139.557982 depth/1341840139.557982.png +1341840139.594119 rgb/1341840139.594119.png 1341840139.594130 depth/1341840139.594130.png +1341840139.626042 rgb/1341840139.626042.png 1341840139.626059 depth/1341840139.626059.png +1341840139.726297 rgb/1341840139.726297.png 1341840139.726312 depth/1341840139.726312.png +1341840139.762004 rgb/1341840139.762004.png 1341840139.762018 depth/1341840139.762018.png +1341840139.794398 rgb/1341840139.794398.png 1341840139.794410 depth/1341840139.794410.png +1341840139.826732 rgb/1341840139.826732.png 1341840139.826743 depth/1341840139.826743.png +1341840139.862007 rgb/1341840139.862007.png 1341840139.862019 depth/1341840139.862019.png +1341840139.894244 rgb/1341840139.894244.png 1341840139.894300 depth/1341840139.894300.png +1341840139.926058 rgb/1341840139.926058.png 1341840139.926081 depth/1341840139.926081.png +1341840139.961989 rgb/1341840139.961989.png 1341840139.962034 depth/1341840139.962034.png +1341840139.994508 rgb/1341840139.994508.png 1341840139.994517 depth/1341840139.994517.png +1341840140.030374 rgb/1341840140.030374.png 1341840140.030433 depth/1341840140.030433.png +1341840140.062130 rgb/1341840140.062130.png 1341840140.062143 depth/1341840140.062143.png +1341840140.094164 rgb/1341840140.094164.png 1341840140.094177 depth/1341840140.094177.png +1341840140.130166 rgb/1341840140.130166.png 1341840140.130176 depth/1341840140.130176.png +1341840140.162059 rgb/1341840140.162059.png 1341840140.162074 depth/1341840140.162074.png +1341840140.197991 rgb/1341840140.197991.png 1341840140.198001 depth/1341840140.198001.png +1341840140.230198 rgb/1341840140.230198.png 1341840140.230212 depth/1341840140.230212.png +1341840140.262494 rgb/1341840140.262494.png 1341840140.262580 depth/1341840140.262580.png +1341840140.298172 rgb/1341840140.298172.png 1341840140.298211 depth/1341840140.298211.png +1341840140.330071 rgb/1341840140.330071.png 1341840140.330091 depth/1341840140.330091.png +1341840140.362068 rgb/1341840140.362068.png 1341840140.362081 depth/1341840140.362081.png diff --git a/Examples/RGB-D/associations/fr3_office.txt b/Examples/RGB-D/associations/fr3_office.txt new file mode 100644 index 0000000000..942f86b4a7 --- /dev/null +++ b/Examples/RGB-D/associations/fr3_office.txt @@ -0,0 +1,2488 @@ +1341847980.722988 rgb/1341847980.722988.png 1341847980.723020 depth/1341847980.723020.png +1341847980.754743 rgb/1341847980.754743.png 1341847980.754755 depth/1341847980.754755.png +1341847980.786856 rgb/1341847980.786856.png 1341847980.786879 depth/1341847980.786879.png +1341847980.822978 rgb/1341847980.822978.png 1341847980.822989 depth/1341847980.822989.png +1341847980.854676 rgb/1341847980.854676.png 1341847980.854690 depth/1341847980.854690.png +1341847980.890728 rgb/1341847980.890728.png 1341847980.890737 depth/1341847980.890737.png +1341847980.922978 rgb/1341847980.922978.png 1341847980.922989 depth/1341847980.922989.png +1341847980.954645 rgb/1341847980.954645.png 1341847980.954676 depth/1341847980.954676.png +1341847980.990699 rgb/1341847980.990699.png 1341847980.990724 depth/1341847980.990724.png +1341847981.022715 rgb/1341847981.022715.png 1341847981.022728 depth/1341847981.022728.png +1341847981.054711 rgb/1341847981.054711.png 1341847981.054773 depth/1341847981.054773.png +1341847981.090715 rgb/1341847981.090715.png 1341847981.090786 depth/1341847981.090786.png +1341847981.122985 rgb/1341847981.122985.png 1341847981.123049 depth/1341847981.123049.png +1341847981.158632 rgb/1341847981.158632.png 1341847981.158648 depth/1341847981.158648.png +1341847981.190636 rgb/1341847981.190636.png 1341847981.190650 depth/1341847981.190650.png +1341847981.222978 rgb/1341847981.222978.png 1341847981.222989 depth/1341847981.222989.png +1341847981.258722 rgb/1341847981.258722.png 1341847981.258781 depth/1341847981.258781.png +1341847981.290787 rgb/1341847981.290787.png 1341847981.290854 depth/1341847981.290854.png +1341847981.322892 rgb/1341847981.322892.png 1341847981.322934 depth/1341847981.322934.png +1341847981.358690 rgb/1341847981.358690.png 1341847981.358724 depth/1341847981.358724.png +1341847981.390810 rgb/1341847981.390810.png 1341847981.390852 depth/1341847981.390852.png +1341847981.426707 rgb/1341847981.426707.png 1341847981.426732 depth/1341847981.426732.png +1341847981.458797 rgb/1341847981.458797.png 1341847981.459399 depth/1341847981.459399.png +1341847981.490701 rgb/1341847981.490701.png 1341847981.493435 depth/1341847981.493435.png +1341847981.527039 rgb/1341847981.527039.png 1341847981.527062 depth/1341847981.527062.png +1341847981.558722 rgb/1341847981.558722.png 1341847981.558770 depth/1341847981.558770.png +1341847981.594855 rgb/1341847981.594855.png 1341847981.594880 depth/1341847981.594880.png +1341847981.626675 rgb/1341847981.626675.png 1341847981.626685 depth/1341847981.626685.png +1341847981.658738 rgb/1341847981.658738.png 1341847981.658793 depth/1341847981.658793.png +1341847981.694720 rgb/1341847981.694720.png 1341847981.694765 depth/1341847981.694765.png +1341847981.726650 rgb/1341847981.726650.png 1341847981.726727 depth/1341847981.726727.png +1341847981.758846 rgb/1341847981.758846.png 1341847981.758922 depth/1341847981.758922.png +1341847981.794659 rgb/1341847981.794659.png 1341847981.794679 depth/1341847981.794679.png +1341847981.826678 rgb/1341847981.826678.png 1341847981.826688 depth/1341847981.826688.png +1341847981.862719 rgb/1341847981.862719.png 1341847981.862742 depth/1341847981.862742.png +1341847981.894631 rgb/1341847981.894631.png 1341847981.894645 depth/1341847981.894645.png +1341847981.926602 rgb/1341847981.926602.png 1341847981.927087 depth/1341847981.927087.png +1341847981.994808 rgb/1341847981.994808.png 1341847981.994858 depth/1341847981.994858.png +1341847982.062739 rgb/1341847982.062739.png 1341847982.062794 depth/1341847982.062794.png +1341847982.094786 rgb/1341847982.094786.png 1341847982.095304 depth/1341847982.095304.png +1341847982.130710 rgb/1341847982.130710.png 1341847982.130739 depth/1341847982.130739.png +1341847982.162730 rgb/1341847982.162730.png 1341847982.162746 depth/1341847982.162746.png +1341847982.194674 rgb/1341847982.194674.png 1341847982.194690 depth/1341847982.194690.png +1341847982.230594 rgb/1341847982.230594.png 1341847982.230626 depth/1341847982.230626.png +1341847982.262666 rgb/1341847982.262666.png 1341847982.262694 depth/1341847982.262694.png +1341847982.294994 rgb/1341847982.294994.png 1341847982.295020 depth/1341847982.295020.png +1341847982.330655 rgb/1341847982.330655.png 1341847982.330680 depth/1341847982.330680.png +1341847982.398909 rgb/1341847982.398909.png 1341847982.398929 depth/1341847982.398929.png +1341847982.430770 rgb/1341847982.430770.png 1341847982.430799 depth/1341847982.430799.png +1341847982.462624 rgb/1341847982.462624.png 1341847982.462632 depth/1341847982.462632.png +1341847982.498616 rgb/1341847982.498616.png 1341847982.498627 depth/1341847982.498627.png +1341847982.530757 rgb/1341847982.530757.png 1341847982.530781 depth/1341847982.530781.png +1341847982.566660 rgb/1341847982.566660.png 1341847982.566676 depth/1341847982.566676.png +1341847982.598726 rgb/1341847982.598726.png 1341847982.598757 depth/1341847982.598757.png +1341847982.630723 rgb/1341847982.630723.png 1341847982.630827 depth/1341847982.630827.png +1341847982.666620 rgb/1341847982.666620.png 1341847982.666629 depth/1341847982.666629.png +1341847982.698638 rgb/1341847982.698638.png 1341847982.698652 depth/1341847982.698652.png +1341847982.730674 rgb/1341847982.730674.png 1341847982.731415 depth/1341847982.731415.png +1341847982.766706 rgb/1341847982.766706.png 1341847982.766748 depth/1341847982.766748.png +1341847982.798737 rgb/1341847982.798737.png 1341847982.798982 depth/1341847982.798982.png +1341847982.834747 rgb/1341847982.834747.png 1341847982.834818 depth/1341847982.834818.png +1341847982.866670 rgb/1341847982.866670.png 1341847982.866706 depth/1341847982.866706.png +1341847982.898700 rgb/1341847982.898700.png 1341847982.898764 depth/1341847982.898764.png +1341847982.934803 rgb/1341847982.934803.png 1341847982.934825 depth/1341847982.934825.png +1341847982.966708 rgb/1341847982.966708.png 1341847982.966733 depth/1341847982.966733.png +1341847982.998783 rgb/1341847982.998783.png 1341847982.998830 depth/1341847982.998830.png +1341847983.034693 rgb/1341847983.034693.png 1341847983.034747 depth/1341847983.034747.png +1341847983.066707 rgb/1341847983.066707.png 1341847983.066757 depth/1341847983.066757.png +1341847983.102757 rgb/1341847983.102757.png 1341847983.102773 depth/1341847983.102773.png +1341847983.134717 rgb/1341847983.134717.png 1341847983.134819 depth/1341847983.134819.png +1341847983.166651 rgb/1341847983.166651.png 1341847983.166667 depth/1341847983.166667.png +1341847983.202653 rgb/1341847983.202653.png 1341847983.202670 depth/1341847983.202670.png +1341847983.234717 rgb/1341847983.234717.png 1341847983.235241 depth/1341847983.235241.png +1341847983.266753 rgb/1341847983.266753.png 1341847983.266928 depth/1341847983.266928.png +1341847983.302701 rgb/1341847983.302701.png 1341847983.302721 depth/1341847983.302721.png +1341847983.334718 rgb/1341847983.334718.png 1341847983.334745 depth/1341847983.334745.png +1341847983.370887 rgb/1341847983.370887.png 1341847983.370946 depth/1341847983.370946.png +1341847983.402670 rgb/1341847983.402670.png 1341847983.402685 depth/1341847983.402685.png +1341847983.434705 rgb/1341847983.434705.png 1341847983.434724 depth/1341847983.434724.png +1341847983.470674 rgb/1341847983.470674.png 1341847983.470687 depth/1341847983.470687.png +1341847983.502767 rgb/1341847983.502767.png 1341847983.502784 depth/1341847983.502784.png +1341847983.534806 rgb/1341847983.534806.png 1341847983.535375 depth/1341847983.535375.png +1341847983.570684 rgb/1341847983.570684.png 1341847983.570707 depth/1341847983.570707.png +1341847983.602741 rgb/1341847983.602741.png 1341847983.602750 depth/1341847983.602750.png +1341847983.638729 rgb/1341847983.638729.png 1341847983.638747 depth/1341847983.638747.png +1341847983.702857 rgb/1341847983.702857.png 1341847983.702880 depth/1341847983.702880.png +1341847983.738736 rgb/1341847983.738736.png 1341847983.738756 depth/1341847983.738756.png +1341847983.770707 rgb/1341847983.770707.png 1341847983.770716 depth/1341847983.770716.png +1341847983.806672 rgb/1341847983.806672.png 1341847983.806687 depth/1341847983.806687.png +1341847983.838719 rgb/1341847983.838719.png 1341847983.838762 depth/1341847983.838762.png +1341847983.870712 rgb/1341847983.870712.png 1341847983.870739 depth/1341847983.870739.png +1341847983.906692 rgb/1341847983.906692.png 1341847983.906718 depth/1341847983.906718.png +1341847983.938757 rgb/1341847983.938757.png 1341847983.938781 depth/1341847983.938781.png +1341847983.970809 rgb/1341847983.970809.png 1341847983.971345 depth/1341847983.971345.png +1341847984.006722 rgb/1341847984.006722.png 1341847984.006741 depth/1341847984.006741.png +1341847984.038718 rgb/1341847984.038718.png 1341847984.038747 depth/1341847984.038747.png +1341847984.074737 rgb/1341847984.074737.png 1341847984.074751 depth/1341847984.074751.png +1341847984.106759 rgb/1341847984.106759.png 1341847984.106788 depth/1341847984.106788.png +1341847984.138698 rgb/1341847984.138698.png 1341847984.138713 depth/1341847984.138713.png +1341847984.174831 rgb/1341847984.174831.png 1341847984.174870 depth/1341847984.174870.png +1341847984.206711 rgb/1341847984.206711.png 1341847984.206723 depth/1341847984.206723.png +1341847984.238670 rgb/1341847984.238670.png 1341847984.238681 depth/1341847984.238681.png +1341847984.274795 rgb/1341847984.274795.png 1341847984.274814 depth/1341847984.274814.png +1341847984.306662 rgb/1341847984.306662.png 1341847984.306728 depth/1341847984.306728.png +1341847984.343094 rgb/1341847984.343094.png 1341847984.343117 depth/1341847984.343117.png +1341847984.406718 rgb/1341847984.406718.png 1341847984.406738 depth/1341847984.406738.png +1341847984.442894 rgb/1341847984.442894.png 1341847984.443623 depth/1341847984.443623.png +1341847984.474640 rgb/1341847984.474640.png 1341847984.474678 depth/1341847984.474678.png +1341847984.506747 rgb/1341847984.506747.png 1341847984.506771 depth/1341847984.506771.png +1341847984.542747 rgb/1341847984.542747.png 1341847984.542793 depth/1341847984.542793.png +1341847984.574807 rgb/1341847984.574807.png 1341847984.574826 depth/1341847984.574826.png +1341847984.610792 rgb/1341847984.610792.png 1341847984.611288 depth/1341847984.611288.png +1341847984.642667 rgb/1341847984.642667.png 1341847984.642687 depth/1341847984.642687.png +1341847984.674804 rgb/1341847984.674804.png 1341847984.674831 depth/1341847984.674831.png +1341847984.710651 rgb/1341847984.710651.png 1341847984.710661 depth/1341847984.710661.png +1341847984.743352 rgb/1341847984.743352.png 1341847984.743366 depth/1341847984.743366.png +1341847984.778881 rgb/1341847984.778881.png 1341847984.778893 depth/1341847984.778893.png +1341847984.810639 rgb/1341847984.810639.png 1341847984.810686 depth/1341847984.810686.png +1341847984.842655 rgb/1341847984.842655.png 1341847984.842727 depth/1341847984.842727.png +1341847984.878779 rgb/1341847984.878779.png 1341847984.878804 depth/1341847984.878804.png +1341847984.910613 rgb/1341847984.910613.png 1341847984.910638 depth/1341847984.910638.png +1341847984.943053 rgb/1341847984.943053.png 1341847984.943074 depth/1341847984.943074.png +1341847984.979236 rgb/1341847984.979236.png 1341847984.979255 depth/1341847984.979255.png +1341847985.010633 rgb/1341847985.010633.png 1341847985.010645 depth/1341847985.010645.png +1341847985.046612 rgb/1341847985.046612.png 1341847985.046651 depth/1341847985.046651.png +1341847985.078667 rgb/1341847985.078667.png 1341847985.078715 depth/1341847985.078715.png +1341847985.110771 rgb/1341847985.110771.png 1341847985.110785 depth/1341847985.110785.png +1341847985.146824 rgb/1341847985.146824.png 1341847985.146837 depth/1341847985.146837.png +1341847985.178699 rgb/1341847985.178699.png 1341847985.178715 depth/1341847985.178715.png +1341847985.210840 rgb/1341847985.210840.png 1341847985.210881 depth/1341847985.210881.png +1341847985.246735 rgb/1341847985.246735.png 1341847985.246755 depth/1341847985.246755.png +1341847985.278902 rgb/1341847985.278902.png 1341847985.279393 depth/1341847985.279393.png +1341847985.314648 rgb/1341847985.314648.png 1341847985.314667 depth/1341847985.314667.png +1341847985.346842 rgb/1341847985.346842.png 1341847985.347567 depth/1341847985.347567.png +1341847985.378830 rgb/1341847985.378830.png 1341847985.379393 depth/1341847985.379393.png +1341847985.414650 rgb/1341847985.414650.png 1341847985.414665 depth/1341847985.414665.png +1341847985.446854 rgb/1341847985.446854.png 1341847985.446867 depth/1341847985.446867.png +1341847985.478685 rgb/1341847985.478685.png 1341847985.478701 depth/1341847985.478701.png +1341847985.514673 rgb/1341847985.514673.png 1341847985.515080 depth/1341847985.515080.png +1341847985.546814 rgb/1341847985.546814.png 1341847985.547228 depth/1341847985.547228.png +1341847985.582581 rgb/1341847985.582581.png 1341847985.582613 depth/1341847985.582613.png +1341847985.614773 rgb/1341847985.614773.png 1341847985.614794 depth/1341847985.614794.png +1341847985.647097 rgb/1341847985.647097.png 1341847985.647135 depth/1341847985.647135.png +1341847985.682842 rgb/1341847985.682842.png 1341847985.682855 depth/1341847985.682855.png +1341847985.714719 rgb/1341847985.714719.png 1341847985.714738 depth/1341847985.714738.png +1341847985.746954 rgb/1341847985.746954.png 1341847985.747012 depth/1341847985.747012.png +1341847985.782765 rgb/1341847985.782765.png 1341847985.782792 depth/1341847985.782792.png +1341847985.814703 rgb/1341847985.814703.png 1341847985.814724 depth/1341847985.814724.png +1341847985.850739 rgb/1341847985.850739.png 1341847985.850752 depth/1341847985.850752.png +1341847985.882782 rgb/1341847985.882782.png 1341847985.882825 depth/1341847985.882825.png +1341847985.914968 rgb/1341847985.914968.png 1341847985.915001 depth/1341847985.915001.png +1341847985.950751 rgb/1341847985.950751.png 1341847985.950789 depth/1341847985.950789.png +1341847985.982712 rgb/1341847985.982712.png 1341847985.983184 depth/1341847985.983184.png +1341847986.018756 rgb/1341847986.018756.png 1341847986.018774 depth/1341847986.018774.png +1341847986.051991 rgb/1341847986.051991.png 1341847986.052003 depth/1341847986.052003.png +1341847986.082612 rgb/1341847986.082612.png 1341847986.082622 depth/1341847986.082622.png +1341847986.118719 rgb/1341847986.118719.png 1341847986.118737 depth/1341847986.118737.png +1341847986.150636 rgb/1341847986.150636.png 1341847986.150649 depth/1341847986.150649.png +1341847986.182648 rgb/1341847986.182648.png 1341847986.182659 depth/1341847986.182659.png +1341847986.218674 rgb/1341847986.218674.png 1341847986.218696 depth/1341847986.218696.png +1341847986.250584 rgb/1341847986.250584.png 1341847986.250603 depth/1341847986.250603.png +1341847986.286733 rgb/1341847986.286733.png 1341847986.286745 depth/1341847986.286745.png +1341847986.326156 rgb/1341847986.326156.png 1341847986.326815 depth/1341847986.326815.png +1341847986.359210 rgb/1341847986.359210.png 1341847986.360005 depth/1341847986.360005.png +1341847986.394467 rgb/1341847986.394467.png 1341847986.395174 depth/1341847986.395174.png +1341847986.425858 rgb/1341847986.425858.png 1341847986.425890 depth/1341847986.425890.png +1341847986.457691 rgb/1341847986.457691.png 1341847986.458500 depth/1341847986.458500.png +1341847986.493735 rgb/1341847986.493735.png 1341847986.493756 depth/1341847986.493756.png +1341847986.525772 rgb/1341847986.525772.png 1341847986.525809 depth/1341847986.525809.png +1341847986.561706 rgb/1341847986.561706.png 1341847986.561718 depth/1341847986.561718.png +1341847986.593712 rgb/1341847986.593712.png 1341847986.594246 depth/1341847986.594246.png +1341847986.625740 rgb/1341847986.625740.png 1341847986.625755 depth/1341847986.625755.png +1341847986.661920 rgb/1341847986.661920.png 1341847986.662611 depth/1341847986.662611.png +1341847986.693739 rgb/1341847986.693739.png 1341847986.693835 depth/1341847986.693835.png +1341847986.725896 rgb/1341847986.725896.png 1341847986.726876 depth/1341847986.726876.png +1341847986.762616 rgb/1341847986.762616.png 1341847986.762633 depth/1341847986.762633.png +1341847986.793794 rgb/1341847986.793794.png 1341847986.793820 depth/1341847986.793820.png +1341847986.829823 rgb/1341847986.829823.png 1341847986.829832 depth/1341847986.829832.png +1341847986.886746 rgb/1341847986.886746.png 1341847986.886842 depth/1341847986.886842.png +1341847986.922699 rgb/1341847986.922699.png 1341847986.922755 depth/1341847986.922755.png +1341847986.954690 rgb/1341847986.954690.png 1341847986.954745 depth/1341847986.954745.png +1341847986.990631 rgb/1341847986.990631.png 1341847986.990660 depth/1341847986.990660.png +1341847987.022895 rgb/1341847987.022895.png 1341847987.022913 depth/1341847987.022913.png +1341847987.054629 rgb/1341847987.054629.png 1341847987.054639 depth/1341847987.054639.png +1341847987.091223 rgb/1341847987.091223.png 1341847987.091553 depth/1341847987.091553.png +1341847987.123199 rgb/1341847987.123199.png 1341847987.123270 depth/1341847987.123270.png +1341847987.190716 rgb/1341847987.190716.png 1341847987.190730 depth/1341847987.190730.png +1341847987.259261 rgb/1341847987.259261.png 1341847987.259272 depth/1341847987.259272.png +1341847987.290653 rgb/1341847987.290653.png 1341847987.291556 depth/1341847987.291556.png +1341847987.322780 rgb/1341847987.322780.png 1341847987.322841 depth/1341847987.322841.png +1341847987.390720 rgb/1341847987.390720.png 1341847987.390738 depth/1341847987.390738.png +1341847987.422820 rgb/1341847987.422820.png 1341847987.423694 depth/1341847987.423694.png +1341847987.458620 rgb/1341847987.458620.png 1341847987.458651 depth/1341847987.458651.png +1341847987.490754 rgb/1341847987.490754.png 1341847987.490783 depth/1341847987.490783.png +1341847987.526761 rgb/1341847987.526761.png 1341847987.526770 depth/1341847987.526770.png +1341847987.558679 rgb/1341847987.558679.png 1341847987.558708 depth/1341847987.558708.png +1341847987.590776 rgb/1341847987.590776.png 1341847987.590797 depth/1341847987.590797.png +1341847987.626925 rgb/1341847987.626925.png 1341847987.626940 depth/1341847987.626940.png +1341847987.658922 rgb/1341847987.658922.png 1341847987.659671 depth/1341847987.659671.png +1341847987.691638 rgb/1341847987.691638.png 1341847987.691690 depth/1341847987.691690.png +1341847987.726721 rgb/1341847987.726721.png 1341847987.726755 depth/1341847987.726755.png +1341847987.758741 rgb/1341847987.758741.png 1341847987.758755 depth/1341847987.758755.png +1341847987.794708 rgb/1341847987.794708.png 1341847987.795290 depth/1341847987.795290.png +1341847987.826748 rgb/1341847987.826748.png 1341847987.826758 depth/1341847987.826758.png +1341847987.865879 rgb/1341847987.865879.png 1341847987.865947 depth/1341847987.865947.png +1341847987.897796 rgb/1341847987.897796.png 1341847987.897811 depth/1341847987.897811.png +1341847987.933722 rgb/1341847987.933722.png 1341847987.933810 depth/1341847987.933810.png +1341847987.965806 rgb/1341847987.965806.png 1341847987.965906 depth/1341847987.965906.png +1341847987.997794 rgb/1341847987.997794.png 1341847987.997809 depth/1341847987.997809.png +1341847988.033757 rgb/1341847988.033757.png 1341847988.033804 depth/1341847988.033804.png +1341847988.065746 rgb/1341847988.065746.png 1341847988.066172 depth/1341847988.066172.png +1341847988.098165 rgb/1341847988.098165.png 1341847988.098177 depth/1341847988.098177.png +1341847988.133763 rgb/1341847988.133763.png 1341847988.133778 depth/1341847988.133778.png +1341847988.165801 rgb/1341847988.165801.png 1341847988.165826 depth/1341847988.165826.png +1341847988.201710 rgb/1341847988.201710.png 1341847988.201741 depth/1341847988.201741.png +1341847988.233777 rgb/1341847988.233777.png 1341847988.233789 depth/1341847988.233789.png +1341847988.265702 rgb/1341847988.265702.png 1341847988.265717 depth/1341847988.265717.png +1341847988.301776 rgb/1341847988.301776.png 1341847988.301805 depth/1341847988.301805.png +1341847988.333739 rgb/1341847988.333739.png 1341847988.333771 depth/1341847988.333771.png +1341847988.369715 rgb/1341847988.369715.png 1341847988.369734 depth/1341847988.369734.png +1341847988.401745 rgb/1341847988.401745.png 1341847988.401770 depth/1341847988.401770.png +1341847988.433996 rgb/1341847988.433996.png 1341847988.434023 depth/1341847988.434023.png +1341847988.469742 rgb/1341847988.469742.png 1341847988.469802 depth/1341847988.469802.png +1341847988.502496 rgb/1341847988.502496.png 1341847988.502545 depth/1341847988.502545.png +1341847988.537778 rgb/1341847988.537778.png 1341847988.537793 depth/1341847988.537793.png +1341847988.569700 rgb/1341847988.569700.png 1341847988.569710 depth/1341847988.569710.png +1341847988.601796 rgb/1341847988.601796.png 1341847988.601811 depth/1341847988.601811.png +1341847988.637768 rgb/1341847988.637768.png 1341847988.637776 depth/1341847988.637776.png +1341847988.669807 rgb/1341847988.669807.png 1341847988.669832 depth/1341847988.669832.png +1341847988.706192 rgb/1341847988.706192.png 1341847988.706208 depth/1341847988.706208.png +1341847988.737940 rgb/1341847988.737940.png 1341847988.737953 depth/1341847988.737953.png +1341847988.769740 rgb/1341847988.769740.png 1341847988.769758 depth/1341847988.769758.png +1341847988.806051 rgb/1341847988.806051.png 1341847988.806076 depth/1341847988.806076.png +1341847988.837897 rgb/1341847988.837897.png 1341847988.837915 depth/1341847988.837915.png +1341847988.873917 rgb/1341847988.873917.png 1341847988.873942 depth/1341847988.873942.png +1341847988.937824 rgb/1341847988.937824.png 1341847988.937882 depth/1341847988.937882.png +1341847988.998737 rgb/1341847988.998737.png 1341847988.998765 depth/1341847988.998765.png +1341847989.034678 rgb/1341847989.034678.png 1341847989.034698 depth/1341847989.034698.png +1341847989.066658 rgb/1341847989.066658.png 1341847989.066676 depth/1341847989.066676.png +1341847989.098821 rgb/1341847989.098821.png 1341847989.099249 depth/1341847989.099249.png +1341847989.134676 rgb/1341847989.134676.png 1341847989.134698 depth/1341847989.134698.png +1341847989.166672 rgb/1341847989.166672.png 1341847989.166691 depth/1341847989.166691.png +1341847989.202743 rgb/1341847989.202743.png 1341847989.202772 depth/1341847989.202772.png +1341847989.234728 rgb/1341847989.234728.png 1341847989.234770 depth/1341847989.234770.png +1341847989.266651 rgb/1341847989.266651.png 1341847989.266663 depth/1341847989.266663.png +1341847989.302773 rgb/1341847989.302773.png 1341847989.302804 depth/1341847989.302804.png +1341847989.334871 rgb/1341847989.334871.png 1341847989.334903 depth/1341847989.334903.png +1341847989.366685 rgb/1341847989.366685.png 1341847989.366730 depth/1341847989.366730.png +1341847989.402777 rgb/1341847989.402777.png 1341847989.402790 depth/1341847989.402790.png +1341847989.434824 rgb/1341847989.434824.png 1341847989.434864 depth/1341847989.434864.png +1341847989.470712 rgb/1341847989.470712.png 1341847989.470743 depth/1341847989.470743.png +1341847989.502614 rgb/1341847989.502614.png 1341847989.502627 depth/1341847989.502627.png +1341847989.534687 rgb/1341847989.534687.png 1341847989.534720 depth/1341847989.534720.png +1341847989.570705 rgb/1341847989.570705.png 1341847989.570732 depth/1341847989.570732.png +1341847989.602804 rgb/1341847989.602804.png 1341847989.603280 depth/1341847989.603280.png +1341847989.634745 rgb/1341847989.634745.png 1341847989.634762 depth/1341847989.634762.png +1341847989.670627 rgb/1341847989.670627.png 1341847989.670637 depth/1341847989.670637.png +1341847989.702606 rgb/1341847989.702606.png 1341847989.702641 depth/1341847989.702641.png +1341847989.738929 rgb/1341847989.738929.png 1341847989.739046 depth/1341847989.739046.png +1341847989.770735 rgb/1341847989.770735.png 1341847989.770752 depth/1341847989.770752.png +1341847989.802890 rgb/1341847989.802890.png 1341847989.802917 depth/1341847989.802917.png +1341847989.838780 rgb/1341847989.838780.png 1341847989.838797 depth/1341847989.838797.png +1341847989.870960 rgb/1341847989.870960.png 1341847989.870960 depth/1341847989.870960.png +1341847989.902718 rgb/1341847989.902718.png 1341847989.902737 depth/1341847989.902737.png +1341847989.938921 rgb/1341847989.938921.png 1341847989.939021 depth/1341847989.939021.png +1341847989.970730 rgb/1341847989.970730.png 1341847989.970757 depth/1341847989.970757.png +1341847990.006923 rgb/1341847990.006923.png 1341847990.006941 depth/1341847990.006941.png +1341847990.039001 rgb/1341847990.039001.png 1341847990.039022 depth/1341847990.039022.png +1341847990.070686 rgb/1341847990.070686.png 1341847990.070724 depth/1341847990.070724.png +1341847990.106701 rgb/1341847990.106701.png 1341847990.106746 depth/1341847990.106746.png +1341847990.139194 rgb/1341847990.139194.png 1341847990.139215 depth/1341847990.139215.png +1341847990.171055 rgb/1341847990.171055.png 1341847990.171115 depth/1341847990.171115.png +1341847990.207022 rgb/1341847990.207022.png 1341847990.207058 depth/1341847990.207058.png +1341847990.238920 rgb/1341847990.238920.png 1341847990.238939 depth/1341847990.238939.png +1341847990.274709 rgb/1341847990.274709.png 1341847990.274725 depth/1341847990.274725.png +1341847990.306743 rgb/1341847990.306743.png 1341847990.307302 depth/1341847990.307302.png +1341847990.339079 rgb/1341847990.339079.png 1341847990.339128 depth/1341847990.339128.png +1341847990.374663 rgb/1341847990.374663.png 1341847990.374681 depth/1341847990.374681.png +1341847990.406760 rgb/1341847990.406760.png 1341847990.407262 depth/1341847990.407262.png +1341847990.442575 rgb/1341847990.442575.png 1341847990.442590 depth/1341847990.442590.png +1341847990.474644 rgb/1341847990.474644.png 1341847990.474662 depth/1341847990.474662.png +1341847990.506783 rgb/1341847990.506783.png 1341847990.506835 depth/1341847990.506835.png +1341847990.542835 rgb/1341847990.542835.png 1341847990.542844 depth/1341847990.542844.png +1341847990.574711 rgb/1341847990.574711.png 1341847990.574721 depth/1341847990.574721.png +1341847990.642783 rgb/1341847990.642783.png 1341847990.642801 depth/1341847990.642801.png +1341847990.674787 rgb/1341847990.674787.png 1341847990.674803 depth/1341847990.674803.png +1341847990.710795 rgb/1341847990.710795.png 1341847990.711535 depth/1341847990.711535.png +1341847990.742712 rgb/1341847990.742712.png 1341847990.742736 depth/1341847990.742736.png +1341847990.774671 rgb/1341847990.774671.png 1341847990.774681 depth/1341847990.774681.png +1341847990.810771 rgb/1341847990.810771.png 1341847990.810817 depth/1341847990.810817.png +1341847990.842713 rgb/1341847990.842713.png 1341847990.842732 depth/1341847990.842732.png +1341847990.874745 rgb/1341847990.874745.png 1341847990.874776 depth/1341847990.874776.png +1341847990.910825 rgb/1341847990.910825.png 1341847990.910852 depth/1341847990.910852.png +1341847990.942685 rgb/1341847990.942685.png 1341847990.942701 depth/1341847990.942701.png +1341847990.978824 rgb/1341847990.978824.png 1341847990.978843 depth/1341847990.978843.png +1341847991.010797 rgb/1341847991.010797.png 1341847991.011241 depth/1341847991.011241.png +1341847991.042752 rgb/1341847991.042752.png 1341847991.042762 depth/1341847991.042762.png +1341847991.078680 rgb/1341847991.078680.png 1341847991.078699 depth/1341847991.078699.png +1341847991.111319 rgb/1341847991.111319.png 1341847991.111338 depth/1341847991.111338.png +1341847991.142784 rgb/1341847991.142784.png 1341847991.142813 depth/1341847991.142813.png +1341847991.178778 rgb/1341847991.178778.png 1341847991.178815 depth/1341847991.178815.png +1341847991.210687 rgb/1341847991.210687.png 1341847991.210701 depth/1341847991.210701.png +1341847991.246842 rgb/1341847991.246842.png 1341847991.246874 depth/1341847991.246874.png +1341847991.278726 rgb/1341847991.278726.png 1341847991.278763 depth/1341847991.278763.png +1341847991.310807 rgb/1341847991.310807.png 1341847991.310849 depth/1341847991.310849.png +1341847991.346722 rgb/1341847991.346722.png 1341847991.346739 depth/1341847991.346739.png +1341847991.378800 rgb/1341847991.378800.png 1341847991.378827 depth/1341847991.378827.png +1341847991.414715 rgb/1341847991.414715.png 1341847991.414740 depth/1341847991.414740.png +1341847991.446744 rgb/1341847991.446744.png 1341847991.446753 depth/1341847991.446753.png +1341847991.478824 rgb/1341847991.478824.png 1341847991.478846 depth/1341847991.478846.png +1341847991.514709 rgb/1341847991.514709.png 1341847991.514730 depth/1341847991.514730.png +1341847991.546725 rgb/1341847991.546725.png 1341847991.546739 depth/1341847991.546739.png +1341847991.578804 rgb/1341847991.578804.png 1341847991.578924 depth/1341847991.578924.png +1341847991.614853 rgb/1341847991.614853.png 1341847991.614880 depth/1341847991.614880.png +1341847991.646714 rgb/1341847991.646714.png 1341847991.646733 depth/1341847991.646733.png +1341847991.689872 rgb/1341847991.689872.png 1341847991.689946 depth/1341847991.689946.png +1341847991.746823 rgb/1341847991.746823.png 1341847991.746844 depth/1341847991.746844.png +1341847991.782657 rgb/1341847991.782657.png 1341847991.782683 depth/1341847991.782683.png +1341847991.814748 rgb/1341847991.814748.png 1341847991.814763 depth/1341847991.814763.png +1341847991.846729 rgb/1341847991.846729.png 1341847991.846745 depth/1341847991.846745.png +1341847991.882784 rgb/1341847991.882784.png 1341847991.882794 depth/1341847991.882794.png +1341847991.915817 rgb/1341847991.915817.png 1341847991.915861 depth/1341847991.915861.png +1341847991.950761 rgb/1341847991.950761.png 1341847991.951013 depth/1341847991.951013.png +1341847991.982826 rgb/1341847991.982826.png 1341847991.982873 depth/1341847991.982873.png +1341847992.014724 rgb/1341847992.014724.png 1341847992.014777 depth/1341847992.014777.png +1341847992.050647 rgb/1341847992.050647.png 1341847992.050662 depth/1341847992.050662.png +1341847992.082793 rgb/1341847992.082793.png 1341847992.082807 depth/1341847992.082807.png +1341847992.114842 rgb/1341847992.114842.png 1341847992.114861 depth/1341847992.114861.png +1341847992.150789 rgb/1341847992.150789.png 1341847992.150826 depth/1341847992.150826.png +1341847992.182813 rgb/1341847992.182813.png 1341847992.182830 depth/1341847992.182830.png +1341847992.218736 rgb/1341847992.218736.png 1341847992.218794 depth/1341847992.218794.png +1341847992.250652 rgb/1341847992.250652.png 1341847992.250777 depth/1341847992.250777.png +1341847992.318683 rgb/1341847992.318683.png 1341847992.318697 depth/1341847992.318697.png +1341847992.350695 rgb/1341847992.350695.png 1341847992.350709 depth/1341847992.350709.png +1341847992.382858 rgb/1341847992.382858.png 1341847992.382868 depth/1341847992.382868.png +1341847992.418855 rgb/1341847992.418855.png 1341847992.418869 depth/1341847992.418869.png +1341847992.450822 rgb/1341847992.450822.png 1341847992.450837 depth/1341847992.450837.png +1341847992.486713 rgb/1341847992.486713.png 1341847992.487395 depth/1341847992.487395.png +1341847992.518735 rgb/1341847992.518735.png 1341847992.518771 depth/1341847992.518771.png +1341847992.550596 rgb/1341847992.550596.png 1341847992.550630 depth/1341847992.550630.png +1341847992.586730 rgb/1341847992.586730.png 1341847992.586755 depth/1341847992.586755.png +1341847992.618832 rgb/1341847992.618832.png 1341847992.618846 depth/1341847992.618846.png +1341847992.654692 rgb/1341847992.654692.png 1341847992.654748 depth/1341847992.654748.png +1341847992.686829 rgb/1341847992.686829.png 1341847992.686855 depth/1341847992.686855.png +1341847992.718718 rgb/1341847992.718718.png 1341847992.718740 depth/1341847992.718740.png +1341847992.754765 rgb/1341847992.754765.png 1341847992.754788 depth/1341847992.754788.png +1341847992.786631 rgb/1341847992.786631.png 1341847992.786663 depth/1341847992.786663.png +1341847992.818723 rgb/1341847992.818723.png 1341847992.818748 depth/1341847992.818748.png +1341847992.854856 rgb/1341847992.854856.png 1341847992.854878 depth/1341847992.854878.png +1341847992.886610 rgb/1341847992.886610.png 1341847992.886642 depth/1341847992.886642.png +1341847992.922713 rgb/1341847992.922713.png 1341847992.922733 depth/1341847992.922733.png +1341847992.954645 rgb/1341847992.954645.png 1341847992.955395 depth/1341847992.955395.png +1341847992.986720 rgb/1341847992.986720.png 1341847992.986737 depth/1341847992.986737.png +1341847993.022736 rgb/1341847993.022736.png 1341847993.022781 depth/1341847993.022781.png +1341847993.054757 rgb/1341847993.054757.png 1341847993.054770 depth/1341847993.054770.png +1341847993.086751 rgb/1341847993.086751.png 1341847993.086778 depth/1341847993.086778.png +1341847993.122668 rgb/1341847993.122668.png 1341847993.122697 depth/1341847993.122697.png +1341847993.154688 rgb/1341847993.154688.png 1341847993.154697 depth/1341847993.154697.png +1341847993.190779 rgb/1341847993.190779.png 1341847993.190813 depth/1341847993.190813.png +1341847993.222703 rgb/1341847993.222703.png 1341847993.222720 depth/1341847993.222720.png +1341847993.261799 rgb/1341847993.261799.png 1341847993.261866 depth/1341847993.261866.png +1341847993.322794 rgb/1341847993.322794.png 1341847993.322820 depth/1341847993.322820.png +1341847993.354702 rgb/1341847993.354702.png 1341847993.354727 depth/1341847993.354727.png +1341847993.390722 rgb/1341847993.390722.png 1341847993.391295 depth/1341847993.391295.png +1341847993.422745 rgb/1341847993.422745.png 1341847993.422772 depth/1341847993.422772.png +1341847993.458848 rgb/1341847993.458848.png 1341847993.458981 depth/1341847993.458981.png +1341847993.490680 rgb/1341847993.490680.png 1341847993.490694 depth/1341847993.490694.png +1341847993.522707 rgb/1341847993.522707.png 1341847993.522726 depth/1341847993.522726.png +1341847993.558719 rgb/1341847993.558719.png 1341847993.558743 depth/1341847993.558743.png +1341847993.590981 rgb/1341847993.590981.png 1341847993.591005 depth/1341847993.591005.png +1341847993.626764 rgb/1341847993.626764.png 1341847993.626777 depth/1341847993.626777.png +1341847993.658928 rgb/1341847993.658928.png 1341847993.658977 depth/1341847993.658977.png +1341847993.690739 rgb/1341847993.690739.png 1341847993.691246 depth/1341847993.691246.png +1341847993.727062 rgb/1341847993.727062.png 1341847993.727881 depth/1341847993.727881.png +1341847993.790887 rgb/1341847993.790887.png 1341847993.791002 depth/1341847993.791002.png +1341847993.826735 rgb/1341847993.826735.png 1341847993.826846 depth/1341847993.826846.png +1341847993.858891 rgb/1341847993.858891.png 1341847993.858904 depth/1341847993.858904.png +1341847993.901726 rgb/1341847993.901726.png 1341847993.902671 depth/1341847993.902671.png +1341847993.933661 rgb/1341847993.933661.png 1341847993.933692 depth/1341847993.933692.png +1341847993.965821 rgb/1341847993.965821.png 1341847993.965832 depth/1341847993.965832.png +1341847994.001991 rgb/1341847994.001991.png 1341847994.002756 depth/1341847994.002756.png +1341847994.034008 rgb/1341847994.034008.png 1341847994.034124 depth/1341847994.034124.png +1341847994.065706 rgb/1341847994.065706.png 1341847994.065765 depth/1341847994.065765.png +1341847994.101772 rgb/1341847994.101772.png 1341847994.101785 depth/1341847994.101785.png +1341847994.133885 rgb/1341847994.133885.png 1341847994.133915 depth/1341847994.133915.png +1341847994.169705 rgb/1341847994.169705.png 1341847994.169723 depth/1341847994.169723.png +1341847994.201675 rgb/1341847994.201675.png 1341847994.201710 depth/1341847994.201710.png +1341847994.233618 rgb/1341847994.233618.png 1341847994.233648 depth/1341847994.233648.png +1341847994.269680 rgb/1341847994.269680.png 1341847994.269699 depth/1341847994.269699.png +1341847994.301751 rgb/1341847994.301751.png 1341847994.301791 depth/1341847994.301791.png +1341847994.333755 rgb/1341847994.333755.png 1341847994.333773 depth/1341847994.333773.png +1341847994.369712 rgb/1341847994.369712.png 1341847994.369729 depth/1341847994.369729.png +1341847994.401655 rgb/1341847994.401655.png 1341847994.401681 depth/1341847994.401681.png +1341847994.433802 rgb/1341847994.433802.png 1341847994.434241 depth/1341847994.434241.png +1341847994.469690 rgb/1341847994.469690.png 1341847994.469702 depth/1341847994.469702.png +1341847994.501736 rgb/1341847994.501736.png 1341847994.501770 depth/1341847994.501770.png +1341847994.537738 rgb/1341847994.537738.png 1341847994.537760 depth/1341847994.537760.png +1341847994.569734 rgb/1341847994.569734.png 1341847994.570212 depth/1341847994.570212.png +1341847994.601688 rgb/1341847994.601688.png 1341847994.601735 depth/1341847994.601735.png +1341847994.637836 rgb/1341847994.637836.png 1341847994.637851 depth/1341847994.637851.png +1341847994.669750 rgb/1341847994.669750.png 1341847994.669907 depth/1341847994.669907.png +1341847994.701643 rgb/1341847994.701643.png 1341847994.701657 depth/1341847994.701657.png +1341847994.769803 rgb/1341847994.769803.png 1341847994.769892 depth/1341847994.769892.png +1341847994.831306 rgb/1341847994.831306.png 1341847994.831318 depth/1341847994.831318.png +1341847994.866828 rgb/1341847994.866828.png 1341847994.866892 depth/1341847994.866892.png +1341847994.898727 rgb/1341847994.898727.png 1341847994.898740 depth/1341847994.898740.png +1341847994.930711 rgb/1341847994.930711.png 1341847994.930781 depth/1341847994.930781.png +1341847994.966673 rgb/1341847994.966673.png 1341847994.966794 depth/1341847994.966794.png +1341847994.998679 rgb/1341847994.998679.png 1341847994.998726 depth/1341847994.998726.png +1341847995.030768 rgb/1341847995.030768.png 1341847995.030829 depth/1341847995.030829.png +1341847995.066673 rgb/1341847995.066673.png 1341847995.066736 depth/1341847995.066736.png +1341847995.098711 rgb/1341847995.098711.png 1341847995.098802 depth/1341847995.098802.png +1341847995.134939 rgb/1341847995.134939.png 1341847995.134968 depth/1341847995.134968.png +1341847995.166644 rgb/1341847995.166644.png 1341847995.166683 depth/1341847995.166683.png +1341847995.198787 rgb/1341847995.198787.png 1341847995.198800 depth/1341847995.198800.png +1341847995.234663 rgb/1341847995.234663.png 1341847995.234690 depth/1341847995.234690.png +1341847995.266776 rgb/1341847995.266776.png 1341847995.266841 depth/1341847995.266841.png +1341847995.298812 rgb/1341847995.298812.png 1341847995.298807 depth/1341847995.298807.png +1341847995.334686 rgb/1341847995.334686.png 1341847995.334708 depth/1341847995.334708.png +1341847995.366701 rgb/1341847995.366701.png 1341847995.366716 depth/1341847995.366716.png +1341847995.402793 rgb/1341847995.402793.png 1341847995.402804 depth/1341847995.402804.png +1341847995.434743 rgb/1341847995.434743.png 1341847995.434769 depth/1341847995.434769.png +1341847995.466776 rgb/1341847995.466776.png 1341847995.466791 depth/1341847995.466791.png +1341847995.502702 rgb/1341847995.502702.png 1341847995.502726 depth/1341847995.502726.png +1341847995.534752 rgb/1341847995.534752.png 1341847995.534803 depth/1341847995.534803.png +1341847995.566681 rgb/1341847995.566681.png 1341847995.566696 depth/1341847995.566696.png +1341847995.602698 rgb/1341847995.602698.png 1341847995.602714 depth/1341847995.602714.png +1341847995.634814 rgb/1341847995.634814.png 1341847995.634845 depth/1341847995.634845.png +1341847995.670769 rgb/1341847995.670769.png 1341847995.670798 depth/1341847995.670798.png +1341847995.702780 rgb/1341847995.702780.png 1341847995.702795 depth/1341847995.702795.png +1341847995.734774 rgb/1341847995.734774.png 1341847995.734786 depth/1341847995.734786.png +1341847995.770704 rgb/1341847995.770704.png 1341847995.770716 depth/1341847995.770716.png +1341847995.802752 rgb/1341847995.802752.png 1341847995.802771 depth/1341847995.802771.png +1341847995.838779 rgb/1341847995.838779.png 1341847995.838812 depth/1341847995.838812.png +1341847995.870641 rgb/1341847995.870641.png 1341847995.870667 depth/1341847995.870667.png +1341847995.902803 rgb/1341847995.902803.png 1341847995.902829 depth/1341847995.902829.png +1341847995.938733 rgb/1341847995.938733.png 1341847995.938742 depth/1341847995.938742.png +1341847995.970733 rgb/1341847995.970733.png 1341847995.970762 depth/1341847995.970762.png +1341847996.002709 rgb/1341847996.002709.png 1341847996.002725 depth/1341847996.002725.png +1341847996.038762 rgb/1341847996.038762.png 1341847996.038793 depth/1341847996.038793.png +1341847996.070721 rgb/1341847996.070721.png 1341847996.070742 depth/1341847996.070742.png +1341847996.106729 rgb/1341847996.106729.png 1341847996.106752 depth/1341847996.106752.png +1341847996.138845 rgb/1341847996.138845.png 1341847996.138877 depth/1341847996.138877.png +1341847996.170714 rgb/1341847996.170714.png 1341847996.170740 depth/1341847996.170740.png +1341847996.206643 rgb/1341847996.206643.png 1341847996.206677 depth/1341847996.206677.png +1341847996.239003 rgb/1341847996.239003.png 1341847996.239037 depth/1341847996.239037.png +1341847996.270754 rgb/1341847996.270754.png 1341847996.270779 depth/1341847996.270779.png +1341847996.338944 rgb/1341847996.338944.png 1341847996.338989 depth/1341847996.338989.png +1341847996.374711 rgb/1341847996.374711.png 1341847996.374732 depth/1341847996.374732.png +1341847996.406705 rgb/1341847996.406705.png 1341847996.406731 depth/1341847996.406731.png +1341847996.438632 rgb/1341847996.438632.png 1341847996.438706 depth/1341847996.438706.png +1341847996.474783 rgb/1341847996.474783.png 1341847996.474837 depth/1341847996.474837.png +1341847996.506707 rgb/1341847996.506707.png 1341847996.506720 depth/1341847996.506720.png +1341847996.538771 rgb/1341847996.538771.png 1341847996.538791 depth/1341847996.538791.png +1341847996.574796 rgb/1341847996.574796.png 1341847996.574812 depth/1341847996.574812.png +1341847996.607104 rgb/1341847996.607104.png 1341847996.607158 depth/1341847996.607158.png +1341847996.642752 rgb/1341847996.642752.png 1341847996.642767 depth/1341847996.642767.png +1341847996.674774 rgb/1341847996.674774.png 1341847996.674789 depth/1341847996.674789.png +1341847996.706896 rgb/1341847996.706896.png 1341847996.706910 depth/1341847996.706910.png +1341847996.742663 rgb/1341847996.742663.png 1341847996.742685 depth/1341847996.742685.png +1341847996.774747 rgb/1341847996.774747.png 1341847996.774759 depth/1341847996.774759.png +1341847996.806787 rgb/1341847996.806787.png 1341847996.806842 depth/1341847996.806842.png +1341847996.842763 rgb/1341847996.842763.png 1341847996.842787 depth/1341847996.842787.png +1341847996.874766 rgb/1341847996.874766.png 1341847996.874793 depth/1341847996.874793.png +1341847996.910785 rgb/1341847996.910785.png 1341847996.911011 depth/1341847996.911011.png +1341847996.942686 rgb/1341847996.942686.png 1341847996.943167 depth/1341847996.943167.png +1341847996.974782 rgb/1341847996.974782.png 1341847996.974796 depth/1341847996.974796.png +1341847997.010744 rgb/1341847997.010744.png 1341847997.010766 depth/1341847997.010766.png +1341847997.042675 rgb/1341847997.042675.png 1341847997.042684 depth/1341847997.042684.png +1341847997.078725 rgb/1341847997.078725.png 1341847997.078744 depth/1341847997.078744.png +1341847997.142993 rgb/1341847997.142993.png 1341847997.143035 depth/1341847997.143035.png +1341847997.178794 rgb/1341847997.178794.png 1341847997.178824 depth/1341847997.178824.png +1341847997.210888 rgb/1341847997.210888.png 1341847997.210908 depth/1341847997.210908.png +1341847997.242959 rgb/1341847997.242959.png 1341847997.242983 depth/1341847997.242983.png +1341847997.278756 rgb/1341847997.278756.png 1341847997.279364 depth/1341847997.279364.png +1341847997.311412 rgb/1341847997.311412.png 1341847997.311453 depth/1341847997.311453.png +1341847997.346642 rgb/1341847997.346642.png 1341847997.346654 depth/1341847997.346654.png +1341847997.378668 rgb/1341847997.378668.png 1341847997.378700 depth/1341847997.378700.png +1341847997.410817 rgb/1341847997.410817.png 1341847997.411689 depth/1341847997.411689.png +1341847997.446693 rgb/1341847997.446693.png 1341847997.446712 depth/1341847997.446712.png +1341847997.478752 rgb/1341847997.478752.png 1341847997.478763 depth/1341847997.478763.png +1341847997.510941 rgb/1341847997.510941.png 1341847997.511370 depth/1341847997.511370.png +1341847997.546599 rgb/1341847997.546599.png 1341847997.546615 depth/1341847997.546615.png +1341847997.578740 rgb/1341847997.578740.png 1341847997.578767 depth/1341847997.578767.png +1341847997.614736 rgb/1341847997.614736.png 1341847997.614761 depth/1341847997.614761.png +1341847997.646995 rgb/1341847997.646995.png 1341847997.647012 depth/1341847997.647012.png +1341847997.678842 rgb/1341847997.678842.png 1341847997.678858 depth/1341847997.678858.png +1341847997.714639 rgb/1341847997.714639.png 1341847997.714649 depth/1341847997.714649.png +1341847997.746602 rgb/1341847997.746602.png 1341847997.746633 depth/1341847997.746633.png +1341847997.778734 rgb/1341847997.778734.png 1341847997.778758 depth/1341847997.778758.png +1341847997.846906 rgb/1341847997.846906.png 1341847997.846947 depth/1341847997.846947.png +1341847997.882641 rgb/1341847997.882641.png 1341847997.883109 depth/1341847997.883109.png +1341847997.915169 rgb/1341847997.915169.png 1341847997.915187 depth/1341847997.915187.png +1341847997.946999 rgb/1341847997.946999.png 1341847997.947048 depth/1341847997.947048.png +1341847997.982715 rgb/1341847997.982715.png 1341847997.982857 depth/1341847997.982857.png +1341847998.014866 rgb/1341847998.014866.png 1341847998.014891 depth/1341847998.014891.png +1341847998.050805 rgb/1341847998.050805.png 1341847998.050878 depth/1341847998.050878.png +1341847998.082631 rgb/1341847998.082631.png 1341847998.082647 depth/1341847998.082647.png +1341847998.122275 rgb/1341847998.122275.png 1341847998.123265 depth/1341847998.123265.png +1341847998.154051 rgb/1341847998.154051.png 1341847998.154516 depth/1341847998.154516.png +1341847998.185663 rgb/1341847998.185663.png 1341847998.185678 depth/1341847998.185678.png +1341847998.253760 rgb/1341847998.253760.png 1341847998.253822 depth/1341847998.253822.png +1341847998.318804 rgb/1341847998.318804.png 1341847998.318825 depth/1341847998.318825.png +1341847998.351206 rgb/1341847998.351206.png 1341847998.351221 depth/1341847998.351221.png +1341847998.382723 rgb/1341847998.382723.png 1341847998.382744 depth/1341847998.382744.png +1341847998.419237 rgb/1341847998.419237.png 1341847998.419264 depth/1341847998.419264.png +1341847998.450786 rgb/1341847998.450786.png 1341847998.450814 depth/1341847998.450814.png +1341847998.484037 rgb/1341847998.484037.png 1341847998.484057 depth/1341847998.484057.png +1341847998.518722 rgb/1341847998.518722.png 1341847998.518744 depth/1341847998.518744.png +1341847998.550746 rgb/1341847998.550746.png 1341847998.550766 depth/1341847998.550766.png +1341847998.586740 rgb/1341847998.586740.png 1341847998.586754 depth/1341847998.586754.png +1341847998.618771 rgb/1341847998.618771.png 1341847998.618853 depth/1341847998.618853.png +1341847998.650736 rgb/1341847998.650736.png 1341847998.650754 depth/1341847998.650754.png +1341847998.686862 rgb/1341847998.686862.png 1341847998.686872 depth/1341847998.686872.png +1341847998.718741 rgb/1341847998.718741.png 1341847998.718754 depth/1341847998.718754.png +1341847998.750838 rgb/1341847998.750838.png 1341847998.750862 depth/1341847998.750862.png +1341847998.786762 rgb/1341847998.786762.png 1341847998.786777 depth/1341847998.786777.png +1341847998.818756 rgb/1341847998.818756.png 1341847998.818773 depth/1341847998.818773.png +1341847998.854711 rgb/1341847998.854711.png 1341847998.854733 depth/1341847998.854733.png +1341847998.886699 rgb/1341847998.886699.png 1341847998.886727 depth/1341847998.886727.png +1341847998.918666 rgb/1341847998.918666.png 1341847998.918681 depth/1341847998.918681.png +1341847998.954799 rgb/1341847998.954799.png 1341847998.954812 depth/1341847998.954812.png +1341847998.986722 rgb/1341847998.986722.png 1341847998.986738 depth/1341847998.986738.png +1341847999.018809 rgb/1341847999.018809.png 1341847999.018827 depth/1341847999.018827.png +1341847999.054894 rgb/1341847999.054894.png 1341847999.054947 depth/1341847999.054947.png +1341847999.086763 rgb/1341847999.086763.png 1341847999.086789 depth/1341847999.086789.png +1341847999.122718 rgb/1341847999.122718.png 1341847999.122734 depth/1341847999.122734.png +1341847999.154891 rgb/1341847999.154891.png 1341847999.154910 depth/1341847999.154910.png +1341847999.186738 rgb/1341847999.186738.png 1341847999.186756 depth/1341847999.186756.png +1341847999.222717 rgb/1341847999.222717.png 1341847999.222728 depth/1341847999.222728.png +1341847999.290995 rgb/1341847999.290995.png 1341847999.291097 depth/1341847999.291097.png +1341847999.322701 rgb/1341847999.322701.png 1341847999.322715 depth/1341847999.322715.png +1341847999.354861 rgb/1341847999.354861.png 1341847999.354880 depth/1341847999.354880.png +1341847999.390790 rgb/1341847999.390790.png 1341847999.390873 depth/1341847999.390873.png +1341847999.423935 rgb/1341847999.423935.png 1341847999.423953 depth/1341847999.423953.png +1341847999.454933 rgb/1341847999.454933.png 1341847999.454965 depth/1341847999.454965.png +1341847999.490878 rgb/1341847999.490878.png 1341847999.490960 depth/1341847999.490960.png +1341847999.522673 rgb/1341847999.522673.png 1341847999.522711 depth/1341847999.522711.png +1341847999.558926 rgb/1341847999.558926.png 1341847999.558949 depth/1341847999.558949.png +1341847999.590686 rgb/1341847999.590686.png 1341847999.590703 depth/1341847999.590703.png +1341847999.622896 rgb/1341847999.622896.png 1341847999.622914 depth/1341847999.622914.png +1341847999.658843 rgb/1341847999.658843.png 1341847999.658860 depth/1341847999.658860.png +1341847999.691111 rgb/1341847999.691111.png 1341847999.691169 depth/1341847999.691169.png +1341847999.722697 rgb/1341847999.722697.png 1341847999.722745 depth/1341847999.722745.png +1341847999.758778 rgb/1341847999.758778.png 1341847999.758816 depth/1341847999.758816.png +1341847999.791003 rgb/1341847999.791003.png 1341847999.791018 depth/1341847999.791018.png +1341847999.826747 rgb/1341847999.826747.png 1341847999.826760 depth/1341847999.826760.png +1341847999.858757 rgb/1341847999.858757.png 1341847999.858819 depth/1341847999.858819.png +1341847999.897730 rgb/1341847999.897730.png 1341847999.897755 depth/1341847999.897755.png +1341847999.958786 rgb/1341847999.958786.png 1341847999.958798 depth/1341847999.958798.png +1341847999.990848 rgb/1341847999.990848.png 1341847999.991017 depth/1341847999.991017.png +1341848000.026656 rgb/1341848000.026656.png 1341848000.026670 depth/1341848000.026670.png +1341848000.058724 rgb/1341848000.058724.png 1341848000.058808 depth/1341848000.058808.png +1341848000.094780 rgb/1341848000.094780.png 1341848000.094794 depth/1341848000.094794.png +1341848000.126737 rgb/1341848000.126737.png 1341848000.126804 depth/1341848000.126804.png +1341848000.158633 rgb/1341848000.158633.png 1341848000.158647 depth/1341848000.158647.png +1341848000.194808 rgb/1341848000.194808.png 1341848000.194844 depth/1341848000.194844.png +1341848000.227063 rgb/1341848000.227063.png 1341848000.228401 depth/1341848000.228401.png +1341848000.266975 rgb/1341848000.266975.png 1341848000.267040 depth/1341848000.267040.png +1341848000.327132 rgb/1341848000.327132.png 1341848000.327144 depth/1341848000.327144.png +1341848000.362696 rgb/1341848000.362696.png 1341848000.362714 depth/1341848000.362714.png +1341848000.394654 rgb/1341848000.394654.png 1341848000.394668 depth/1341848000.394668.png +1341848000.426772 rgb/1341848000.426772.png 1341848000.426894 depth/1341848000.426894.png +1341848000.462696 rgb/1341848000.462696.png 1341848000.462704 depth/1341848000.462704.png +1341848000.494711 rgb/1341848000.494711.png 1341848000.494720 depth/1341848000.494720.png +1341848000.530849 rgb/1341848000.530849.png 1341848000.530871 depth/1341848000.530871.png +1341848000.562770 rgb/1341848000.562770.png 1341848000.562803 depth/1341848000.562803.png +1341848000.594838 rgb/1341848000.594838.png 1341848000.594876 depth/1341848000.594876.png +1341848000.630641 rgb/1341848000.630641.png 1341848000.630658 depth/1341848000.630658.png +1341848000.662663 rgb/1341848000.662663.png 1341848000.662683 depth/1341848000.662683.png +1341848000.695377 rgb/1341848000.695377.png 1341848000.695394 depth/1341848000.695394.png +1341848000.730805 rgb/1341848000.730805.png 1341848000.730825 depth/1341848000.730825.png +1341848000.762655 rgb/1341848000.762655.png 1341848000.762704 depth/1341848000.762704.png +1341848000.798741 rgb/1341848000.798741.png 1341848000.798754 depth/1341848000.798754.png +1341848000.830729 rgb/1341848000.830729.png 1341848000.830744 depth/1341848000.830744.png +1341848000.862750 rgb/1341848000.862750.png 1341848000.862762 depth/1341848000.862762.png +1341848000.898723 rgb/1341848000.898723.png 1341848000.898741 depth/1341848000.898741.png +1341848000.930722 rgb/1341848000.930722.png 1341848000.930740 depth/1341848000.930740.png +1341848000.963197 rgb/1341848000.963197.png 1341848000.963623 depth/1341848000.963623.png +1341848000.998783 rgb/1341848000.998783.png 1341848000.998807 depth/1341848000.998807.png +1341848001.030740 rgb/1341848001.030740.png 1341848001.030757 depth/1341848001.030757.png +1341848001.067042 rgb/1341848001.067042.png 1341848001.067105 depth/1341848001.067105.png +1341848001.098800 rgb/1341848001.098800.png 1341848001.098830 depth/1341848001.098830.png +1341848001.130714 rgb/1341848001.130714.png 1341848001.130736 depth/1341848001.130736.png +1341848001.205951 rgb/1341848001.205951.png 1341848001.206049 depth/1341848001.206049.png +1341848001.266775 rgb/1341848001.266775.png 1341848001.266790 depth/1341848001.266790.png +1341848001.299150 rgb/1341848001.299150.png 1341848001.299167 depth/1341848001.299167.png +1341848001.334803 rgb/1341848001.334803.png 1341848001.334830 depth/1341848001.334830.png +1341848001.366701 rgb/1341848001.366701.png 1341848001.366725 depth/1341848001.366725.png +1341848001.399276 rgb/1341848001.399276.png 1341848001.399293 depth/1341848001.399293.png +1341848001.434718 rgb/1341848001.434718.png 1341848001.434760 depth/1341848001.434760.png +1341848001.466720 rgb/1341848001.466720.png 1341848001.466756 depth/1341848001.466756.png +1341848001.502686 rgb/1341848001.502686.png 1341848001.502748 depth/1341848001.502748.png +1341848001.534905 rgb/1341848001.534905.png 1341848001.535602 depth/1341848001.535602.png +1341848001.567011 rgb/1341848001.567011.png 1341848001.567686 depth/1341848001.567686.png +1341848001.602899 rgb/1341848001.602899.png 1341848001.603041 depth/1341848001.603041.png +1341848001.634657 rgb/1341848001.634657.png 1341848001.634679 depth/1341848001.634679.png +1341848001.666646 rgb/1341848001.666646.png 1341848001.666695 depth/1341848001.666695.png +1341848001.734859 rgb/1341848001.734859.png 1341848001.734874 depth/1341848001.734874.png +1341848001.770725 rgb/1341848001.770725.png 1341848001.771400 depth/1341848001.771400.png +1341848001.802763 rgb/1341848001.802763.png 1341848001.803395 depth/1341848001.803395.png +1341848001.834761 rgb/1341848001.834761.png 1341848001.834778 depth/1341848001.834778.png +1341848001.870724 rgb/1341848001.870724.png 1341848001.870742 depth/1341848001.870742.png +1341848001.902749 rgb/1341848001.902749.png 1341848001.902764 depth/1341848001.902764.png +1341848001.934732 rgb/1341848001.934732.png 1341848001.934794 depth/1341848001.934794.png +1341848001.970708 rgb/1341848001.970708.png 1341848001.970782 depth/1341848001.970782.png +1341848002.002731 rgb/1341848002.002731.png 1341848002.002752 depth/1341848002.002752.png +1341848002.038858 rgb/1341848002.038858.png 1341848002.038880 depth/1341848002.038880.png +1341848002.070767 rgb/1341848002.070767.png 1341848002.070781 depth/1341848002.070781.png +1341848002.102720 rgb/1341848002.102720.png 1341848002.102819 depth/1341848002.102819.png +1341848002.138653 rgb/1341848002.138653.png 1341848002.138667 depth/1341848002.138667.png +1341848002.171849 rgb/1341848002.171849.png 1341848002.171908 depth/1341848002.171908.png +1341848002.202698 rgb/1341848002.202698.png 1341848002.202713 depth/1341848002.202713.png +1341848002.238731 rgb/1341848002.238731.png 1341848002.238742 depth/1341848002.238742.png +1341848002.270763 rgb/1341848002.270763.png 1341848002.270780 depth/1341848002.270780.png +1341848002.306708 rgb/1341848002.306708.png 1341848002.306724 depth/1341848002.306724.png +1341848002.338850 rgb/1341848002.338850.png 1341848002.338920 depth/1341848002.338920.png +1341848002.370786 rgb/1341848002.370786.png 1341848002.371472 depth/1341848002.371472.png +1341848002.406793 rgb/1341848002.406793.png 1341848002.406802 depth/1341848002.406802.png +1341848002.438766 rgb/1341848002.438766.png 1341848002.438797 depth/1341848002.438797.png +1341848002.474697 rgb/1341848002.474697.png 1341848002.474720 depth/1341848002.474720.png +1341848002.506756 rgb/1341848002.506756.png 1341848002.506777 depth/1341848002.506777.png +1341848002.538812 rgb/1341848002.538812.png 1341848002.539346 depth/1341848002.539346.png +1341848002.574707 rgb/1341848002.574707.png 1341848002.574741 depth/1341848002.574741.png +1341848002.606780 rgb/1341848002.606780.png 1341848002.606818 depth/1341848002.606818.png +1341848002.639359 rgb/1341848002.639359.png 1341848002.639381 depth/1341848002.639381.png +1341848002.674651 rgb/1341848002.674651.png 1341848002.674664 depth/1341848002.674664.png +1341848002.713789 rgb/1341848002.713789.png 1341848002.713950 depth/1341848002.713950.png +1341848002.774760 rgb/1341848002.774760.png 1341848002.774778 depth/1341848002.774778.png +1341848002.806780 rgb/1341848002.806780.png 1341848002.806797 depth/1341848002.806797.png +1341848002.842833 rgb/1341848002.842833.png 1341848002.842854 depth/1341848002.842854.png +1341848002.875238 rgb/1341848002.875238.png 1341848002.875294 depth/1341848002.875294.png +1341848002.906656 rgb/1341848002.906656.png 1341848002.906670 depth/1341848002.906670.png +1341848002.943323 rgb/1341848002.943323.png 1341848002.943336 depth/1341848002.943336.png +1341848002.974597 rgb/1341848002.974597.png 1341848002.974617 depth/1341848002.974617.png +1341848003.010885 rgb/1341848003.010885.png 1341848003.010926 depth/1341848003.010926.png +1341848003.042638 rgb/1341848003.042638.png 1341848003.042649 depth/1341848003.042649.png +1341848003.074988 rgb/1341848003.074988.png 1341848003.075599 depth/1341848003.075599.png +1341848003.110641 rgb/1341848003.110641.png 1341848003.110659 depth/1341848003.110659.png +1341848003.142626 rgb/1341848003.142626.png 1341848003.142643 depth/1341848003.142643.png +1341848003.242926 rgb/1341848003.242926.png 1341848003.243104 depth/1341848003.243104.png +1341848003.278886 rgb/1341848003.278886.png 1341848003.278901 depth/1341848003.278901.png +1341848003.310739 rgb/1341848003.310739.png 1341848003.310752 depth/1341848003.310752.png +1341848003.342708 rgb/1341848003.342708.png 1341848003.342720 depth/1341848003.342720.png +1341848003.378999 rgb/1341848003.378999.png 1341848003.379019 depth/1341848003.379019.png +1341848003.410779 rgb/1341848003.410779.png 1341848003.410799 depth/1341848003.410799.png +1341848003.442728 rgb/1341848003.442728.png 1341848003.442757 depth/1341848003.442757.png +1341848003.478703 rgb/1341848003.478703.png 1341848003.478734 depth/1341848003.478734.png +1341848003.510700 rgb/1341848003.510700.png 1341848003.510745 depth/1341848003.510745.png +1341848003.546854 rgb/1341848003.546854.png 1341848003.548421 depth/1341848003.548421.png +1341848003.578749 rgb/1341848003.578749.png 1341848003.578762 depth/1341848003.578762.png +1341848003.617886 rgb/1341848003.617886.png 1341848003.617927 depth/1341848003.617927.png +1341848003.649972 rgb/1341848003.649972.png 1341848003.649997 depth/1341848003.649997.png +1341848003.685816 rgb/1341848003.685816.png 1341848003.685833 depth/1341848003.685833.png +1341848003.717853 rgb/1341848003.717853.png 1341848003.718179 depth/1341848003.718179.png +1341848003.753761 rgb/1341848003.753761.png 1341848003.753810 depth/1341848003.753810.png +1341848003.785807 rgb/1341848003.785807.png 1341848003.785825 depth/1341848003.785825.png +1341848003.817941 rgb/1341848003.817941.png 1341848003.817959 depth/1341848003.817959.png +1341848003.853971 rgb/1341848003.853971.png 1341848003.853983 depth/1341848003.853983.png +1341848003.885751 rgb/1341848003.885751.png 1341848003.885767 depth/1341848003.885767.png +1341848003.921688 rgb/1341848003.921688.png 1341848003.921702 depth/1341848003.921702.png +1341848003.953824 rgb/1341848003.953824.png 1341848003.953837 depth/1341848003.953837.png +1341848003.985789 rgb/1341848003.985789.png 1341848003.986490 depth/1341848003.986490.png +1341848004.021643 rgb/1341848004.021643.png 1341848004.021656 depth/1341848004.021656.png +1341848004.053778 rgb/1341848004.053778.png 1341848004.053793 depth/1341848004.053793.png +1341848004.089723 rgb/1341848004.089723.png 1341848004.089739 depth/1341848004.089739.png +1341848004.121698 rgb/1341848004.121698.png 1341848004.121723 depth/1341848004.121723.png +1341848004.153695 rgb/1341848004.153695.png 1341848004.154409 depth/1341848004.154409.png +1341848004.189785 rgb/1341848004.189785.png 1341848004.189798 depth/1341848004.189798.png +1341848004.221773 rgb/1341848004.221773.png 1341848004.221783 depth/1341848004.221783.png +1341848004.257760 rgb/1341848004.257760.png 1341848004.257772 depth/1341848004.257772.png +1341848004.289843 rgb/1341848004.289843.png 1341848004.289860 depth/1341848004.289860.png +1341848004.321820 rgb/1341848004.321820.png 1341848004.321834 depth/1341848004.321834.png +1341848004.357934 rgb/1341848004.357934.png 1341848004.357948 depth/1341848004.357948.png +1341848004.389781 rgb/1341848004.389781.png 1341848004.389798 depth/1341848004.389798.png +1341848004.421857 rgb/1341848004.421857.png 1341848004.421982 depth/1341848004.421982.png +1341848004.457752 rgb/1341848004.457752.png 1341848004.457769 depth/1341848004.457769.png +1341848004.489793 rgb/1341848004.489793.png 1341848004.489811 depth/1341848004.489811.png +1341848004.525726 rgb/1341848004.525726.png 1341848004.525737 depth/1341848004.525737.png +1341848004.557784 rgb/1341848004.557784.png 1341848004.557799 depth/1341848004.557799.png +1341848004.589761 rgb/1341848004.589761.png 1341848004.590427 depth/1341848004.590427.png +1341848004.625757 rgb/1341848004.625757.png 1341848004.625778 depth/1341848004.625778.png +1341848004.657882 rgb/1341848004.657882.png 1341848004.657913 depth/1341848004.657913.png +1341848004.689871 rgb/1341848004.689871.png 1341848004.689888 depth/1341848004.689888.png +1341848004.725815 rgb/1341848004.725815.png 1341848004.725831 depth/1341848004.725831.png +1341848004.757723 rgb/1341848004.757723.png 1341848004.757745 depth/1341848004.757745.png +1341848004.789709 rgb/1341848004.789709.png 1341848004.789719 depth/1341848004.789719.png +1341848004.825782 rgb/1341848004.825782.png 1341848004.825792 depth/1341848004.825792.png +1341848004.857706 rgb/1341848004.857706.png 1341848004.857726 depth/1341848004.857726.png +1341848004.889791 rgb/1341848004.889791.png 1341848004.889806 depth/1341848004.889806.png +1341848004.925788 rgb/1341848004.925788.png 1341848004.925821 depth/1341848004.925821.png +1341848004.957758 rgb/1341848004.957758.png 1341848004.957773 depth/1341848004.957773.png +1341848004.993849 rgb/1341848004.993849.png 1341848004.993863 depth/1341848004.993863.png +1341848005.025661 rgb/1341848005.025661.png 1341848005.025661 depth/1341848005.025661.png +1341848005.057739 rgb/1341848005.057739.png 1341848005.058466 depth/1341848005.058466.png +1341848005.093879 rgb/1341848005.093879.png 1341848005.093906 depth/1341848005.093906.png +1341848005.125700 rgb/1341848005.125700.png 1341848005.125710 depth/1341848005.125710.png +1341848005.157668 rgb/1341848005.157668.png 1341848005.157676 depth/1341848005.157676.png +1341848005.193749 rgb/1341848005.193749.png 1341848005.193763 depth/1341848005.193763.png +1341848005.225713 rgb/1341848005.225713.png 1341848005.225725 depth/1341848005.225725.png +1341848005.257748 rgb/1341848005.257748.png 1341848005.257761 depth/1341848005.257761.png +1341848005.293718 rgb/1341848005.293718.png 1341848005.293733 depth/1341848005.293733.png +1341848005.325870 rgb/1341848005.325870.png 1341848005.325901 depth/1341848005.325901.png +1341848005.357655 rgb/1341848005.357655.png 1341848005.357695 depth/1341848005.357695.png +1341848005.393694 rgb/1341848005.393694.png 1341848005.393707 depth/1341848005.393707.png +1341848005.425692 rgb/1341848005.425692.png 1341848005.425710 depth/1341848005.425710.png +1341848005.461850 rgb/1341848005.461850.png 1341848005.461862 depth/1341848005.461862.png +1341848005.493689 rgb/1341848005.493689.png 1341848005.493702 depth/1341848005.493702.png +1341848005.525844 rgb/1341848005.525844.png 1341848005.526425 depth/1341848005.526425.png +1341848005.561789 rgb/1341848005.561789.png 1341848005.561806 depth/1341848005.561806.png +1341848005.593673 rgb/1341848005.593673.png 1341848005.593689 depth/1341848005.593689.png +1341848005.629831 rgb/1341848005.629831.png 1341848005.629854 depth/1341848005.629854.png +1341848005.661802 rgb/1341848005.661802.png 1341848005.661818 depth/1341848005.661818.png +1341848005.693760 rgb/1341848005.693760.png 1341848005.693782 depth/1341848005.693782.png +1341848005.729741 rgb/1341848005.729741.png 1341848005.729756 depth/1341848005.729756.png +1341848005.761746 rgb/1341848005.761746.png 1341848005.761763 depth/1341848005.761763.png +1341848005.797852 rgb/1341848005.797852.png 1341848005.797870 depth/1341848005.797870.png +1341848005.829917 rgb/1341848005.829917.png 1341848005.829931 depth/1341848005.829931.png +1341848005.861699 rgb/1341848005.861699.png 1341848005.861711 depth/1341848005.861711.png +1341848005.897793 rgb/1341848005.897793.png 1341848005.897803 depth/1341848005.897803.png +1341848005.929656 rgb/1341848005.929656.png 1341848005.929669 depth/1341848005.929669.png +1341848005.965681 rgb/1341848005.965681.png 1341848005.965690 depth/1341848005.965690.png +1341848005.997804 rgb/1341848005.997804.png 1341848005.997817 depth/1341848005.997817.png +1341848006.029768 rgb/1341848006.029768.png 1341848006.029788 depth/1341848006.029788.png +1341848006.065849 rgb/1341848006.065849.png 1341848006.065861 depth/1341848006.065861.png +1341848006.097854 rgb/1341848006.097854.png 1341848006.097878 depth/1341848006.097878.png +1341848006.133683 rgb/1341848006.133683.png 1341848006.133702 depth/1341848006.133702.png +1341848006.165815 rgb/1341848006.165815.png 1341848006.165828 depth/1341848006.165828.png +1341848006.197589 rgb/1341848006.197589.png 1341848006.197630 depth/1341848006.197630.png +1341848006.233778 rgb/1341848006.233778.png 1341848006.233815 depth/1341848006.233815.png +1341848006.265787 rgb/1341848006.265787.png 1341848006.265800 depth/1341848006.265800.png +1341848006.301762 rgb/1341848006.301762.png 1341848006.301785 depth/1341848006.301785.png +1341848006.333717 rgb/1341848006.333717.png 1341848006.333730 depth/1341848006.333730.png +1341848006.366035 rgb/1341848006.366035.png 1341848006.366634 depth/1341848006.366634.png +1341848006.401760 rgb/1341848006.401760.png 1341848006.401777 depth/1341848006.401777.png +1341848006.433710 rgb/1341848006.433710.png 1341848006.433743 depth/1341848006.433743.png +1341848006.469715 rgb/1341848006.469715.png 1341848006.469729 depth/1341848006.469729.png +1341848006.501659 rgb/1341848006.501659.png 1341848006.501683 depth/1341848006.501683.png +1341848006.533741 rgb/1341848006.533741.png 1341848006.533763 depth/1341848006.533763.png +1341848006.569740 rgb/1341848006.569740.png 1341848006.569755 depth/1341848006.569755.png +1341848006.601774 rgb/1341848006.601774.png 1341848006.602403 depth/1341848006.602403.png +1341848006.637780 rgb/1341848006.637780.png 1341848006.637885 depth/1341848006.637885.png +1341848006.670119 rgb/1341848006.670119.png 1341848006.670137 depth/1341848006.670137.png +1341848006.701798 rgb/1341848006.701798.png 1341848006.701816 depth/1341848006.701816.png +1341848006.737817 rgb/1341848006.737817.png 1341848006.737832 depth/1341848006.737832.png +1341848006.769742 rgb/1341848006.769742.png 1341848006.769771 depth/1341848006.769771.png +1341848006.801940 rgb/1341848006.801940.png 1341848006.801992 depth/1341848006.801992.png +1341848006.837619 rgb/1341848006.837619.png 1341848006.837904 depth/1341848006.837904.png +1341848006.870724 rgb/1341848006.870724.png 1341848006.870742 depth/1341848006.870742.png +1341848006.901756 rgb/1341848006.901756.png 1341848006.901778 depth/1341848006.901778.png +1341848006.937738 rgb/1341848006.937738.png 1341848006.937752 depth/1341848006.937752.png +1341848006.969708 rgb/1341848006.969708.png 1341848006.969722 depth/1341848006.969722.png +1341848007.005802 rgb/1341848007.005802.png 1341848007.005815 depth/1341848007.005815.png +1341848007.037835 rgb/1341848007.037835.png 1341848007.037850 depth/1341848007.037850.png +1341848007.069678 rgb/1341848007.069678.png 1341848007.069726 depth/1341848007.069726.png +1341848007.105687 rgb/1341848007.105687.png 1341848007.105713 depth/1341848007.105713.png +1341848007.137866 rgb/1341848007.137866.png 1341848007.138464 depth/1341848007.138464.png +1341848007.169651 rgb/1341848007.169651.png 1341848007.169667 depth/1341848007.169667.png +1341848007.205747 rgb/1341848007.205747.png 1341848007.205760 depth/1341848007.205760.png +1341848007.237921 rgb/1341848007.237921.png 1341848007.237958 depth/1341848007.237958.png +1341848007.298875 rgb/1341848007.298875.png 1341848007.298924 depth/1341848007.298924.png +1341848007.331423 rgb/1341848007.331423.png 1341848007.331488 depth/1341848007.331488.png +1341848007.366699 rgb/1341848007.366699.png 1341848007.366720 depth/1341848007.366720.png +1341848007.398700 rgb/1341848007.398700.png 1341848007.398712 depth/1341848007.398712.png +1341848007.434791 rgb/1341848007.434791.png 1341848007.434822 depth/1341848007.434822.png +1341848007.466689 rgb/1341848007.466689.png 1341848007.466740 depth/1341848007.466740.png +1341848007.498756 rgb/1341848007.498756.png 1341848007.498777 depth/1341848007.498777.png +1341848007.534834 rgb/1341848007.534834.png 1341848007.534850 depth/1341848007.534850.png +1341848007.566719 rgb/1341848007.566719.png 1341848007.566737 depth/1341848007.566737.png +1341848007.598725 rgb/1341848007.598725.png 1341848007.598741 depth/1341848007.598741.png +1341848007.634799 rgb/1341848007.634799.png 1341848007.634838 depth/1341848007.634838.png +1341848007.666675 rgb/1341848007.666675.png 1341848007.666683 depth/1341848007.666683.png +1341848007.702797 rgb/1341848007.702797.png 1341848007.702831 depth/1341848007.702831.png +1341848007.734605 rgb/1341848007.734605.png 1341848007.734671 depth/1341848007.734671.png +1341848007.766913 rgb/1341848007.766913.png 1341848007.766939 depth/1341848007.766939.png +1341848007.802889 rgb/1341848007.802889.png 1341848007.802912 depth/1341848007.802912.png +1341848007.834962 rgb/1341848007.834962.png 1341848007.834998 depth/1341848007.834998.png +1341848007.866745 rgb/1341848007.866745.png 1341848007.866768 depth/1341848007.866768.png +1341848007.902779 rgb/1341848007.902779.png 1341848007.902804 depth/1341848007.902804.png +1341848007.934851 rgb/1341848007.934851.png 1341848007.934873 depth/1341848007.934873.png +1341848007.970690 rgb/1341848007.970690.png 1341848007.970706 depth/1341848007.970706.png +1341848008.002709 rgb/1341848008.002709.png 1341848008.002724 depth/1341848008.002724.png +1341848008.034820 rgb/1341848008.034820.png 1341848008.034876 depth/1341848008.034876.png +1341848008.070825 rgb/1341848008.070825.png 1341848008.070834 depth/1341848008.070834.png +1341848008.103209 rgb/1341848008.103209.png 1341848008.103236 depth/1341848008.103236.png +1341848008.138809 rgb/1341848008.138809.png 1341848008.138821 depth/1341848008.138821.png +1341848008.171058 rgb/1341848008.171058.png 1341848008.171117 depth/1341848008.171117.png +1341848008.202734 rgb/1341848008.202734.png 1341848008.202763 depth/1341848008.202763.png +1341848008.238657 rgb/1341848008.238657.png 1341848008.238773 depth/1341848008.238773.png +1341848008.270710 rgb/1341848008.270710.png 1341848008.270729 depth/1341848008.270729.png +1341848008.302748 rgb/1341848008.302748.png 1341848008.302791 depth/1341848008.302791.png +1341848008.338769 rgb/1341848008.338769.png 1341848008.338801 depth/1341848008.338801.png +1341848008.370731 rgb/1341848008.370731.png 1341848008.370758 depth/1341848008.370758.png +1341848008.438870 rgb/1341848008.438870.png 1341848008.438900 depth/1341848008.438900.png +1341848008.470807 rgb/1341848008.470807.png 1341848008.471606 depth/1341848008.471606.png +1341848008.506855 rgb/1341848008.506855.png 1341848008.506888 depth/1341848008.506888.png +1341848008.538786 rgb/1341848008.538786.png 1341848008.538800 depth/1341848008.538800.png +1341848008.570727 rgb/1341848008.570727.png 1341848008.571285 depth/1341848008.571285.png +1341848008.606698 rgb/1341848008.606698.png 1341848008.606724 depth/1341848008.606724.png +1341848008.638714 rgb/1341848008.638714.png 1341848008.638729 depth/1341848008.638729.png +1341848008.674639 rgb/1341848008.674639.png 1341848008.674663 depth/1341848008.674663.png +1341848008.706785 rgb/1341848008.706785.png 1341848008.706846 depth/1341848008.706846.png +1341848008.738678 rgb/1341848008.738678.png 1341848008.738715 depth/1341848008.738715.png +1341848008.775071 rgb/1341848008.775071.png 1341848008.775111 depth/1341848008.775111.png +1341848008.806865 rgb/1341848008.806865.png 1341848008.806917 depth/1341848008.806917.png +1341848008.838798 rgb/1341848008.838798.png 1341848008.838814 depth/1341848008.838814.png +1341848008.874631 rgb/1341848008.874631.png 1341848008.875086 depth/1341848008.875086.png +1341848008.906680 rgb/1341848008.906680.png 1341848008.906700 depth/1341848008.906700.png +1341848008.943051 rgb/1341848008.943051.png 1341848008.943141 depth/1341848008.943141.png +1341848008.974723 rgb/1341848008.974723.png 1341848008.974742 depth/1341848008.974742.png +1341848009.006825 rgb/1341848009.006825.png 1341848009.006865 depth/1341848009.006865.png +1341848009.042740 rgb/1341848009.042740.png 1341848009.042907 depth/1341848009.042907.png +1341848009.110807 rgb/1341848009.110807.png 1341848009.110847 depth/1341848009.110847.png +1341848009.142732 rgb/1341848009.142732.png 1341848009.142810 depth/1341848009.142810.png +1341848009.174693 rgb/1341848009.174693.png 1341848009.174705 depth/1341848009.174705.png +1341848009.210697 rgb/1341848009.210697.png 1341848009.210730 depth/1341848009.210730.png +1341848009.242869 rgb/1341848009.242869.png 1341848009.243384 depth/1341848009.243384.png +1341848009.274683 rgb/1341848009.274683.png 1341848009.274703 depth/1341848009.274703.png +1341848009.310898 rgb/1341848009.310898.png 1341848009.310929 depth/1341848009.310929.png +1341848009.342882 rgb/1341848009.342882.png 1341848009.342912 depth/1341848009.342912.png +1341848009.378700 rgb/1341848009.378700.png 1341848009.378717 depth/1341848009.378717.png +1341848009.442927 rgb/1341848009.442927.png 1341848009.443003 depth/1341848009.443003.png +1341848009.479022 rgb/1341848009.479022.png 1341848009.479061 depth/1341848009.479061.png +1341848009.510631 rgb/1341848009.510631.png 1341848009.510651 depth/1341848009.510651.png +1341848009.542815 rgb/1341848009.542815.png 1341848009.542831 depth/1341848009.542831.png +1341848009.578814 rgb/1341848009.578814.png 1341848009.578828 depth/1341848009.578828.png +1341848009.610955 rgb/1341848009.610955.png 1341848009.610985 depth/1341848009.610985.png +1341848009.646873 rgb/1341848009.646873.png 1341848009.646890 depth/1341848009.646890.png +1341848009.678666 rgb/1341848009.678666.png 1341848009.678709 depth/1341848009.678709.png +1341848009.710835 rgb/1341848009.710835.png 1341848009.710857 depth/1341848009.710857.png +1341848009.746819 rgb/1341848009.746819.png 1341848009.746840 depth/1341848009.746840.png +1341848009.778767 rgb/1341848009.778767.png 1341848009.778966 depth/1341848009.778966.png +1341848009.810661 rgb/1341848009.810661.png 1341848009.810678 depth/1341848009.810678.png +1341848009.846800 rgb/1341848009.846800.png 1341848009.846812 depth/1341848009.846812.png +1341848009.878688 rgb/1341848009.878688.png 1341848009.878704 depth/1341848009.878704.png +1341848009.914782 rgb/1341848009.914782.png 1341848009.914830 depth/1341848009.914830.png +1341848009.946990 rgb/1341848009.946990.png 1341848009.947019 depth/1341848009.947019.png +1341848009.978905 rgb/1341848009.978905.png 1341848009.979030 depth/1341848009.979030.png +1341848010.014819 rgb/1341848010.014819.png 1341848010.014838 depth/1341848010.014838.png +1341848010.046835 rgb/1341848010.046835.png 1341848010.047807 depth/1341848010.047807.png +1341848010.082650 rgb/1341848010.082650.png 1341848010.082721 depth/1341848010.082721.png +1341848010.114748 rgb/1341848010.114748.png 1341848010.114802 depth/1341848010.114802.png +1341848010.146752 rgb/1341848010.146752.png 1341848010.146785 depth/1341848010.146785.png +1341848010.182709 rgb/1341848010.182709.png 1341848010.182775 depth/1341848010.182775.png +1341848010.214739 rgb/1341848010.214739.png 1341848010.214759 depth/1341848010.214759.png +1341848010.246831 rgb/1341848010.246831.png 1341848010.246841 depth/1341848010.246841.png +1341848010.282749 rgb/1341848010.282749.png 1341848010.282781 depth/1341848010.282781.png +1341848010.314754 rgb/1341848010.314754.png 1341848010.314763 depth/1341848010.314763.png +1341848010.351054 rgb/1341848010.351054.png 1341848010.351621 depth/1341848010.351621.png +1341848010.382819 rgb/1341848010.382819.png 1341848010.382839 depth/1341848010.382839.png +1341848010.414692 rgb/1341848010.414692.png 1341848010.414716 depth/1341848010.414716.png +1341848010.450872 rgb/1341848010.450872.png 1341848010.450889 depth/1341848010.450889.png +1341848010.483088 rgb/1341848010.483088.png 1341848010.483600 depth/1341848010.483600.png +1341848010.514760 rgb/1341848010.514760.png 1341848010.514800 depth/1341848010.514800.png +1341848010.550631 rgb/1341848010.550631.png 1341848010.550812 depth/1341848010.550812.png +1341848010.582861 rgb/1341848010.582861.png 1341848010.582885 depth/1341848010.582885.png +1341848010.618690 rgb/1341848010.618690.png 1341848010.618730 depth/1341848010.618730.png +1341848010.650956 rgb/1341848010.650956.png 1341848010.650976 depth/1341848010.650976.png +1341848010.682633 rgb/1341848010.682633.png 1341848010.682652 depth/1341848010.682652.png +1341848010.718753 rgb/1341848010.718753.png 1341848010.719184 depth/1341848010.719184.png +1341848010.750922 rgb/1341848010.750922.png 1341848010.751486 depth/1341848010.751486.png +1341848010.782711 rgb/1341848010.782711.png 1341848010.782730 depth/1341848010.782730.png +1341848010.818844 rgb/1341848010.818844.png 1341848010.818854 depth/1341848010.818854.png +1341848010.850765 rgb/1341848010.850765.png 1341848010.851350 depth/1341848010.851350.png +1341848010.886687 rgb/1341848010.886687.png 1341848010.886724 depth/1341848010.886724.png +1341848010.918833 rgb/1341848010.918833.png 1341848010.918846 depth/1341848010.918846.png +1341848010.950793 rgb/1341848010.950793.png 1341848010.951377 depth/1341848010.951377.png +1341848010.986761 rgb/1341848010.986761.png 1341848010.986772 depth/1341848010.986772.png +1341848011.018704 rgb/1341848011.018704.png 1341848011.019273 depth/1341848011.019273.png +1341848011.051016 rgb/1341848011.051016.png 1341848011.051039 depth/1341848011.051039.png +1341848011.086749 rgb/1341848011.086749.png 1341848011.086773 depth/1341848011.086773.png +1341848011.118701 rgb/1341848011.118701.png 1341848011.118723 depth/1341848011.118723.png +1341848011.154630 rgb/1341848011.154630.png 1341848011.154649 depth/1341848011.154649.png +1341848011.186671 rgb/1341848011.186671.png 1341848011.186703 depth/1341848011.186703.png +1341848011.219095 rgb/1341848011.219095.png 1341848011.219111 depth/1341848011.219111.png +1341848011.254693 rgb/1341848011.254693.png 1341848011.254713 depth/1341848011.254713.png +1341848011.286627 rgb/1341848011.286627.png 1341848011.286673 depth/1341848011.286673.png +1341848011.322712 rgb/1341848011.322712.png 1341848011.322826 depth/1341848011.322826.png +1341848011.354750 rgb/1341848011.354750.png 1341848011.354764 depth/1341848011.354764.png +1341848011.386749 rgb/1341848011.386749.png 1341848011.386775 depth/1341848011.386775.png +1341848011.422722 rgb/1341848011.422722.png 1341848011.422732 depth/1341848011.422732.png +1341848011.454654 rgb/1341848011.454654.png 1341848011.454701 depth/1341848011.454701.png +1341848011.486754 rgb/1341848011.486754.png 1341848011.486777 depth/1341848011.486777.png +1341848011.522854 rgb/1341848011.522854.png 1341848011.522895 depth/1341848011.522895.png +1341848011.554674 rgb/1341848011.554674.png 1341848011.554735 depth/1341848011.554735.png +1341848011.590867 rgb/1341848011.590867.png 1341848011.590936 depth/1341848011.590936.png +1341848011.622723 rgb/1341848011.622723.png 1341848011.622767 depth/1341848011.622767.png +1341848011.654892 rgb/1341848011.654892.png 1341848011.655386 depth/1341848011.655386.png +1341848011.690778 rgb/1341848011.690778.png 1341848011.690790 depth/1341848011.690790.png +1341848011.722610 rgb/1341848011.722610.png 1341848011.722645 depth/1341848011.722645.png +1341848011.754796 rgb/1341848011.754796.png 1341848011.754833 depth/1341848011.754833.png +1341848011.790831 rgb/1341848011.790831.png 1341848011.790843 depth/1341848011.790843.png +1341848011.822705 rgb/1341848011.822705.png 1341848011.822722 depth/1341848011.822722.png +1341848011.858763 rgb/1341848011.858763.png 1341848011.859228 depth/1341848011.859228.png +1341848011.890689 rgb/1341848011.890689.png 1341848011.890702 depth/1341848011.890702.png +1341848011.922914 rgb/1341848011.922914.png 1341848011.923583 depth/1341848011.923583.png +1341848011.958828 rgb/1341848011.958828.png 1341848011.958858 depth/1341848011.958858.png +1341848011.990755 rgb/1341848011.990755.png 1341848011.991385 depth/1341848011.991385.png +1341848012.022737 rgb/1341848012.022737.png 1341848012.022777 depth/1341848012.022777.png +1341848012.058861 rgb/1341848012.058861.png 1341848012.058886 depth/1341848012.058886.png +1341848012.090822 rgb/1341848012.090822.png 1341848012.091474 depth/1341848012.091474.png +1341848012.126859 rgb/1341848012.126859.png 1341848012.126875 depth/1341848012.126875.png +1341848012.190967 rgb/1341848012.190967.png 1341848012.191005 depth/1341848012.191005.png +1341848012.226750 rgb/1341848012.226750.png 1341848012.226789 depth/1341848012.226789.png +1341848012.258713 rgb/1341848012.258713.png 1341848012.258767 depth/1341848012.258767.png +1341848012.295247 rgb/1341848012.295247.png 1341848012.295262 depth/1341848012.295262.png +1341848012.326868 rgb/1341848012.326868.png 1341848012.326913 depth/1341848012.326913.png +1341848012.358782 rgb/1341848012.358782.png 1341848012.359263 depth/1341848012.359263.png +1341848012.394721 rgb/1341848012.394721.png 1341848012.394744 depth/1341848012.394744.png +1341848012.426830 rgb/1341848012.426830.png 1341848012.426870 depth/1341848012.426870.png +1341848012.458805 rgb/1341848012.458805.png 1341848012.458819 depth/1341848012.458819.png +1341848012.494697 rgb/1341848012.494697.png 1341848012.494718 depth/1341848012.494718.png +1341848012.526756 rgb/1341848012.526756.png 1341848012.526771 depth/1341848012.526771.png +1341848012.562690 rgb/1341848012.562690.png 1341848012.562751 depth/1341848012.562751.png +1341848012.594669 rgb/1341848012.594669.png 1341848012.595251 depth/1341848012.595251.png +1341848012.626774 rgb/1341848012.626774.png 1341848012.626789 depth/1341848012.626789.png +1341848012.662763 rgb/1341848012.662763.png 1341848012.662786 depth/1341848012.662786.png +1341848012.695339 rgb/1341848012.695339.png 1341848012.695354 depth/1341848012.695354.png +1341848012.726854 rgb/1341848012.726854.png 1341848012.726885 depth/1341848012.726885.png +1341848012.762672 rgb/1341848012.762672.png 1341848012.762686 depth/1341848012.762686.png +1341848012.794727 rgb/1341848012.794727.png 1341848012.794773 depth/1341848012.794773.png +1341848012.830669 rgb/1341848012.830669.png 1341848012.830698 depth/1341848012.830698.png +1341848012.862795 rgb/1341848012.862795.png 1341848012.862809 depth/1341848012.862809.png +1341848012.894740 rgb/1341848012.894740.png 1341848012.894767 depth/1341848012.894767.png +1341848012.930848 rgb/1341848012.930848.png 1341848012.930882 depth/1341848012.930882.png +1341848012.962752 rgb/1341848012.962752.png 1341848012.962985 depth/1341848012.962985.png +1341848012.994842 rgb/1341848012.994842.png 1341848012.994868 depth/1341848012.994868.png +1341848013.030944 rgb/1341848013.030944.png 1341848013.030973 depth/1341848013.030973.png +1341848013.062714 rgb/1341848013.062714.png 1341848013.063076 depth/1341848013.063076.png +1341848013.098784 rgb/1341848013.098784.png 1341848013.098799 depth/1341848013.098799.png +1341848013.130817 rgb/1341848013.130817.png 1341848013.130848 depth/1341848013.130848.png +1341848013.162759 rgb/1341848013.162759.png 1341848013.162778 depth/1341848013.162778.png +1341848013.198719 rgb/1341848013.198719.png 1341848013.198734 depth/1341848013.198734.png +1341848013.230855 rgb/1341848013.230855.png 1341848013.230869 depth/1341848013.230869.png +1341848013.262723 rgb/1341848013.262723.png 1341848013.262743 depth/1341848013.262743.png +1341848013.298709 rgb/1341848013.298709.png 1341848013.298774 depth/1341848013.298774.png +1341848013.330754 rgb/1341848013.330754.png 1341848013.330792 depth/1341848013.330792.png +1341848013.366705 rgb/1341848013.366705.png 1341848013.366741 depth/1341848013.366741.png +1341848013.398748 rgb/1341848013.398748.png 1341848013.398774 depth/1341848013.398774.png +1341848013.430850 rgb/1341848013.430850.png 1341848013.430871 depth/1341848013.430871.png +1341848013.466959 rgb/1341848013.466959.png 1341848013.466977 depth/1341848013.466977.png +1341848013.498782 rgb/1341848013.498782.png 1341848013.498821 depth/1341848013.498821.png +1341848013.534779 rgb/1341848013.534779.png 1341848013.534803 depth/1341848013.534803.png +1341848013.566664 rgb/1341848013.566664.png 1341848013.566708 depth/1341848013.566708.png +1341848013.598764 rgb/1341848013.598764.png 1341848013.598783 depth/1341848013.598783.png +1341848013.634812 rgb/1341848013.634812.png 1341848013.634835 depth/1341848013.634835.png +1341848013.666669 rgb/1341848013.666669.png 1341848013.666681 depth/1341848013.666681.png +1341848013.698821 rgb/1341848013.698821.png 1341848013.698836 depth/1341848013.698836.png +1341848013.734623 rgb/1341848013.734623.png 1341848013.734633 depth/1341848013.734633.png +1341848013.766827 rgb/1341848013.766827.png 1341848013.766854 depth/1341848013.766854.png +1341848013.802717 rgb/1341848013.802717.png 1341848013.802736 depth/1341848013.802736.png +1341848013.834802 rgb/1341848013.834802.png 1341848013.834816 depth/1341848013.834816.png +1341848013.866791 rgb/1341848013.866791.png 1341848013.866814 depth/1341848013.866814.png +1341848013.902735 rgb/1341848013.902735.png 1341848013.902763 depth/1341848013.902763.png +1341848013.966740 rgb/1341848013.966740.png 1341848013.966791 depth/1341848013.966791.png +1341848014.002717 rgb/1341848014.002717.png 1341848014.002734 depth/1341848014.002734.png +1341848014.034942 rgb/1341848014.034942.png 1341848014.034991 depth/1341848014.034991.png +1341848014.070990 rgb/1341848014.070990.png 1341848014.071022 depth/1341848014.071022.png +1341848014.102686 rgb/1341848014.102686.png 1341848014.102699 depth/1341848014.102699.png +1341848014.134725 rgb/1341848014.134725.png 1341848014.134744 depth/1341848014.134744.png +1341848014.170724 rgb/1341848014.170724.png 1341848014.170789 depth/1341848014.170789.png +1341848014.202658 rgb/1341848014.202658.png 1341848014.202677 depth/1341848014.202677.png +1341848014.234751 rgb/1341848014.234751.png 1341848014.234775 depth/1341848014.234775.png +1341848014.270714 rgb/1341848014.270714.png 1341848014.270773 depth/1341848014.270773.png +1341848014.302738 rgb/1341848014.302738.png 1341848014.302751 depth/1341848014.302751.png +1341848014.338694 rgb/1341848014.338694.png 1341848014.338717 depth/1341848014.338717.png +1341848014.370553 rgb/1341848014.370553.png 1341848014.370821 depth/1341848014.370821.png +1341848014.438848 rgb/1341848014.438848.png 1341848014.438869 depth/1341848014.438869.png +1341848014.470783 rgb/1341848014.470783.png 1341848014.470797 depth/1341848014.470797.png +1341848014.506633 rgb/1341848014.506633.png 1341848014.506658 depth/1341848014.506658.png +1341848014.538728 rgb/1341848014.538728.png 1341848014.538744 depth/1341848014.538744.png +1341848014.570790 rgb/1341848014.570790.png 1341848014.570803 depth/1341848014.570803.png +1341848014.606858 rgb/1341848014.606858.png 1341848014.606882 depth/1341848014.606882.png +1341848014.638688 rgb/1341848014.638688.png 1341848014.638705 depth/1341848014.638705.png +1341848014.670828 rgb/1341848014.670828.png 1341848014.671380 depth/1341848014.671380.png +1341848014.706765 rgb/1341848014.706765.png 1341848014.706993 depth/1341848014.706993.png +1341848014.738691 rgb/1341848014.738691.png 1341848014.738705 depth/1341848014.738705.png +1341848014.774750 rgb/1341848014.774750.png 1341848014.774767 depth/1341848014.774767.png +1341848014.806669 rgb/1341848014.806669.png 1341848014.806684 depth/1341848014.806684.png +1341848014.838740 rgb/1341848014.838740.png 1341848014.838775 depth/1341848014.838775.png +1341848014.874686 rgb/1341848014.874686.png 1341848014.874729 depth/1341848014.874729.png +1341848014.906647 rgb/1341848014.906647.png 1341848014.906657 depth/1341848014.906657.png +1341848014.938697 rgb/1341848014.938697.png 1341848014.938709 depth/1341848014.938709.png +1341848014.974705 rgb/1341848014.974705.png 1341848014.974719 depth/1341848014.974719.png +1341848015.006657 rgb/1341848015.006657.png 1341848015.006672 depth/1341848015.006672.png +1341848015.042593 rgb/1341848015.042593.png 1341848015.042656 depth/1341848015.042656.png +1341848015.074864 rgb/1341848015.074864.png 1341848015.074894 depth/1341848015.074894.png +1341848015.106838 rgb/1341848015.106838.png 1341848015.106864 depth/1341848015.106864.png +1341848015.142691 rgb/1341848015.142691.png 1341848015.142708 depth/1341848015.142708.png +1341848015.174708 rgb/1341848015.174708.png 1341848015.174741 depth/1341848015.174741.png +1341848015.207238 rgb/1341848015.207238.png 1341848015.207717 depth/1341848015.207717.png +1341848015.243495 rgb/1341848015.243495.png 1341848015.243592 depth/1341848015.243592.png +1341848015.274780 rgb/1341848015.274780.png 1341848015.274791 depth/1341848015.274791.png +1341848015.310598 rgb/1341848015.310598.png 1341848015.310805 depth/1341848015.310805.png +1341848015.342895 rgb/1341848015.342895.png 1341848015.342916 depth/1341848015.342916.png +1341848015.374733 rgb/1341848015.374733.png 1341848015.374754 depth/1341848015.374754.png +1341848015.410655 rgb/1341848015.410655.png 1341848015.410669 depth/1341848015.410669.png +1341848015.442783 rgb/1341848015.442783.png 1341848015.442801 depth/1341848015.442801.png +1341848015.474959 rgb/1341848015.474959.png 1341848015.474976 depth/1341848015.474976.png +1341848015.510927 rgb/1341848015.510927.png 1341848015.510957 depth/1341848015.510957.png +1341848015.542834 rgb/1341848015.542834.png 1341848015.543288 depth/1341848015.543288.png +1341848015.581753 rgb/1341848015.581753.png 1341848015.581781 depth/1341848015.581781.png +1341848015.617769 rgb/1341848015.617769.png 1341848015.618482 depth/1341848015.618482.png +1341848015.650094 rgb/1341848015.650094.png 1341848015.650136 depth/1341848015.650136.png +1341848015.685811 rgb/1341848015.685811.png 1341848015.685825 depth/1341848015.685825.png +1341848015.718057 rgb/1341848015.718057.png 1341848015.719587 depth/1341848015.719587.png +1341848015.749815 rgb/1341848015.749815.png 1341848015.749843 depth/1341848015.749843.png +1341848015.785761 rgb/1341848015.785761.png 1341848015.785775 depth/1341848015.785775.png +1341848015.817883 rgb/1341848015.817883.png 1341848015.817912 depth/1341848015.817912.png +1341848015.853811 rgb/1341848015.853811.png 1341848015.854043 depth/1341848015.854043.png +1341848015.885654 rgb/1341848015.885654.png 1341848015.885668 depth/1341848015.885668.png +1341848015.917793 rgb/1341848015.917793.png 1341848015.917819 depth/1341848015.917819.png +1341848015.954005 rgb/1341848015.954005.png 1341848015.954061 depth/1341848015.954061.png +1341848015.986663 rgb/1341848015.986663.png 1341848015.987003 depth/1341848015.987003.png +1341848016.021677 rgb/1341848016.021677.png 1341848016.021701 depth/1341848016.021701.png +1341848016.053936 rgb/1341848016.053936.png 1341848016.053969 depth/1341848016.053969.png +1341848016.085724 rgb/1341848016.085724.png 1341848016.085742 depth/1341848016.085742.png +1341848016.121844 rgb/1341848016.121844.png 1341848016.121873 depth/1341848016.121873.png +1341848016.153821 rgb/1341848016.153821.png 1341848016.153858 depth/1341848016.153858.png +1341848016.185769 rgb/1341848016.185769.png 1341848016.185803 depth/1341848016.185803.png +1341848016.221734 rgb/1341848016.221734.png 1341848016.221788 depth/1341848016.221788.png +1341848016.253686 rgb/1341848016.253686.png 1341848016.253706 depth/1341848016.253706.png +1341848016.289960 rgb/1341848016.289960.png 1341848016.289975 depth/1341848016.289975.png +1341848016.322013 rgb/1341848016.322013.png 1341848016.322971 depth/1341848016.322971.png +1341848016.353746 rgb/1341848016.353746.png 1341848016.354394 depth/1341848016.354394.png +1341848016.389789 rgb/1341848016.389789.png 1341848016.389816 depth/1341848016.389816.png +1341848016.421705 rgb/1341848016.421705.png 1341848016.422556 depth/1341848016.422556.png +1341848016.453901 rgb/1341848016.453901.png 1341848016.454511 depth/1341848016.454511.png +1341848016.490058 rgb/1341848016.490058.png 1341848016.490717 depth/1341848016.490717.png +1341848016.521813 rgb/1341848016.521813.png 1341848016.521830 depth/1341848016.521830.png +1341848016.554210 rgb/1341848016.554210.png 1341848016.554621 depth/1341848016.554621.png +1341848016.589825 rgb/1341848016.589825.png 1341848016.589841 depth/1341848016.589841.png +1341848016.621860 rgb/1341848016.621860.png 1341848016.622571 depth/1341848016.622571.png +1341848016.657837 rgb/1341848016.657837.png 1341848016.657879 depth/1341848016.657879.png +1341848016.689891 rgb/1341848016.689891.png 1341848016.689920 depth/1341848016.689920.png +1341848016.757848 rgb/1341848016.757848.png 1341848016.757902 depth/1341848016.757902.png +1341848016.818817 rgb/1341848016.818817.png 1341848016.818829 depth/1341848016.818829.png +1341848016.850754 rgb/1341848016.850754.png 1341848016.850779 depth/1341848016.850779.png +1341848016.882757 rgb/1341848016.882757.png 1341848016.882773 depth/1341848016.882773.png +1341848016.918907 rgb/1341848016.918907.png 1341848016.918954 depth/1341848016.918954.png +1341848016.950706 rgb/1341848016.950706.png 1341848016.950732 depth/1341848016.950732.png +1341848016.986658 rgb/1341848016.986658.png 1341848016.986668 depth/1341848016.986668.png +1341848017.018678 rgb/1341848017.018678.png 1341848017.018699 depth/1341848017.018699.png +1341848017.050760 rgb/1341848017.050760.png 1341848017.050790 depth/1341848017.050790.png +1341848017.086845 rgb/1341848017.086845.png 1341848017.087686 depth/1341848017.087686.png +1341848017.118641 rgb/1341848017.118641.png 1341848017.118659 depth/1341848017.118659.png +1341848017.150678 rgb/1341848017.150678.png 1341848017.150706 depth/1341848017.150706.png +1341848017.186855 rgb/1341848017.186855.png 1341848017.186867 depth/1341848017.186867.png +1341848017.218765 rgb/1341848017.218765.png 1341848017.218781 depth/1341848017.218781.png +1341848017.254693 rgb/1341848017.254693.png 1341848017.254710 depth/1341848017.254710.png +1341848017.286638 rgb/1341848017.286638.png 1341848017.286649 depth/1341848017.286649.png +1341848017.318695 rgb/1341848017.318695.png 1341848017.318710 depth/1341848017.318710.png +1341848017.354737 rgb/1341848017.354737.png 1341848017.354762 depth/1341848017.354762.png +1341848017.386825 rgb/1341848017.386825.png 1341848017.387567 depth/1341848017.387567.png +1341848017.418824 rgb/1341848017.418824.png 1341848017.418853 depth/1341848017.418853.png +1341848017.454792 rgb/1341848017.454792.png 1341848017.454807 depth/1341848017.454807.png +1341848017.486699 rgb/1341848017.486699.png 1341848017.486724 depth/1341848017.486724.png +1341848017.522694 rgb/1341848017.522694.png 1341848017.522742 depth/1341848017.522742.png +1341848017.554797 rgb/1341848017.554797.png 1341848017.554807 depth/1341848017.554807.png +1341848017.587838 rgb/1341848017.587838.png 1341848017.587857 depth/1341848017.587857.png +1341848017.622714 rgb/1341848017.622714.png 1341848017.622730 depth/1341848017.622730.png +1341848017.654814 rgb/1341848017.654814.png 1341848017.654844 depth/1341848017.654844.png +1341848017.686820 rgb/1341848017.686820.png 1341848017.686847 depth/1341848017.686847.png +1341848017.722837 rgb/1341848017.722837.png 1341848017.722849 depth/1341848017.722849.png +1341848017.754780 rgb/1341848017.754780.png 1341848017.754796 depth/1341848017.754796.png +1341848017.790699 rgb/1341848017.790699.png 1341848017.790714 depth/1341848017.790714.png +1341848017.822756 rgb/1341848017.822756.png 1341848017.823281 depth/1341848017.823281.png +1341848017.854726 rgb/1341848017.854726.png 1341848017.854745 depth/1341848017.854745.png +1341848017.890737 rgb/1341848017.890737.png 1341848017.890747 depth/1341848017.890747.png +1341848017.922823 rgb/1341848017.922823.png 1341848017.922849 depth/1341848017.922849.png +1341848017.958643 rgb/1341848017.958643.png 1341848017.958669 depth/1341848017.958669.png +1341848017.990683 rgb/1341848017.990683.png 1341848017.990698 depth/1341848017.990698.png +1341848018.022671 rgb/1341848018.022671.png 1341848018.022686 depth/1341848018.022686.png +1341848018.058766 rgb/1341848018.058766.png 1341848018.058780 depth/1341848018.058780.png +1341848018.090894 rgb/1341848018.090894.png 1341848018.091600 depth/1341848018.091600.png +1341848018.122747 rgb/1341848018.122747.png 1341848018.122774 depth/1341848018.122774.png +1341848018.159145 rgb/1341848018.159145.png 1341848018.159160 depth/1341848018.159160.png +1341848018.190824 rgb/1341848018.190824.png 1341848018.190833 depth/1341848018.190833.png +1341848018.226660 rgb/1341848018.226660.png 1341848018.226676 depth/1341848018.226676.png +1341848018.258766 rgb/1341848018.258766.png 1341848018.258776 depth/1341848018.258776.png +1341848018.290747 rgb/1341848018.290747.png 1341848018.290763 depth/1341848018.290763.png +1341848018.333905 rgb/1341848018.333905.png 1341848018.333920 depth/1341848018.333920.png +1341848018.367205 rgb/1341848018.367205.png 1341848018.367246 depth/1341848018.367246.png +1341848018.397728 rgb/1341848018.397728.png 1341848018.398249 depth/1341848018.398249.png +1341848018.433770 rgb/1341848018.433770.png 1341848018.433789 depth/1341848018.433789.png +1341848018.465663 rgb/1341848018.465663.png 1341848018.465797 depth/1341848018.465797.png +1341848018.501822 rgb/1341848018.501822.png 1341848018.501833 depth/1341848018.501833.png +1341848018.534507 rgb/1341848018.534507.png 1341848018.534528 depth/1341848018.534528.png +1341848018.565849 rgb/1341848018.565849.png 1341848018.565868 depth/1341848018.565868.png +1341848018.601739 rgb/1341848018.601739.png 1341848018.601762 depth/1341848018.601762.png +1341848018.633687 rgb/1341848018.633687.png 1341848018.633745 depth/1341848018.633745.png +1341848018.669811 rgb/1341848018.669811.png 1341848018.669908 depth/1341848018.669908.png +1341848018.701756 rgb/1341848018.701756.png 1341848018.701811 depth/1341848018.701811.png +1341848018.733853 rgb/1341848018.733853.png 1341848018.733907 depth/1341848018.733907.png +1341848018.769715 rgb/1341848018.769715.png 1341848018.769731 depth/1341848018.769731.png +1341848018.802234 rgb/1341848018.802234.png 1341848018.802331 depth/1341848018.802331.png +1341848018.833759 rgb/1341848018.833759.png 1341848018.833794 depth/1341848018.833794.png +1341848018.869787 rgb/1341848018.869787.png 1341848018.869812 depth/1341848018.869812.png +1341848018.901964 rgb/1341848018.901964.png 1341848018.902019 depth/1341848018.902019.png +1341848018.933795 rgb/1341848018.933795.png 1341848018.933805 depth/1341848018.933805.png +1341848018.969688 rgb/1341848018.969688.png 1341848018.969703 depth/1341848018.969703.png +1341848019.002336 rgb/1341848019.002336.png 1341848019.002352 depth/1341848019.002352.png +1341848019.069833 rgb/1341848019.069833.png 1341848019.069892 depth/1341848019.069892.png +1341848019.130792 rgb/1341848019.130792.png 1341848019.130828 depth/1341848019.130828.png +1341848019.162652 rgb/1341848019.162652.png 1341848019.162677 depth/1341848019.162677.png +1341848019.198644 rgb/1341848019.198644.png 1341848019.198662 depth/1341848019.198662.png +1341848019.231114 rgb/1341848019.231114.png 1341848019.231515 depth/1341848019.231515.png +1341848019.262728 rgb/1341848019.262728.png 1341848019.262747 depth/1341848019.262747.png +1341848019.298715 rgb/1341848019.298715.png 1341848019.298728 depth/1341848019.298728.png +1341848019.330680 rgb/1341848019.330680.png 1341848019.330801 depth/1341848019.330801.png +1341848019.362697 rgb/1341848019.362697.png 1341848019.362719 depth/1341848019.362719.png +1341848019.398715 rgb/1341848019.398715.png 1341848019.398731 depth/1341848019.398731.png +1341848019.431028 rgb/1341848019.431028.png 1341848019.431071 depth/1341848019.431071.png +1341848019.467021 rgb/1341848019.467021.png 1341848019.467528 depth/1341848019.467528.png +1341848019.498756 rgb/1341848019.498756.png 1341848019.498786 depth/1341848019.498786.png +1341848019.530821 rgb/1341848019.530821.png 1341848019.530845 depth/1341848019.530845.png +1341848019.567087 rgb/1341848019.567087.png 1341848019.567145 depth/1341848019.567145.png +1341848019.598737 rgb/1341848019.598737.png 1341848019.598763 depth/1341848019.598763.png +1341848019.630654 rgb/1341848019.630654.png 1341848019.630664 depth/1341848019.630664.png +1341848019.666875 rgb/1341848019.666875.png 1341848019.666895 depth/1341848019.666895.png +1341848019.698668 rgb/1341848019.698668.png 1341848019.698714 depth/1341848019.698714.png +1341848019.734756 rgb/1341848019.734756.png 1341848019.734778 depth/1341848019.734778.png +1341848019.766703 rgb/1341848019.766703.png 1341848019.767180 depth/1341848019.767180.png +1341848019.798719 rgb/1341848019.798719.png 1341848019.798730 depth/1341848019.798730.png +1341848019.834660 rgb/1341848019.834660.png 1341848019.835148 depth/1341848019.835148.png +1341848019.898833 rgb/1341848019.898833.png 1341848019.898856 depth/1341848019.898856.png +1341848019.934782 rgb/1341848019.934782.png 1341848019.935323 depth/1341848019.935323.png +1341848019.966705 rgb/1341848019.966705.png 1341848019.966718 depth/1341848019.966718.png +1341848020.002811 rgb/1341848020.002811.png 1341848020.002827 depth/1341848020.002827.png +1341848020.034693 rgb/1341848020.034693.png 1341848020.034751 depth/1341848020.034751.png +1341848020.066696 rgb/1341848020.066696.png 1341848020.066711 depth/1341848020.066711.png +1341848020.102776 rgb/1341848020.102776.png 1341848020.102828 depth/1341848020.102828.png +1341848020.134758 rgb/1341848020.134758.png 1341848020.134797 depth/1341848020.134797.png +1341848020.170835 rgb/1341848020.170835.png 1341848020.170870 depth/1341848020.170870.png +1341848020.202706 rgb/1341848020.202706.png 1341848020.202731 depth/1341848020.202731.png +1341848020.234873 rgb/1341848020.234873.png 1341848020.234962 depth/1341848020.234962.png +1341848020.271152 rgb/1341848020.271152.png 1341848020.271164 depth/1341848020.271164.png +1341848020.302754 rgb/1341848020.302754.png 1341848020.302781 depth/1341848020.302781.png +1341848020.334861 rgb/1341848020.334861.png 1341848020.334915 depth/1341848020.334915.png +1341848020.370812 rgb/1341848020.370812.png 1341848020.370828 depth/1341848020.370828.png +1341848020.438816 rgb/1341848020.438816.png 1341848020.438829 depth/1341848020.438829.png +1341848020.471200 rgb/1341848020.471200.png 1341848020.471215 depth/1341848020.471215.png +1341848020.502691 rgb/1341848020.502691.png 1341848020.502708 depth/1341848020.502708.png +1341848020.538748 rgb/1341848020.538748.png 1341848020.538775 depth/1341848020.538775.png +1341848020.570790 rgb/1341848020.570790.png 1341848020.570808 depth/1341848020.570808.png +1341848020.602764 rgb/1341848020.602764.png 1341848020.602784 depth/1341848020.602784.png +1341848020.638929 rgb/1341848020.638929.png 1341848020.638951 depth/1341848020.638951.png +1341848020.670809 rgb/1341848020.670809.png 1341848020.670825 depth/1341848020.670825.png +1341848020.706669 rgb/1341848020.706669.png 1341848020.706711 depth/1341848020.706711.png +1341848020.738994 rgb/1341848020.738994.png 1341848020.739029 depth/1341848020.739029.png +1341848020.770817 rgb/1341848020.770817.png 1341848020.770832 depth/1341848020.770832.png +1341848020.807216 rgb/1341848020.807216.png 1341848020.807293 depth/1341848020.807293.png +1341848020.839066 rgb/1341848020.839066.png 1341848020.839106 depth/1341848020.839106.png +1341848020.870955 rgb/1341848020.870955.png 1341848020.870982 depth/1341848020.870982.png +1341848020.906582 rgb/1341848020.906582.png 1341848020.906626 depth/1341848020.906626.png +1341848020.938790 rgb/1341848020.938790.png 1341848020.938813 depth/1341848020.938813.png +1341848020.974874 rgb/1341848020.974874.png 1341848020.974888 depth/1341848020.974888.png +1341848021.006632 rgb/1341848021.006632.png 1341848021.006653 depth/1341848021.006653.png +1341848021.039636 rgb/1341848021.039636.png 1341848021.039683 depth/1341848021.039683.png +1341848021.074762 rgb/1341848021.074762.png 1341848021.074778 depth/1341848021.074778.png +1341848021.106691 rgb/1341848021.106691.png 1341848021.106711 depth/1341848021.106711.png +1341848021.142795 rgb/1341848021.142795.png 1341848021.142912 depth/1341848021.142912.png +1341848021.175038 rgb/1341848021.175038.png 1341848021.175064 depth/1341848021.175064.png +1341848021.206698 rgb/1341848021.206698.png 1341848021.206716 depth/1341848021.206716.png +1341848021.242671 rgb/1341848021.242671.png 1341848021.242711 depth/1341848021.242711.png +1341848021.274899 rgb/1341848021.274899.png 1341848021.274910 depth/1341848021.274910.png +1341848021.307283 rgb/1341848021.307283.png 1341848021.307304 depth/1341848021.307304.png +1341848021.343359 rgb/1341848021.343359.png 1341848021.347770 depth/1341848021.347770.png +1341848021.384830 rgb/1341848021.384830.png 1341848021.385282 depth/1341848021.385282.png +1341848021.414272 rgb/1341848021.414272.png 1341848021.414623 depth/1341848021.414623.png +1341848021.455728 rgb/1341848021.455728.png 1341848021.456491 depth/1341848021.456491.png +1341848021.487906 rgb/1341848021.487906.png 1341848021.488948 depth/1341848021.488948.png +1341848021.514696 rgb/1341848021.514696.png 1341848021.514729 depth/1341848021.514729.png +1341848021.550755 rgb/1341848021.550755.png 1341848021.551117 depth/1341848021.551117.png +1341848021.617752 rgb/1341848021.617752.png 1341848021.618003 depth/1341848021.618003.png +1341848021.678764 rgb/1341848021.678764.png 1341848021.678782 depth/1341848021.678782.png +1341848021.710743 rgb/1341848021.710743.png 1341848021.710760 depth/1341848021.710760.png +1341848021.742811 rgb/1341848021.742811.png 1341848021.742825 depth/1341848021.742825.png +1341848021.778676 rgb/1341848021.778676.png 1341848021.779227 depth/1341848021.779227.png +1341848021.810867 rgb/1341848021.810867.png 1341848021.810903 depth/1341848021.810903.png +1341848021.844563 rgb/1341848021.844563.png 1341848021.844607 depth/1341848021.844607.png +1341848021.878887 rgb/1341848021.878887.png 1341848021.878906 depth/1341848021.878906.png +1341848021.910628 rgb/1341848021.910628.png 1341848021.910642 depth/1341848021.910642.png +1341848021.946714 rgb/1341848021.946714.png 1341848021.946736 depth/1341848021.946736.png +1341848021.978747 rgb/1341848021.978747.png 1341848021.978772 depth/1341848021.978772.png +1341848022.010782 rgb/1341848022.010782.png 1341848022.010803 depth/1341848022.010803.png +1341848022.046709 rgb/1341848022.046709.png 1341848022.046726 depth/1341848022.046726.png +1341848022.078665 rgb/1341848022.078665.png 1341848022.079245 depth/1341848022.079245.png +1341848022.110954 rgb/1341848022.110954.png 1341848022.111657 depth/1341848022.111657.png +1341848022.146749 rgb/1341848022.146749.png 1341848022.146788 depth/1341848022.146788.png +1341848022.178988 rgb/1341848022.178988.png 1341848022.179046 depth/1341848022.179046.png +1341848022.214773 rgb/1341848022.214773.png 1341848022.214790 depth/1341848022.214790.png +1341848022.246774 rgb/1341848022.246774.png 1341848022.247466 depth/1341848022.247466.png +1341848022.278764 rgb/1341848022.278764.png 1341848022.279313 depth/1341848022.279313.png +1341848022.314757 rgb/1341848022.314757.png 1341848022.314776 depth/1341848022.314776.png +1341848022.354110 rgb/1341848022.354110.png 1341848022.354136 depth/1341848022.354136.png +1341848022.387191 rgb/1341848022.387191.png 1341848022.388540 depth/1341848022.388540.png +1341848022.417848 rgb/1341848022.417848.png 1341848022.418465 depth/1341848022.418465.png +1341848022.454164 rgb/1341848022.454164.png 1341848022.454189 depth/1341848022.454189.png +1341848022.485638 rgb/1341848022.485638.png 1341848022.485655 depth/1341848022.485655.png +1341848022.521730 rgb/1341848022.521730.png 1341848022.522527 depth/1341848022.522527.png +1341848022.554231 rgb/1341848022.554231.png 1341848022.554515 depth/1341848022.554515.png +1341848022.586067 rgb/1341848022.586067.png 1341848022.586079 depth/1341848022.586079.png +1341848022.621801 rgb/1341848022.621801.png 1341848022.621834 depth/1341848022.621834.png +1341848022.654208 rgb/1341848022.654208.png 1341848022.654220 depth/1341848022.654220.png +1341848022.690287 rgb/1341848022.690287.png 1341848022.690339 depth/1341848022.690339.png +1341848022.721700 rgb/1341848022.721700.png 1341848022.722043 depth/1341848022.722043.png +1341848022.782985 rgb/1341848022.782985.png 1341848022.783028 depth/1341848022.783028.png +1341848022.814772 rgb/1341848022.814772.png 1341848022.814851 depth/1341848022.814851.png +1341848022.850799 rgb/1341848022.850799.png 1341848022.851481 depth/1341848022.851481.png +1341848022.882710 rgb/1341848022.882710.png 1341848022.882730 depth/1341848022.882730.png +1341848022.918835 rgb/1341848022.918835.png 1341848022.918869 depth/1341848022.918869.png +1341848022.950815 rgb/1341848022.950815.png 1341848022.950861 depth/1341848022.950861.png +1341848022.982728 rgb/1341848022.982728.png 1341848022.982744 depth/1341848022.982744.png +1341848023.018822 rgb/1341848023.018822.png 1341848023.018832 depth/1341848023.018832.png +1341848023.050766 rgb/1341848023.050766.png 1341848023.050781 depth/1341848023.050781.png +1341848023.082738 rgb/1341848023.082738.png 1341848023.082824 depth/1341848023.082824.png +1341848023.118789 rgb/1341848023.118789.png 1341848023.118804 depth/1341848023.118804.png +1341848023.150992 rgb/1341848023.150992.png 1341848023.151020 depth/1341848023.151020.png +1341848023.186687 rgb/1341848023.186687.png 1341848023.186714 depth/1341848023.186714.png +1341848023.218702 rgb/1341848023.218702.png 1341848023.218801 depth/1341848023.218801.png +1341848023.286758 rgb/1341848023.286758.png 1341848023.286974 depth/1341848023.286974.png +1341848023.318763 rgb/1341848023.318763.png 1341848023.318791 depth/1341848023.318791.png +1341848023.354762 rgb/1341848023.354762.png 1341848023.354851 depth/1341848023.354851.png +1341848023.386908 rgb/1341848023.386908.png 1341848023.387380 depth/1341848023.387380.png +1341848023.418717 rgb/1341848023.418717.png 1341848023.418747 depth/1341848023.418747.png +1341848023.454710 rgb/1341848023.454710.png 1341848023.454727 depth/1341848023.454727.png +1341848023.487092 rgb/1341848023.487092.png 1341848023.487102 depth/1341848023.487102.png +1341848023.518675 rgb/1341848023.518675.png 1341848023.518691 depth/1341848023.518691.png +1341848023.555068 rgb/1341848023.555068.png 1341848023.555084 depth/1341848023.555084.png +1341848023.586796 rgb/1341848023.586796.png 1341848023.586829 depth/1341848023.586829.png +1341848023.622845 rgb/1341848023.622845.png 1341848023.622864 depth/1341848023.622864.png +1341848023.687172 rgb/1341848023.687172.png 1341848023.687231 depth/1341848023.687231.png +1341848023.722693 rgb/1341848023.722693.png 1341848023.722722 depth/1341848023.722722.png +1341848023.754690 rgb/1341848023.754690.png 1341848023.754708 depth/1341848023.754708.png +1341848023.786854 rgb/1341848023.786854.png 1341848023.786872 depth/1341848023.786872.png +1341848023.822788 rgb/1341848023.822788.png 1341848023.822813 depth/1341848023.822813.png +1341848023.854825 rgb/1341848023.854825.png 1341848023.854837 depth/1341848023.854837.png +1341848023.890666 rgb/1341848023.890666.png 1341848023.891258 depth/1341848023.891258.png +1341848023.922784 rgb/1341848023.922784.png 1341848023.922935 depth/1341848023.922935.png +1341848023.954826 rgb/1341848023.954826.png 1341848023.955360 depth/1341848023.955360.png +1341848023.990739 rgb/1341848023.990739.png 1341848023.990753 depth/1341848023.990753.png +1341848024.022671 rgb/1341848024.022671.png 1341848024.022689 depth/1341848024.022689.png +1341848024.054725 rgb/1341848024.054725.png 1341848024.054737 depth/1341848024.054737.png +1341848024.122843 rgb/1341848024.122843.png 1341848024.122894 depth/1341848024.122894.png +1341848024.158762 rgb/1341848024.158762.png 1341848024.158798 depth/1341848024.158798.png +1341848024.190945 rgb/1341848024.190945.png 1341848024.190998 depth/1341848024.190998.png +1341848024.222838 rgb/1341848024.222838.png 1341848024.222850 depth/1341848024.222850.png +1341848024.258826 rgb/1341848024.258826.png 1341848024.258842 depth/1341848024.258842.png +1341848024.290769 rgb/1341848024.290769.png 1341848024.290872 depth/1341848024.290872.png +1341848024.322705 rgb/1341848024.322705.png 1341848024.322718 depth/1341848024.322718.png +1341848024.358743 rgb/1341848024.358743.png 1341848024.358801 depth/1341848024.358801.png +1341848024.390878 rgb/1341848024.390878.png 1341848024.391387 depth/1341848024.391387.png +1341848024.426783 rgb/1341848024.426783.png 1341848024.427236 depth/1341848024.427236.png +1341848024.458795 rgb/1341848024.458795.png 1341848024.458805 depth/1341848024.458805.png +1341848024.491019 rgb/1341848024.491019.png 1341848024.491036 depth/1341848024.491036.png +1341848024.526783 rgb/1341848024.526783.png 1341848024.526824 depth/1341848024.526824.png +1341848024.558627 rgb/1341848024.558627.png 1341848024.558650 depth/1341848024.558650.png +1341848024.594736 rgb/1341848024.594736.png 1341848024.594752 depth/1341848024.594752.png +1341848024.626657 rgb/1341848024.626657.png 1341848024.626676 depth/1341848024.626676.png +1341848024.658717 rgb/1341848024.658717.png 1341848024.658732 depth/1341848024.658732.png +1341848024.694820 rgb/1341848024.694820.png 1341848024.694844 depth/1341848024.694844.png +1341848024.727054 rgb/1341848024.727054.png 1341848024.727084 depth/1341848024.727084.png +1341848024.758938 rgb/1341848024.758938.png 1341848024.758959 depth/1341848024.758959.png +1341848024.794701 rgb/1341848024.794701.png 1341848024.794722 depth/1341848024.794722.png +1341848024.826727 rgb/1341848024.826727.png 1341848024.826800 depth/1341848024.826800.png +1341848024.862797 rgb/1341848024.862797.png 1341848024.862820 depth/1341848024.862820.png +1341848024.894777 rgb/1341848024.894777.png 1341848024.894797 depth/1341848024.894797.png +1341848024.926754 rgb/1341848024.926754.png 1341848024.927028 depth/1341848024.927028.png +1341848024.962678 rgb/1341848024.962678.png 1341848024.962751 depth/1341848024.962751.png +1341848024.994729 rgb/1341848024.994729.png 1341848024.994762 depth/1341848024.994762.png +1341848025.026872 rgb/1341848025.026872.png 1341848025.026914 depth/1341848025.026914.png +1341848025.062647 rgb/1341848025.062647.png 1341848025.062709 depth/1341848025.062709.png +1341848025.131056 rgb/1341848025.131056.png 1341848025.131097 depth/1341848025.131097.png +1341848025.163080 rgb/1341848025.163080.png 1341848025.167799 depth/1341848025.167799.png +1341848025.194910 rgb/1341848025.194910.png 1341848025.198408 depth/1341848025.198408.png +1341848025.230646 rgb/1341848025.230646.png 1341848025.230676 depth/1341848025.230676.png +1341848025.262679 rgb/1341848025.262679.png 1341848025.262716 depth/1341848025.262716.png +1341848025.294743 rgb/1341848025.294743.png 1341848025.294760 depth/1341848025.294760.png +1341848025.330653 rgb/1341848025.330653.png 1341848025.330673 depth/1341848025.330673.png +1341848025.363022 rgb/1341848025.363022.png 1341848025.363045 depth/1341848025.363045.png +1341848025.398825 rgb/1341848025.398825.png 1341848025.398864 depth/1341848025.398864.png +1341848025.430687 rgb/1341848025.430687.png 1341848025.430702 depth/1341848025.430702.png +1341848025.462832 rgb/1341848025.462832.png 1341848025.462851 depth/1341848025.462851.png +1341848025.498683 rgb/1341848025.498683.png 1341848025.498694 depth/1341848025.498694.png +1341848025.530800 rgb/1341848025.530800.png 1341848025.530813 depth/1341848025.530813.png +1341848025.566751 rgb/1341848025.566751.png 1341848025.566774 depth/1341848025.566774.png +1341848025.598738 rgb/1341848025.598738.png 1341848025.598755 depth/1341848025.598755.png +1341848025.630731 rgb/1341848025.630731.png 1341848025.630827 depth/1341848025.630827.png +1341848025.666677 rgb/1341848025.666677.png 1341848025.666699 depth/1341848025.666699.png +1341848025.698755 rgb/1341848025.698755.png 1341848025.698772 depth/1341848025.698772.png +1341848025.730719 rgb/1341848025.730719.png 1341848025.730736 depth/1341848025.730736.png +1341848025.766716 rgb/1341848025.766716.png 1341848025.766728 depth/1341848025.766728.png +1341848025.798909 rgb/1341848025.798909.png 1341848025.798965 depth/1341848025.798965.png +1341848025.834828 rgb/1341848025.834828.png 1341848025.834852 depth/1341848025.834852.png +1341848025.866679 rgb/1341848025.866679.png 1341848025.866702 depth/1341848025.866702.png +1341848025.898725 rgb/1341848025.898725.png 1341848025.898811 depth/1341848025.898811.png +1341848025.934824 rgb/1341848025.934824.png 1341848025.934850 depth/1341848025.934850.png +1341848025.967138 rgb/1341848025.967138.png 1341848025.967180 depth/1341848025.967180.png +1341848025.998679 rgb/1341848025.998679.png 1341848025.998763 depth/1341848025.998763.png +1341848026.034640 rgb/1341848026.034640.png 1341848026.034672 depth/1341848026.034672.png +1341848026.066857 rgb/1341848026.066857.png 1341848026.066885 depth/1341848026.066885.png +1341848026.102823 rgb/1341848026.102823.png 1341848026.102834 depth/1341848026.102834.png +1341848026.134670 rgb/1341848026.134670.png 1341848026.134679 depth/1341848026.134679.png +1341848026.166699 rgb/1341848026.166699.png 1341848026.167384 depth/1341848026.167384.png +1341848026.202754 rgb/1341848026.202754.png 1341848026.202788 depth/1341848026.202788.png +1341848026.234940 rgb/1341848026.234940.png 1341848026.234963 depth/1341848026.234963.png +1341848026.267001 rgb/1341848026.267001.png 1341848026.267027 depth/1341848026.267027.png +1341848026.302861 rgb/1341848026.302861.png 1341848026.302871 depth/1341848026.302871.png +1341848026.334824 rgb/1341848026.334824.png 1341848026.334861 depth/1341848026.334861.png +1341848026.371024 rgb/1341848026.371024.png 1341848026.371055 depth/1341848026.371055.png +1341848026.402725 rgb/1341848026.402725.png 1341848026.402746 depth/1341848026.402746.png +1341848026.434734 rgb/1341848026.434734.png 1341848026.434767 depth/1341848026.434767.png +1341848026.470839 rgb/1341848026.470839.png 1341848026.470906 depth/1341848026.470906.png +1341848026.502672 rgb/1341848026.502672.png 1341848026.502716 depth/1341848026.502716.png +1341848026.534739 rgb/1341848026.534739.png 1341848026.534781 depth/1341848026.534781.png +1341848026.570847 rgb/1341848026.570847.png 1341848026.570890 depth/1341848026.570890.png +1341848026.602721 rgb/1341848026.602721.png 1341848026.602778 depth/1341848026.602778.png +1341848026.641972 rgb/1341848026.641972.png 1341848026.642025 depth/1341848026.642025.png +1341848026.702795 rgb/1341848026.702795.png 1341848026.702812 depth/1341848026.702812.png +1341848026.738795 rgb/1341848026.738795.png 1341848026.738850 depth/1341848026.738850.png +1341848026.770813 rgb/1341848026.770813.png 1341848026.770822 depth/1341848026.770822.png +1341848026.806747 rgb/1341848026.806747.png 1341848026.806756 depth/1341848026.806756.png +1341848026.838668 rgb/1341848026.838668.png 1341848026.838685 depth/1341848026.838685.png +1341848026.878025 rgb/1341848026.878025.png 1341848026.878058 depth/1341848026.878058.png +1341848026.938881 rgb/1341848026.938881.png 1341848026.938914 depth/1341848026.938914.png +1341848026.970651 rgb/1341848026.970651.png 1341848026.970715 depth/1341848026.970715.png +1341848027.006815 rgb/1341848027.006815.png 1341848027.006847 depth/1341848027.006847.png +1341848027.038669 rgb/1341848027.038669.png 1341848027.038724 depth/1341848027.038724.png +1341848027.074785 rgb/1341848027.074785.png 1341848027.074808 depth/1341848027.074808.png +1341848027.106663 rgb/1341848027.106663.png 1341848027.106672 depth/1341848027.106672.png +1341848027.138671 rgb/1341848027.138671.png 1341848027.138707 depth/1341848027.138707.png +1341848027.174831 rgb/1341848027.174831.png 1341848027.174845 depth/1341848027.174845.png +1341848027.207212 rgb/1341848027.207212.png 1341848027.207228 depth/1341848027.207228.png +1341848027.238696 rgb/1341848027.238696.png 1341848027.238712 depth/1341848027.238712.png +1341848027.274701 rgb/1341848027.274701.png 1341848027.274713 depth/1341848027.274713.png +1341848027.306705 rgb/1341848027.306705.png 1341848027.306742 depth/1341848027.306742.png +1341848027.342775 rgb/1341848027.342775.png 1341848027.342833 depth/1341848027.342833.png +1341848027.374943 rgb/1341848027.374943.png 1341848027.374989 depth/1341848027.374989.png +1341848027.406837 rgb/1341848027.406837.png 1341848027.406863 depth/1341848027.406863.png +1341848027.442959 rgb/1341848027.442959.png 1341848027.442981 depth/1341848027.442981.png +1341848027.474800 rgb/1341848027.474800.png 1341848027.474828 depth/1341848027.474828.png +1341848027.506714 rgb/1341848027.506714.png 1341848027.506780 depth/1341848027.506780.png +1341848027.543310 rgb/1341848027.543310.png 1341848027.543335 depth/1341848027.543335.png +1341848027.574717 rgb/1341848027.574717.png 1341848027.575728 depth/1341848027.575728.png +1341848027.610716 rgb/1341848027.610716.png 1341848027.611142 depth/1341848027.611142.png +1341848027.642684 rgb/1341848027.642684.png 1341848027.643153 depth/1341848027.643153.png +1341848027.674731 rgb/1341848027.674731.png 1341848027.674775 depth/1341848027.674775.png +1341848027.711026 rgb/1341848027.711026.png 1341848027.711730 depth/1341848027.711730.png +1341848027.742789 rgb/1341848027.742789.png 1341848027.742804 depth/1341848027.742804.png +1341848027.778768 rgb/1341848027.778768.png 1341848027.778817 depth/1341848027.778817.png +1341848027.810746 rgb/1341848027.810746.png 1341848027.810851 depth/1341848027.810851.png +1341848027.842836 rgb/1341848027.842836.png 1341848027.842862 depth/1341848027.842862.png +1341848027.878669 rgb/1341848027.878669.png 1341848027.878682 depth/1341848027.878682.png +1341848027.911127 rgb/1341848027.911127.png 1341848027.911189 depth/1341848027.911189.png +1341848027.942732 rgb/1341848027.942732.png 1341848027.942760 depth/1341848027.942760.png +1341848027.978757 rgb/1341848027.978757.png 1341848027.978770 depth/1341848027.978770.png +1341848028.011034 rgb/1341848028.011034.png 1341848028.011132 depth/1341848028.011132.png +1341848028.046706 rgb/1341848028.046706.png 1341848028.046719 depth/1341848028.046719.png +1341848028.078967 rgb/1341848028.078967.png 1341848028.079918 depth/1341848028.079918.png +1341848028.110971 rgb/1341848028.110971.png 1341848028.112250 depth/1341848028.112250.png +1341848028.150637 rgb/1341848028.150637.png 1341848028.150704 depth/1341848028.150704.png +1341848028.186050 rgb/1341848028.186050.png 1341848028.187273 depth/1341848028.187273.png +1341848028.254235 rgb/1341848028.254235.png 1341848028.255491 depth/1341848028.255491.png +1341848028.314908 rgb/1341848028.314908.png 1341848028.315859 depth/1341848028.315859.png +1341848028.378956 rgb/1341848028.378956.png 1341848028.378974 depth/1341848028.378974.png +1341848028.414628 rgb/1341848028.414628.png 1341848028.415502 depth/1341848028.415502.png +1341848028.447632 rgb/1341848028.447632.png 1341848028.447654 depth/1341848028.447654.png +1341848028.482785 rgb/1341848028.482785.png 1341848028.483591 depth/1341848028.483591.png +1341848028.514701 rgb/1341848028.514701.png 1341848028.514716 depth/1341848028.514716.png +1341848028.546612 rgb/1341848028.546612.png 1341848028.546624 depth/1341848028.546624.png +1341848028.582747 rgb/1341848028.582747.png 1341848028.582765 depth/1341848028.582765.png +1341848028.614649 rgb/1341848028.614649.png 1341848028.614668 depth/1341848028.614668.png +1341848028.653766 rgb/1341848028.653766.png 1341848028.653785 depth/1341848028.653785.png +1341848028.721828 rgb/1341848028.721828.png 1341848028.721886 depth/1341848028.721886.png +1341848028.782861 rgb/1341848028.782861.png 1341848028.782881 depth/1341848028.782881.png +1341848028.814757 rgb/1341848028.814757.png 1341848028.814775 depth/1341848028.814775.png +1341848028.850773 rgb/1341848028.850773.png 1341848028.850785 depth/1341848028.850785.png +1341848028.882714 rgb/1341848028.882714.png 1341848028.882756 depth/1341848028.882756.png +1341848028.914838 rgb/1341848028.914838.png 1341848028.914857 depth/1341848028.914857.png +1341848028.950881 rgb/1341848028.950881.png 1341848028.951062 depth/1341848028.951062.png +1341848028.982690 rgb/1341848028.982690.png 1341848028.982706 depth/1341848028.982706.png +1341848029.018728 rgb/1341848029.018728.png 1341848029.018750 depth/1341848029.018750.png +1341848029.082877 rgb/1341848029.082877.png 1341848029.082899 depth/1341848029.082899.png +1341848029.118800 rgb/1341848029.118800.png 1341848029.118814 depth/1341848029.118814.png +1341848029.150715 rgb/1341848029.150715.png 1341848029.151467 depth/1341848029.151467.png +1341848029.182676 rgb/1341848029.182676.png 1341848029.182687 depth/1341848029.182687.png +1341848029.218708 rgb/1341848029.218708.png 1341848029.218723 depth/1341848029.218723.png +1341848029.250626 rgb/1341848029.250626.png 1341848029.250646 depth/1341848029.250646.png +1341848029.286969 rgb/1341848029.286969.png 1341848029.286988 depth/1341848029.286988.png +1341848029.320225 rgb/1341848029.320225.png 1341848029.320239 depth/1341848029.320239.png +1341848029.350954 rgb/1341848029.350954.png 1341848029.351197 depth/1341848029.351197.png +1341848029.386923 rgb/1341848029.386923.png 1341848029.386940 depth/1341848029.386940.png +1341848029.418757 rgb/1341848029.418757.png 1341848029.418775 depth/1341848029.418775.png +1341848029.450819 rgb/1341848029.450819.png 1341848029.450896 depth/1341848029.450896.png +1341848029.486788 rgb/1341848029.486788.png 1341848029.486809 depth/1341848029.486809.png +1341848029.518925 rgb/1341848029.518925.png 1341848029.519151 depth/1341848029.519151.png +1341848029.554721 rgb/1341848029.554721.png 1341848029.554734 depth/1341848029.554734.png +1341848029.586990 rgb/1341848029.586990.png 1341848029.587004 depth/1341848029.587004.png +1341848029.618715 rgb/1341848029.618715.png 1341848029.618729 depth/1341848029.618729.png +1341848029.655302 rgb/1341848029.655302.png 1341848029.655324 depth/1341848029.655324.png +1341848029.686830 rgb/1341848029.686830.png 1341848029.686905 depth/1341848029.686905.png +1341848029.718752 rgb/1341848029.718752.png 1341848029.718815 depth/1341848029.718815.png +1341848029.754791 rgb/1341848029.754791.png 1341848029.754809 depth/1341848029.754809.png +1341848029.786949 rgb/1341848029.786949.png 1341848029.787734 depth/1341848029.787734.png +1341848029.822778 rgb/1341848029.822778.png 1341848029.822795 depth/1341848029.822795.png +1341848029.854811 rgb/1341848029.854811.png 1341848029.854831 depth/1341848029.854831.png +1341848029.887992 rgb/1341848029.887992.png 1341848029.888015 depth/1341848029.888015.png +1341848029.922779 rgb/1341848029.922779.png 1341848029.923583 depth/1341848029.923583.png +1341848029.954640 rgb/1341848029.954640.png 1341848029.954654 depth/1341848029.954654.png +1341848029.990762 rgb/1341848029.990762.png 1341848029.990907 depth/1341848029.990907.png +1341848030.022873 rgb/1341848030.022873.png 1341848030.022894 depth/1341848030.022894.png +1341848030.054776 rgb/1341848030.054776.png 1341848030.054803 depth/1341848030.054803.png +1341848030.090782 rgb/1341848030.090782.png 1341848030.090796 depth/1341848030.090796.png +1341848030.122796 rgb/1341848030.122796.png 1341848030.122805 depth/1341848030.122805.png +1341848030.154918 rgb/1341848030.154918.png 1341848030.154932 depth/1341848030.154932.png +1341848030.190683 rgb/1341848030.190683.png 1341848030.190756 depth/1341848030.190756.png +1341848030.222713 rgb/1341848030.222713.png 1341848030.222780 depth/1341848030.222780.png +1341848030.258930 rgb/1341848030.258930.png 1341848030.258949 depth/1341848030.258949.png +1341848030.290864 rgb/1341848030.290864.png 1341848030.290914 depth/1341848030.290914.png +1341848030.322775 rgb/1341848030.322775.png 1341848030.323592 depth/1341848030.323592.png +1341848030.358886 rgb/1341848030.358886.png 1341848030.358972 depth/1341848030.358972.png +1341848030.390832 rgb/1341848030.390832.png 1341848030.390848 depth/1341848030.390848.png +1341848030.422795 rgb/1341848030.422795.png 1341848030.422812 depth/1341848030.422812.png +1341848030.458888 rgb/1341848030.458888.png 1341848030.458900 depth/1341848030.458900.png +1341848030.490846 rgb/1341848030.490846.png 1341848030.490939 depth/1341848030.490939.png +1341848030.526716 rgb/1341848030.526716.png 1341848030.526729 depth/1341848030.526729.png +1341848030.565795 rgb/1341848030.565795.png 1341848030.565858 depth/1341848030.565858.png +1341848030.626961 rgb/1341848030.626961.png 1341848030.627016 depth/1341848030.627016.png +1341848030.658903 rgb/1341848030.658903.png 1341848030.658937 depth/1341848030.658937.png +1341848030.690656 rgb/1341848030.690656.png 1341848030.690669 depth/1341848030.690669.png +1341848030.726765 rgb/1341848030.726765.png 1341848030.726776 depth/1341848030.726776.png +1341848030.758759 rgb/1341848030.758759.png 1341848030.758782 depth/1341848030.758782.png +1341848030.794692 rgb/1341848030.794692.png 1341848030.794790 depth/1341848030.794790.png +1341848030.827483 rgb/1341848030.827483.png 1341848030.827510 depth/1341848030.827510.png +1341848030.859838 rgb/1341848030.859838.png 1341848030.860076 depth/1341848030.860076.png +1341848030.894711 rgb/1341848030.894711.png 1341848030.894737 depth/1341848030.894737.png +1341848030.926741 rgb/1341848030.926741.png 1341848030.926760 depth/1341848030.926760.png +1341848030.958727 rgb/1341848030.958727.png 1341848030.958740 depth/1341848030.958740.png +1341848030.994735 rgb/1341848030.994735.png 1341848030.994752 depth/1341848030.994752.png +1341848031.026698 rgb/1341848031.026698.png 1341848031.026758 depth/1341848031.026758.png +1341848031.062783 rgb/1341848031.062783.png 1341848031.062796 depth/1341848031.062796.png +1341848031.094761 rgb/1341848031.094761.png 1341848031.094801 depth/1341848031.094801.png +1341848031.126776 rgb/1341848031.126776.png 1341848031.126837 depth/1341848031.126837.png +1341848031.162860 rgb/1341848031.162860.png 1341848031.162900 depth/1341848031.162900.png +1341848031.194685 rgb/1341848031.194685.png 1341848031.194721 depth/1341848031.194721.png +1341848031.230953 rgb/1341848031.230953.png 1341848031.231582 depth/1341848031.231582.png +1341848031.262715 rgb/1341848031.262715.png 1341848031.262738 depth/1341848031.262738.png +1341848031.294747 rgb/1341848031.294747.png 1341848031.294789 depth/1341848031.294789.png +1341848031.330754 rgb/1341848031.330754.png 1341848031.330775 depth/1341848031.330775.png +1341848031.363008 rgb/1341848031.363008.png 1341848031.363880 depth/1341848031.363880.png +1341848031.394753 rgb/1341848031.394753.png 1341848031.394778 depth/1341848031.394778.png +1341848031.430611 rgb/1341848031.430611.png 1341848031.430627 depth/1341848031.430627.png +1341848031.472150 rgb/1341848031.472150.png 1341848031.472171 depth/1341848031.472171.png +1341848031.502110 rgb/1341848031.502110.png 1341848031.502139 depth/1341848031.502139.png +1341848031.562876 rgb/1341848031.562876.png 1341848031.562937 depth/1341848031.562937.png +1341848031.598730 rgb/1341848031.598730.png 1341848031.598770 depth/1341848031.598770.png +1341848031.630816 rgb/1341848031.630816.png 1341848031.630831 depth/1341848031.630831.png +1341848031.662784 rgb/1341848031.662784.png 1341848031.663486 depth/1341848031.663486.png +1341848031.698757 rgb/1341848031.698757.png 1341848031.698824 depth/1341848031.698824.png +1341848031.730668 rgb/1341848031.730668.png 1341848031.730691 depth/1341848031.730691.png +1341848031.766658 rgb/1341848031.766658.png 1341848031.766694 depth/1341848031.766694.png +1341848031.798743 rgb/1341848031.798743.png 1341848031.798754 depth/1341848031.798754.png +1341848031.830821 rgb/1341848031.830821.png 1341848031.831520 depth/1341848031.831520.png +1341848031.866735 rgb/1341848031.866735.png 1341848031.866772 depth/1341848031.866772.png +1341848031.898722 rgb/1341848031.898722.png 1341848031.898737 depth/1341848031.898737.png +1341848031.930844 rgb/1341848031.930844.png 1341848031.931492 depth/1341848031.931492.png +1341848031.966694 rgb/1341848031.966694.png 1341848031.966709 depth/1341848031.966709.png +1341848031.998742 rgb/1341848031.998742.png 1341848031.998759 depth/1341848031.998759.png +1341848032.034711 rgb/1341848032.034711.png 1341848032.034732 depth/1341848032.034732.png +1341848032.066718 rgb/1341848032.066718.png 1341848032.066736 depth/1341848032.066736.png +1341848032.098732 rgb/1341848032.098732.png 1341848032.098745 depth/1341848032.098745.png +1341848032.134739 rgb/1341848032.134739.png 1341848032.134784 depth/1341848032.134784.png +1341848032.166964 rgb/1341848032.166964.png 1341848032.166979 depth/1341848032.166979.png +1341848032.203043 rgb/1341848032.203043.png 1341848032.203097 depth/1341848032.203097.png +1341848032.234663 rgb/1341848032.234663.png 1341848032.234711 depth/1341848032.234711.png +1341848032.266730 rgb/1341848032.266730.png 1341848032.266756 depth/1341848032.266756.png +1341848032.302842 rgb/1341848032.302842.png 1341848032.302891 depth/1341848032.302891.png +1341848032.334617 rgb/1341848032.334617.png 1341848032.334681 depth/1341848032.334681.png +1341848032.366699 rgb/1341848032.366699.png 1341848032.367298 depth/1341848032.367298.png +1341848032.402980 rgb/1341848032.402980.png 1341848032.402996 depth/1341848032.402996.png +1341848032.434730 rgb/1341848032.434730.png 1341848032.434774 depth/1341848032.434774.png +1341848032.470791 rgb/1341848032.470791.png 1341848032.470848 depth/1341848032.470848.png +1341848032.502972 rgb/1341848032.502972.png 1341848032.502987 depth/1341848032.502987.png +1341848032.534733 rgb/1341848032.534733.png 1341848032.534750 depth/1341848032.534750.png +1341848032.570910 rgb/1341848032.570910.png 1341848032.570937 depth/1341848032.570937.png +1341848032.603044 rgb/1341848032.603044.png 1341848032.603067 depth/1341848032.603067.png +1341848032.634746 rgb/1341848032.634746.png 1341848032.634766 depth/1341848032.634766.png +1341848032.670780 rgb/1341848032.670780.png 1341848032.670791 depth/1341848032.670791.png +1341848032.702791 rgb/1341848032.702791.png 1341848032.702808 depth/1341848032.702808.png +1341848032.738725 rgb/1341848032.738725.png 1341848032.738747 depth/1341848032.738747.png +1341848032.770741 rgb/1341848032.770741.png 1341848032.770781 depth/1341848032.770781.png +1341848032.802941 rgb/1341848032.802941.png 1341848032.803038 depth/1341848032.803038.png +1341848032.838781 rgb/1341848032.838781.png 1341848032.838796 depth/1341848032.838796.png +1341848032.870732 rgb/1341848032.870732.png 1341848032.870753 depth/1341848032.870753.png +1341848032.902707 rgb/1341848032.902707.png 1341848032.902950 depth/1341848032.902950.png +1341848032.938845 rgb/1341848032.938845.png 1341848032.938895 depth/1341848032.938895.png +1341848032.970816 rgb/1341848032.970816.png 1341848032.970839 depth/1341848032.970839.png +1341848033.006687 rgb/1341848033.006687.png 1341848033.006708 depth/1341848033.006708.png +1341848033.039238 rgb/1341848033.039238.png 1341848033.039254 depth/1341848033.039254.png +1341848033.070841 rgb/1341848033.070841.png 1341848033.070860 depth/1341848033.070860.png +1341848033.106948 rgb/1341848033.106948.png 1341848033.106966 depth/1341848033.106966.png +1341848033.139110 rgb/1341848033.139110.png 1341848033.139123 depth/1341848033.139123.png +1341848033.170741 rgb/1341848033.170741.png 1341848033.170754 depth/1341848033.170754.png +1341848033.206854 rgb/1341848033.206854.png 1341848033.206871 depth/1341848033.206871.png +1341848033.238728 rgb/1341848033.238728.png 1341848033.239415 depth/1341848033.239415.png +1341848033.274940 rgb/1341848033.274940.png 1341848033.274956 depth/1341848033.274956.png +1341848033.306665 rgb/1341848033.306665.png 1341848033.306706 depth/1341848033.306706.png +1341848033.338836 rgb/1341848033.338836.png 1341848033.338847 depth/1341848033.338847.png +1341848033.374810 rgb/1341848033.374810.png 1341848033.374830 depth/1341848033.374830.png +1341848033.406805 rgb/1341848033.406805.png 1341848033.406820 depth/1341848033.406820.png +1341848033.443097 rgb/1341848033.443097.png 1341848033.443142 depth/1341848033.443142.png +1341848033.474671 rgb/1341848033.474671.png 1341848033.474682 depth/1341848033.474682.png +1341848033.506807 rgb/1341848033.506807.png 1341848033.506821 depth/1341848033.506821.png +1341848033.542876 rgb/1341848033.542876.png 1341848033.542898 depth/1341848033.542898.png +1341848033.574826 rgb/1341848033.574826.png 1341848033.575008 depth/1341848033.575008.png +1341848033.606870 rgb/1341848033.606870.png 1341848033.606896 depth/1341848033.606896.png +1341848033.642934 rgb/1341848033.642934.png 1341848033.642954 depth/1341848033.642954.png +1341848033.674924 rgb/1341848033.674924.png 1341848033.674937 depth/1341848033.674937.png +1341848033.710808 rgb/1341848033.710808.png 1341848033.710835 depth/1341848033.710835.png +1341848033.742797 rgb/1341848033.742797.png 1341848033.742812 depth/1341848033.742812.png +1341848033.774817 rgb/1341848033.774817.png 1341848033.774832 depth/1341848033.774832.png +1341848033.811114 rgb/1341848033.811114.png 1341848033.811932 depth/1341848033.811932.png +1341848033.842774 rgb/1341848033.842774.png 1341848033.842813 depth/1341848033.842813.png +1341848033.874878 rgb/1341848033.874878.png 1341848033.874896 depth/1341848033.874896.png +1341848033.911229 rgb/1341848033.911229.png 1341848033.911372 depth/1341848033.911372.png +1341848033.942752 rgb/1341848033.942752.png 1341848033.942768 depth/1341848033.942768.png +1341848033.978916 rgb/1341848033.978916.png 1341848033.978933 depth/1341848033.978933.png +1341848034.010755 rgb/1341848034.010755.png 1341848034.010820 depth/1341848034.010820.png +1341848034.042713 rgb/1341848034.042713.png 1341848034.042730 depth/1341848034.042730.png +1341848034.078802 rgb/1341848034.078802.png 1341848034.078815 depth/1341848034.078815.png +1341848034.110771 rgb/1341848034.110771.png 1341848034.110948 depth/1341848034.110948.png +1341848034.142710 rgb/1341848034.142710.png 1341848034.142724 depth/1341848034.142724.png +1341848034.178809 rgb/1341848034.178809.png 1341848034.178845 depth/1341848034.178845.png +1341848034.210696 rgb/1341848034.210696.png 1341848034.210706 depth/1341848034.210706.png +1341848034.246723 rgb/1341848034.246723.png 1341848034.246736 depth/1341848034.246736.png +1341848034.278739 rgb/1341848034.278739.png 1341848034.278759 depth/1341848034.278759.png +1341848034.318061 rgb/1341848034.318061.png 1341848034.318578 depth/1341848034.318578.png +1341848034.353785 rgb/1341848034.353785.png 1341848034.353802 depth/1341848034.353802.png +1341848034.386162 rgb/1341848034.386162.png 1341848034.386178 depth/1341848034.386178.png +1341848034.421769 rgb/1341848034.421769.png 1341848034.421782 depth/1341848034.421782.png +1341848034.453838 rgb/1341848034.453838.png 1341848034.454621 depth/1341848034.454621.png +1341848034.485678 rgb/1341848034.485678.png 1341848034.485690 depth/1341848034.485690.png +1341848034.521747 rgb/1341848034.521747.png 1341848034.521758 depth/1341848034.521758.png +1341848034.553684 rgb/1341848034.553684.png 1341848034.553808 depth/1341848034.553808.png +1341848034.585774 rgb/1341848034.585774.png 1341848034.585791 depth/1341848034.585791.png +1341848034.653784 rgb/1341848034.653784.png 1341848034.654020 depth/1341848034.654020.png +1341848034.715163 rgb/1341848034.715163.png 1341848034.715221 depth/1341848034.715221.png +1341848034.746742 rgb/1341848034.746742.png 1341848034.746757 depth/1341848034.746757.png +1341848034.782798 rgb/1341848034.782798.png 1341848034.782867 depth/1341848034.782867.png +1341848034.814737 rgb/1341848034.814737.png 1341848034.814783 depth/1341848034.814783.png +1341848034.846851 rgb/1341848034.846851.png 1341848034.846883 depth/1341848034.846883.png +1341848034.882707 rgb/1341848034.882707.png 1341848034.882748 depth/1341848034.882748.png +1341848034.914816 rgb/1341848034.914816.png 1341848034.914862 depth/1341848034.914862.png +1341848034.951491 rgb/1341848034.951491.png 1341848034.952538 depth/1341848034.952538.png +1341848034.983028 rgb/1341848034.983028.png 1341848034.983102 depth/1341848034.983102.png +1341848035.014942 rgb/1341848035.014942.png 1341848035.014963 depth/1341848035.014963.png +1341848035.050945 rgb/1341848035.050945.png 1341848035.051588 depth/1341848035.051588.png +1341848035.084295 rgb/1341848035.084295.png 1341848035.084843 depth/1341848035.084843.png +1341848035.118886 rgb/1341848035.118886.png 1341848035.119920 depth/1341848035.119920.png +1341848035.218946 rgb/1341848035.218946.png 1341848035.219021 depth/1341848035.219021.png +1341848035.284261 rgb/1341848035.284261.png 1341848035.284280 depth/1341848035.284280.png +1341848035.319914 rgb/1341848035.319914.png 1341848035.320216 depth/1341848035.320216.png +1341848035.350991 rgb/1341848035.350991.png 1341848035.351243 depth/1341848035.351243.png +1341848035.422709 rgb/1341848035.422709.png 1341848035.423486 depth/1341848035.423486.png +1341848035.486822 rgb/1341848035.486822.png 1341848035.486844 depth/1341848035.486844.png +1341848035.518623 rgb/1341848035.518623.png 1341848035.518643 depth/1341848035.518643.png +1341848035.550852 rgb/1341848035.550852.png 1341848035.550866 depth/1341848035.550866.png +1341848035.586716 rgb/1341848035.586716.png 1341848035.586745 depth/1341848035.586745.png +1341848035.618790 rgb/1341848035.618790.png 1341848035.619346 depth/1341848035.619346.png +1341848035.654654 rgb/1341848035.654654.png 1341848035.654670 depth/1341848035.654670.png +1341848035.686693 rgb/1341848035.686693.png 1341848035.686737 depth/1341848035.686737.png +1341848035.718791 rgb/1341848035.718791.png 1341848035.718808 depth/1341848035.718808.png +1341848035.755991 rgb/1341848035.755991.png 1341848035.756650 depth/1341848035.756650.png +1341848035.786729 rgb/1341848035.786729.png 1341848035.786744 depth/1341848035.786744.png +1341848035.818784 rgb/1341848035.818784.png 1341848035.818816 depth/1341848035.818816.png +1341848035.854701 rgb/1341848035.854701.png 1341848035.854749 depth/1341848035.854749.png +1341848035.886689 rgb/1341848035.886689.png 1341848035.886726 depth/1341848035.886726.png +1341848035.922832 rgb/1341848035.922832.png 1341848035.922862 depth/1341848035.922862.png +1341848035.954633 rgb/1341848035.954633.png 1341848035.954650 depth/1341848035.954650.png +1341848035.986741 rgb/1341848035.986741.png 1341848035.986765 depth/1341848035.986765.png +1341848036.022779 rgb/1341848036.022779.png 1341848036.022805 depth/1341848036.022805.png +1341848036.054911 rgb/1341848036.054911.png 1341848036.054940 depth/1341848036.054940.png +1341848036.087013 rgb/1341848036.087013.png 1341848036.087039 depth/1341848036.087039.png +1341848036.122737 rgb/1341848036.122737.png 1341848036.122749 depth/1341848036.122749.png +1341848036.154810 rgb/1341848036.154810.png 1341848036.154843 depth/1341848036.154843.png +1341848036.190835 rgb/1341848036.190835.png 1341848036.190873 depth/1341848036.190873.png +1341848036.223282 rgb/1341848036.223282.png 1341848036.223325 depth/1341848036.223325.png +1341848036.254692 rgb/1341848036.254692.png 1341848036.254719 depth/1341848036.254719.png +1341848036.290758 rgb/1341848036.290758.png 1341848036.290792 depth/1341848036.290792.png +1341848036.354859 rgb/1341848036.354859.png 1341848036.354932 depth/1341848036.354932.png +1341848036.390843 rgb/1341848036.390843.png 1341848036.390859 depth/1341848036.390859.png +1341848036.458823 rgb/1341848036.458823.png 1341848036.458857 depth/1341848036.458857.png +1341848036.491205 rgb/1341848036.491205.png 1341848036.491256 depth/1341848036.491256.png +1341848036.522726 rgb/1341848036.522726.png 1341848036.522744 depth/1341848036.522744.png +1341848036.558942 rgb/1341848036.558942.png 1341848036.558959 depth/1341848036.558959.png +1341848036.590723 rgb/1341848036.590723.png 1341848036.590845 depth/1341848036.590845.png +1341848036.626802 rgb/1341848036.626802.png 1341848036.626814 depth/1341848036.626814.png +1341848036.658670 rgb/1341848036.658670.png 1341848036.659276 depth/1341848036.659276.png +1341848036.691175 rgb/1341848036.691175.png 1341848036.691212 depth/1341848036.691212.png +1341848036.726753 rgb/1341848036.726753.png 1341848036.727207 depth/1341848036.727207.png +1341848036.758851 rgb/1341848036.758851.png 1341848036.758965 depth/1341848036.758965.png +1341848036.790720 rgb/1341848036.790720.png 1341848036.790795 depth/1341848036.790795.png +1341848036.826992 rgb/1341848036.826992.png 1341848036.827011 depth/1341848036.827011.png +1341848036.858633 rgb/1341848036.858633.png 1341848036.858692 depth/1341848036.858692.png +1341848036.926846 rgb/1341848036.926846.png 1341848036.926861 depth/1341848036.926861.png +1341848036.958725 rgb/1341848036.958725.png 1341848036.958741 depth/1341848036.958741.png +1341848036.994836 rgb/1341848036.994836.png 1341848036.994877 depth/1341848036.994877.png +1341848037.026790 rgb/1341848037.026790.png 1341848037.026816 depth/1341848037.026816.png +1341848037.061042 rgb/1341848037.061042.png 1341848037.061067 depth/1341848037.061067.png +1341848037.094661 rgb/1341848037.094661.png 1341848037.094704 depth/1341848037.094704.png +1341848037.126709 rgb/1341848037.126709.png 1341848037.126721 depth/1341848037.126721.png +1341848037.162789 rgb/1341848037.162789.png 1341848037.162827 depth/1341848037.162827.png +1341848037.194724 rgb/1341848037.194724.png 1341848037.194761 depth/1341848037.194761.png +1341848037.227032 rgb/1341848037.227032.png 1341848037.227067 depth/1341848037.227067.png +1341848037.263738 rgb/1341848037.263738.png 1341848037.263842 depth/1341848037.263842.png +1341848037.295192 rgb/1341848037.295192.png 1341848037.295209 depth/1341848037.295209.png +1341848037.326868 rgb/1341848037.326868.png 1341848037.326883 depth/1341848037.326883.png +1341848037.362746 rgb/1341848037.362746.png 1341848037.362781 depth/1341848037.362781.png +1341848037.395057 rgb/1341848037.395057.png 1341848037.395068 depth/1341848037.395068.png +1341848037.430946 rgb/1341848037.430946.png 1341848037.431014 depth/1341848037.431014.png +1341848037.462765 rgb/1341848037.462765.png 1341848037.462779 depth/1341848037.462779.png +1341848037.530725 rgb/1341848037.530725.png 1341848037.530750 depth/1341848037.530750.png +1341848037.562958 rgb/1341848037.562958.png 1341848037.562996 depth/1341848037.562996.png +1341848037.595756 rgb/1341848037.595756.png 1341848037.595772 depth/1341848037.595772.png +1341848037.630756 rgb/1341848037.630756.png 1341848037.631133 depth/1341848037.631133.png +1341848037.662669 rgb/1341848037.662669.png 1341848037.662683 depth/1341848037.662683.png +1341848037.698670 rgb/1341848037.698670.png 1341848037.698730 depth/1341848037.698730.png +1341848037.730964 rgb/1341848037.730964.png 1341848037.730978 depth/1341848037.730978.png +1341848037.769764 rgb/1341848037.769764.png 1341848037.769809 depth/1341848037.769809.png +1341848037.837792 rgb/1341848037.837792.png 1341848037.837827 depth/1341848037.837827.png +1341848037.898921 rgb/1341848037.898921.png 1341848037.898948 depth/1341848037.898948.png +1341848037.930939 rgb/1341848037.930939.png 1341848037.930977 depth/1341848037.930977.png +1341848037.966864 rgb/1341848037.966864.png 1341848037.966899 depth/1341848037.966899.png +1341848037.998629 rgb/1341848037.998629.png 1341848037.998697 depth/1341848037.998697.png +1341848038.030908 rgb/1341848038.030908.png 1341848038.030940 depth/1341848038.030940.png +1341848038.066849 rgb/1341848038.066849.png 1341848038.066878 depth/1341848038.066878.png +1341848038.098674 rgb/1341848038.098674.png 1341848038.098693 depth/1341848038.098693.png +1341848038.134662 rgb/1341848038.134662.png 1341848038.134674 depth/1341848038.134674.png +1341848038.166674 rgb/1341848038.166674.png 1341848038.166692 depth/1341848038.166692.png +1341848038.198711 rgb/1341848038.198711.png 1341848038.198737 depth/1341848038.198737.png +1341848038.234726 rgb/1341848038.234726.png 1341848038.234752 depth/1341848038.234752.png +1341848038.274093 rgb/1341848038.274093.png 1341848038.274266 depth/1341848038.274266.png +1341848038.306525 rgb/1341848038.306525.png 1341848038.306668 depth/1341848038.306668.png +1341848038.341933 rgb/1341848038.341933.png 1341848038.341971 depth/1341848038.341971.png +1341848038.374117 rgb/1341848038.374117.png 1341848038.374124 depth/1341848038.374124.png +1341848038.409802 rgb/1341848038.409802.png 1341848038.409820 depth/1341848038.409820.png +1341848038.441825 rgb/1341848038.441825.png 1341848038.442214 depth/1341848038.442214.png +1341848038.473889 rgb/1341848038.473889.png 1341848038.473912 depth/1341848038.473912.png +1341848038.510185 rgb/1341848038.510185.png 1341848038.510216 depth/1341848038.510216.png +1341848038.566862 rgb/1341848038.566862.png 1341848038.566894 depth/1341848038.566894.png +1341848038.602989 rgb/1341848038.602989.png 1341848038.603019 depth/1341848038.603019.png +1341848038.634739 rgb/1341848038.634739.png 1341848038.634757 depth/1341848038.634757.png +1341848038.670685 rgb/1341848038.670685.png 1341848038.670717 depth/1341848038.670717.png +1341848038.702868 rgb/1341848038.702868.png 1341848038.702904 depth/1341848038.702904.png +1341848038.734794 rgb/1341848038.734794.png 1341848038.734810 depth/1341848038.734810.png +1341848038.770741 rgb/1341848038.770741.png 1341848038.770771 depth/1341848038.770771.png +1341848038.802800 rgb/1341848038.802800.png 1341848038.802827 depth/1341848038.802827.png +1341848038.838770 rgb/1341848038.838770.png 1341848038.838789 depth/1341848038.838789.png +1341848038.871141 rgb/1341848038.871141.png 1341848038.871181 depth/1341848038.871181.png +1341848038.902781 rgb/1341848038.902781.png 1341848038.903335 depth/1341848038.903335.png +1341848038.938767 rgb/1341848038.938767.png 1341848038.938797 depth/1341848038.938797.png +1341848038.970765 rgb/1341848038.970765.png 1341848038.970800 depth/1341848038.970800.png +1341848039.002634 rgb/1341848039.002634.png 1341848039.002655 depth/1341848039.002655.png +1341848039.038895 rgb/1341848039.038895.png 1341848039.038923 depth/1341848039.038923.png +1341848039.070805 rgb/1341848039.070805.png 1341848039.070823 depth/1341848039.070823.png +1341848039.106775 rgb/1341848039.106775.png 1341848039.106791 depth/1341848039.106791.png +1341848039.138656 rgb/1341848039.138656.png 1341848039.138659 depth/1341848039.138659.png +1341848039.170737 rgb/1341848039.170737.png 1341848039.170769 depth/1341848039.170769.png +1341848039.206814 rgb/1341848039.206814.png 1341848039.206838 depth/1341848039.206838.png +1341848039.238881 rgb/1341848039.238881.png 1341848039.239191 depth/1341848039.239191.png +1341848039.270959 rgb/1341848039.270959.png 1341848039.270979 depth/1341848039.270979.png +1341848039.306747 rgb/1341848039.306747.png 1341848039.306767 depth/1341848039.306767.png +1341848039.338889 rgb/1341848039.338889.png 1341848039.338904 depth/1341848039.338904.png +1341848039.374766 rgb/1341848039.374766.png 1341848039.375554 depth/1341848039.375554.png +1341848039.406886 rgb/1341848039.406886.png 1341848039.407826 depth/1341848039.407826.png +1341848039.438853 rgb/1341848039.438853.png 1341848039.438869 depth/1341848039.438869.png +1341848039.474867 rgb/1341848039.474867.png 1341848039.474885 depth/1341848039.474885.png +1341848039.507121 rgb/1341848039.507121.png 1341848039.508068 depth/1341848039.508068.png +1341848039.538659 rgb/1341848039.538659.png 1341848039.538673 depth/1341848039.538673.png +1341848039.574890 rgb/1341848039.574890.png 1341848039.574934 depth/1341848039.574934.png +1341848039.606721 rgb/1341848039.606721.png 1341848039.606737 depth/1341848039.606737.png +1341848039.642714 rgb/1341848039.642714.png 1341848039.642732 depth/1341848039.642732.png +1341848039.674760 rgb/1341848039.674760.png 1341848039.674771 depth/1341848039.674771.png +1341848039.707168 rgb/1341848039.707168.png 1341848039.707178 depth/1341848039.707178.png +1341848039.742862 rgb/1341848039.742862.png 1341848039.743701 depth/1341848039.743701.png +1341848039.775334 rgb/1341848039.775334.png 1341848039.775351 depth/1341848039.775351.png +1341848039.806875 rgb/1341848039.806875.png 1341848039.807101 depth/1341848039.807101.png +1341848039.843282 rgb/1341848039.843282.png 1341848039.843291 depth/1341848039.843291.png +1341848039.881803 rgb/1341848039.881803.png 1341848039.881841 depth/1341848039.881841.png +1341848039.943367 rgb/1341848039.943367.png 1341848039.943397 depth/1341848039.943397.png +1341848039.974815 rgb/1341848039.974815.png 1341848039.974838 depth/1341848039.974838.png +1341848040.010707 rgb/1341848040.010707.png 1341848040.010730 depth/1341848040.010730.png +1341848040.042768 rgb/1341848040.042768.png 1341848040.042790 depth/1341848040.042790.png +1341848040.078716 rgb/1341848040.078716.png 1341848040.078739 depth/1341848040.078739.png +1341848040.110819 rgb/1341848040.110819.png 1341848040.110865 depth/1341848040.110865.png +1341848040.142744 rgb/1341848040.142744.png 1341848040.142781 depth/1341848040.142781.png +1341848040.178810 rgb/1341848040.178810.png 1341848040.178825 depth/1341848040.178825.png +1341848040.211029 rgb/1341848040.211029.png 1341848040.211044 depth/1341848040.211044.png +1341848040.242681 rgb/1341848040.242681.png 1341848040.242703 depth/1341848040.242703.png +1341848040.278950 rgb/1341848040.278950.png 1341848040.278972 depth/1341848040.278972.png +1341848040.310719 rgb/1341848040.310719.png 1341848040.310730 depth/1341848040.310730.png +1341848040.346920 rgb/1341848040.346920.png 1341848040.346941 depth/1341848040.346941.png +1341848040.378809 rgb/1341848040.378809.png 1341848040.378824 depth/1341848040.378824.png +1341848040.410884 rgb/1341848040.410884.png 1341848040.410915 depth/1341848040.410915.png +1341848040.446720 rgb/1341848040.446720.png 1341848040.446754 depth/1341848040.446754.png +1341848040.478680 rgb/1341848040.478680.png 1341848040.478753 depth/1341848040.478753.png +1341848040.517796 rgb/1341848040.517796.png 1341848040.510881 depth/1341848040.510881.png +1341848040.578879 rgb/1341848040.578879.png 1341848040.578922 depth/1341848040.578922.png +1341848040.614917 rgb/1341848040.614917.png 1341848040.614969 depth/1341848040.614969.png +1341848040.646758 rgb/1341848040.646758.png 1341848040.646773 depth/1341848040.646773.png +1341848040.679034 rgb/1341848040.679034.png 1341848040.679046 depth/1341848040.679046.png +1341848040.714653 rgb/1341848040.714653.png 1341848040.714664 depth/1341848040.714664.png +1341848040.746821 rgb/1341848040.746821.png 1341848040.746831 depth/1341848040.746831.png +1341848040.778774 rgb/1341848040.778774.png 1341848040.778786 depth/1341848040.778786.png +1341848040.814675 rgb/1341848040.814675.png 1341848040.814687 depth/1341848040.814687.png +1341848040.846908 rgb/1341848040.846908.png 1341848040.846924 depth/1341848040.846924.png +1341848040.882827 rgb/1341848040.882827.png 1341848040.883358 depth/1341848040.883358.png +1341848040.914699 rgb/1341848040.914699.png 1341848040.914798 depth/1341848040.914798.png +1341848040.946862 rgb/1341848040.946862.png 1341848040.946870 depth/1341848040.946870.png +1341848040.984484 rgb/1341848040.984484.png 1341848040.985270 depth/1341848040.985270.png +1341848041.022638 rgb/1341848041.022638.png 1341848041.023937 depth/1341848041.023937.png +1341848041.058859 rgb/1341848041.058859.png 1341848041.058889 depth/1341848041.058889.png +1341848041.094347 rgb/1341848041.094347.png 1341848041.095717 depth/1341848041.095717.png +1341848041.122188 rgb/1341848041.122188.png 1341848041.122200 depth/1341848041.122200.png +1341848041.189954 rgb/1341848041.189954.png 1341848041.189991 depth/1341848041.189991.png +1341848041.250726 rgb/1341848041.250726.png 1341848041.250741 depth/1341848041.250741.png +1341848041.283054 rgb/1341848041.283054.png 1341848041.284122 depth/1341848041.284122.png +1341848041.319290 rgb/1341848041.319290.png 1341848041.320300 depth/1341848041.320300.png +1341848041.355465 rgb/1341848041.355465.png 1341848041.356564 depth/1341848041.356564.png +1341848041.384901 rgb/1341848041.384901.png 1341848041.385925 depth/1341848041.385925.png +1341848041.418768 rgb/1341848041.418768.png 1341848041.418779 depth/1341848041.418779.png +1341848041.450845 rgb/1341848041.450845.png 1341848041.451522 depth/1341848041.451522.png +1341848041.482801 rgb/1341848041.482801.png 1341848041.483609 depth/1341848041.483609.png +1341848041.518788 rgb/1341848041.518788.png 1341848041.519116 depth/1341848041.519116.png +1341848041.550730 rgb/1341848041.550730.png 1341848041.551098 depth/1341848041.551098.png +1341848041.586805 rgb/1341848041.586805.png 1341848041.586822 depth/1341848041.586822.png +1341848041.618743 rgb/1341848041.618743.png 1341848041.618759 depth/1341848041.618759.png +1341848041.650957 rgb/1341848041.650957.png 1341848041.650973 depth/1341848041.650973.png +1341848041.686781 rgb/1341848041.686781.png 1341848041.686793 depth/1341848041.686793.png +1341848041.718789 rgb/1341848041.718789.png 1341848041.718845 depth/1341848041.718845.png +1341848041.750776 rgb/1341848041.750776.png 1341848041.750796 depth/1341848041.750796.png +1341848041.786711 rgb/1341848041.786711.png 1341848041.786723 depth/1341848041.786723.png +1341848041.818704 rgb/1341848041.818704.png 1341848041.818714 depth/1341848041.818714.png +1341848041.854747 rgb/1341848041.854747.png 1341848041.854755 depth/1341848041.854755.png +1341848041.886710 rgb/1341848041.886710.png 1341848041.886728 depth/1341848041.886728.png +1341848041.918718 rgb/1341848041.918718.png 1341848041.918730 depth/1341848041.918730.png +1341848041.994975 rgb/1341848041.994975.png 1341848041.986734 depth/1341848041.986734.png +1341848042.018871 rgb/1341848042.018871.png 1341848042.019582 depth/1341848042.019582.png +1341848042.054627 rgb/1341848042.054627.png 1341848042.054650 depth/1341848042.054650.png +1341848042.089498 rgb/1341848042.089498.png 1341848042.089516 depth/1341848042.089516.png +1341848042.122881 rgb/1341848042.122881.png 1341848042.122905 depth/1341848042.122905.png +1341848042.154788 rgb/1341848042.154788.png 1341848042.154807 depth/1341848042.154807.png +1341848042.186714 rgb/1341848042.186714.png 1341848042.186794 depth/1341848042.186794.png +1341848042.222883 rgb/1341848042.222883.png 1341848042.222915 depth/1341848042.222915.png +1341848042.254762 rgb/1341848042.254762.png 1341848042.254771 depth/1341848042.254771.png +1341848042.290694 rgb/1341848042.290694.png 1341848042.290712 depth/1341848042.290712.png +1341848042.322759 rgb/1341848042.322759.png 1341848042.322792 depth/1341848042.322792.png +1341848042.354987 rgb/1341848042.354987.png 1341848042.355022 depth/1341848042.355022.png +1341848042.390711 rgb/1341848042.390711.png 1341848042.390726 depth/1341848042.390726.png +1341848042.429737 rgb/1341848042.429737.png 1341848042.429783 depth/1341848042.429783.png +1341848042.490921 rgb/1341848042.490921.png 1341848042.490969 depth/1341848042.490969.png +1341848042.522713 rgb/1341848042.522713.png 1341848042.522727 depth/1341848042.522727.png +1341848042.558691 rgb/1341848042.558691.png 1341848042.558699 depth/1341848042.558699.png +1341848042.590841 rgb/1341848042.590841.png 1341848042.590860 depth/1341848042.590860.png +1341848042.622730 rgb/1341848042.622730.png 1341848042.622787 depth/1341848042.622787.png +1341848042.658741 rgb/1341848042.658741.png 1341848042.658766 depth/1341848042.658766.png +1341848042.697779 rgb/1341848042.697779.png 1341848042.697819 depth/1341848042.697819.png +1341848042.729778 rgb/1341848042.729778.png 1341848042.729807 depth/1341848042.729807.png +1341848042.761637 rgb/1341848042.761637.png 1341848042.761653 depth/1341848042.761653.png +1341848042.797954 rgb/1341848042.797954.png 1341848042.797965 depth/1341848042.797965.png +1341848042.829708 rgb/1341848042.829708.png 1341848042.829769 depth/1341848042.829769.png +1341848042.861726 rgb/1341848042.861726.png 1341848042.861744 depth/1341848042.861744.png +1341848042.897767 rgb/1341848042.897767.png 1341848042.897784 depth/1341848042.897784.png +1341848042.929860 rgb/1341848042.929860.png 1341848042.929876 depth/1341848042.929876.png +1341848042.965708 rgb/1341848042.965708.png 1341848042.965723 depth/1341848042.965723.png +1341848042.997994 rgb/1341848042.997994.png 1341848042.998639 depth/1341848042.998639.png +1341848043.030335 rgb/1341848043.030335.png 1341848043.030388 depth/1341848043.030388.png +1341848043.065737 rgb/1341848043.065737.png 1341848043.065763 depth/1341848043.065763.png +1341848043.097862 rgb/1341848043.097862.png 1341848043.097882 depth/1341848043.097882.png +1341848043.133955 rgb/1341848043.133955.png 1341848043.133981 depth/1341848043.133981.png +1341848043.165792 rgb/1341848043.165792.png 1341848043.165803 depth/1341848043.165803.png +1341848043.201879 rgb/1341848043.201879.png 1341848043.201911 depth/1341848043.201911.png +1341848043.233861 rgb/1341848043.233861.png 1341848043.233874 depth/1341848043.233874.png +1341848043.265717 rgb/1341848043.265717.png 1341848043.265835 depth/1341848043.265835.png +1341848043.301798 rgb/1341848043.301798.png 1341848043.301842 depth/1341848043.301842.png +1341848043.334034 rgb/1341848043.334034.png 1341848043.334065 depth/1341848043.334065.png +1341848043.369819 rgb/1341848043.369819.png 1341848043.369863 depth/1341848043.369863.png +1341848043.401743 rgb/1341848043.401743.png 1341848043.401757 depth/1341848043.401757.png +1341848043.433949 rgb/1341848043.433949.png 1341848043.433974 depth/1341848043.433974.png +1341848043.469625 rgb/1341848043.469625.png 1341848043.469655 depth/1341848043.469655.png +1341848043.501696 rgb/1341848043.501696.png 1341848043.501719 depth/1341848043.501719.png +1341848043.537825 rgb/1341848043.537825.png 1341848043.537840 depth/1341848043.537840.png +1341848043.569664 rgb/1341848043.569664.png 1341848043.569696 depth/1341848043.569696.png +1341848043.601838 rgb/1341848043.601838.png 1341848043.601863 depth/1341848043.601863.png +1341848043.637798 rgb/1341848043.637798.png 1341848043.637825 depth/1341848043.637825.png +1341848043.670144 rgb/1341848043.670144.png 1341848043.670837 depth/1341848043.670837.png +1341848043.701979 rgb/1341848043.701979.png 1341848043.701997 depth/1341848043.701997.png +1341848043.737757 rgb/1341848043.737757.png 1341848043.738719 depth/1341848043.738719.png +1341848043.769828 rgb/1341848043.769828.png 1341848043.769854 depth/1341848043.769854.png +1341848043.805817 rgb/1341848043.805817.png 1341848043.805831 depth/1341848043.805831.png +1341848043.837855 rgb/1341848043.837855.png 1341848043.837882 depth/1341848043.837882.png +1341848043.869697 rgb/1341848043.869697.png 1341848043.870385 depth/1341848043.870385.png +1341848043.905731 rgb/1341848043.905731.png 1341848043.905743 depth/1341848043.905743.png +1341848043.938034 rgb/1341848043.938034.png 1341848043.938044 depth/1341848043.938044.png +1341848043.969826 rgb/1341848043.969826.png 1341848043.969839 depth/1341848043.969839.png +1341848044.005919 rgb/1341848044.005919.png 1341848044.005940 depth/1341848044.005940.png +1341848044.037703 rgb/1341848044.037703.png 1341848044.037722 depth/1341848044.037722.png +1341848044.073762 rgb/1341848044.073762.png 1341848044.073825 depth/1341848044.073825.png +1341848044.105804 rgb/1341848044.105804.png 1341848044.105831 depth/1341848044.105831.png +1341848044.137722 rgb/1341848044.137722.png 1341848044.137734 depth/1341848044.137734.png +1341848044.173825 rgb/1341848044.173825.png 1341848044.173851 depth/1341848044.173851.png +1341848044.205750 rgb/1341848044.205750.png 1341848044.205765 depth/1341848044.205765.png +1341848044.237767 rgb/1341848044.237767.png 1341848044.237808 depth/1341848044.237808.png +1341848044.273822 rgb/1341848044.273822.png 1341848044.273852 depth/1341848044.273852.png +1341848044.305742 rgb/1341848044.305742.png 1341848044.305751 depth/1341848044.305751.png +1341848044.337838 rgb/1341848044.337838.png 1341848044.338467 depth/1341848044.338467.png +1341848044.373688 rgb/1341848044.373688.png 1341848044.373771 depth/1341848044.373771.png +1341848044.405874 rgb/1341848044.405874.png 1341848044.406389 depth/1341848044.406389.png +1341848044.441696 rgb/1341848044.441696.png 1341848044.441804 depth/1341848044.441804.png +1341848044.473716 rgb/1341848044.473716.png 1341848044.473726 depth/1341848044.473726.png +1341848044.505687 rgb/1341848044.505687.png 1341848044.505703 depth/1341848044.505703.png +1341848044.541856 rgb/1341848044.541856.png 1341848044.541889 depth/1341848044.541889.png +1341848044.573760 rgb/1341848044.573760.png 1341848044.573776 depth/1341848044.573776.png +1341848044.605829 rgb/1341848044.605829.png 1341848044.605851 depth/1341848044.605851.png +1341848044.641741 rgb/1341848044.641741.png 1341848044.641753 depth/1341848044.641753.png +1341848044.705966 rgb/1341848044.705966.png 1341848044.706034 depth/1341848044.706034.png +1341848044.771011 rgb/1341848044.771011.png 1341848044.771614 depth/1341848044.771614.png +1341848044.802833 rgb/1341848044.802833.png 1341848044.803289 depth/1341848044.803289.png +1341848044.834852 rgb/1341848044.834852.png 1341848044.834869 depth/1341848044.834869.png +1341848044.870686 rgb/1341848044.870686.png 1341848044.870710 depth/1341848044.870710.png +1341848044.902692 rgb/1341848044.902692.png 1341848044.902865 depth/1341848044.902865.png +1341848044.970797 rgb/1341848044.970797.png 1341848044.970831 depth/1341848044.970831.png +1341848045.002641 rgb/1341848045.002641.png 1341848045.002657 depth/1341848045.002657.png +1341848045.038733 rgb/1341848045.038733.png 1341848045.038769 depth/1341848045.038769.png +1341848045.070849 rgb/1341848045.070849.png 1341848045.071339 depth/1341848045.071339.png +1341848045.102831 rgb/1341848045.102831.png 1341848045.102854 depth/1341848045.102854.png +1341848045.138762 rgb/1341848045.138762.png 1341848045.139311 depth/1341848045.139311.png +1341848045.170759 rgb/1341848045.170759.png 1341848045.170788 depth/1341848045.170788.png +1341848045.202698 rgb/1341848045.202698.png 1341848045.202711 depth/1341848045.202711.png +1341848045.238872 rgb/1341848045.238872.png 1341848045.238927 depth/1341848045.238927.png +1341848045.270833 rgb/1341848045.270833.png 1341848045.270857 depth/1341848045.270857.png +1341848045.306816 rgb/1341848045.306816.png 1341848045.306863 depth/1341848045.306863.png +1341848045.338698 rgb/1341848045.338698.png 1341848045.338809 depth/1341848045.338809.png +1341848045.370799 rgb/1341848045.370799.png 1341848045.370820 depth/1341848045.370820.png +1341848045.406703 rgb/1341848045.406703.png 1341848045.406744 depth/1341848045.406744.png +1341848045.438695 rgb/1341848045.438695.png 1341848045.438734 depth/1341848045.438734.png +1341848045.474692 rgb/1341848045.474692.png 1341848045.474832 depth/1341848045.474832.png +1341848045.538886 rgb/1341848045.538886.png 1341848045.538904 depth/1341848045.538904.png +1341848045.606920 rgb/1341848045.606920.png 1341848045.607002 depth/1341848045.607002.png +1341848045.645890 rgb/1341848045.645890.png 1341848045.645941 depth/1341848045.645941.png +1341848045.706968 rgb/1341848045.706968.png 1341848045.707020 depth/1341848045.707020.png +1341848045.743092 rgb/1341848045.743092.png 1341848045.743136 depth/1341848045.743136.png +1341848045.774776 rgb/1341848045.774776.png 1341848045.774792 depth/1341848045.774792.png +1341848045.807609 rgb/1341848045.807609.png 1341848045.807673 depth/1341848045.807673.png +1341848045.842865 rgb/1341848045.842865.png 1341848045.842900 depth/1341848045.842900.png +1341848045.874777 rgb/1341848045.874777.png 1341848045.875086 depth/1341848045.875086.png +1341848045.906765 rgb/1341848045.906765.png 1341848045.906846 depth/1341848045.906846.png +1341848045.942758 rgb/1341848045.942758.png 1341848045.942880 depth/1341848045.942880.png +1341848045.974768 rgb/1341848045.974768.png 1341848045.974792 depth/1341848045.974792.png +1341848046.010763 rgb/1341848046.010763.png 1341848046.010772 depth/1341848046.010772.png +1341848046.042828 rgb/1341848046.042828.png 1341848046.042856 depth/1341848046.042856.png +1341848046.074722 rgb/1341848046.074722.png 1341848046.074759 depth/1341848046.074759.png +1341848046.110817 rgb/1341848046.110817.png 1341848046.111023 depth/1341848046.111023.png +1341848046.142773 rgb/1341848046.142773.png 1341848046.142790 depth/1341848046.142790.png +1341848046.181848 rgb/1341848046.181848.png 1341848046.182775 depth/1341848046.182775.png +1341848046.219718 rgb/1341848046.219718.png 1341848046.219760 depth/1341848046.219760.png +1341848046.249730 rgb/1341848046.249730.png 1341848046.249758 depth/1341848046.249758.png +1341848046.283599 rgb/1341848046.283599.png 1341848046.284157 depth/1341848046.284157.png +1341848046.317731 rgb/1341848046.317731.png 1341848046.317760 depth/1341848046.317760.png +1341848046.349732 rgb/1341848046.349732.png 1341848046.349752 depth/1341848046.349752.png +1341848046.382309 rgb/1341848046.382309.png 1341848046.382801 depth/1341848046.382801.png +1341848046.417763 rgb/1341848046.417763.png 1341848046.417780 depth/1341848046.417780.png +1341848046.449782 rgb/1341848046.449782.png 1341848046.449814 depth/1341848046.449814.png +1341848046.485848 rgb/1341848046.485848.png 1341848046.485866 depth/1341848046.485866.png +1341848046.517760 rgb/1341848046.517760.png 1341848046.517776 depth/1341848046.517776.png +1341848046.549658 rgb/1341848046.549658.png 1341848046.549677 depth/1341848046.549677.png +1341848046.586076 rgb/1341848046.586076.png 1341848046.586113 depth/1341848046.586113.png +1341848046.617769 rgb/1341848046.617769.png 1341848046.617799 depth/1341848046.617799.png +1341848046.653748 rgb/1341848046.653748.png 1341848046.653760 depth/1341848046.653760.png +1341848046.714925 rgb/1341848046.714925.png 1341848046.715121 depth/1341848046.715121.png +1341848046.746888 rgb/1341848046.746888.png 1341848046.746904 depth/1341848046.746904.png +1341848046.778736 rgb/1341848046.778736.png 1341848046.778755 depth/1341848046.778755.png +1341848046.814747 rgb/1341848046.814747.png 1341848046.814769 depth/1341848046.814769.png +1341848046.846853 rgb/1341848046.846853.png 1341848046.846875 depth/1341848046.846875.png +1341848046.878793 rgb/1341848046.878793.png 1341848046.878814 depth/1341848046.878814.png +1341848046.915079 rgb/1341848046.915079.png 1341848046.915688 depth/1341848046.915688.png +1341848046.946882 rgb/1341848046.946882.png 1341848046.947809 depth/1341848046.947809.png +1341848046.982780 rgb/1341848046.982780.png 1341848046.983538 depth/1341848046.983538.png +1341848047.015086 rgb/1341848047.015086.png 1341848047.015187 depth/1341848047.015187.png +1341848047.047884 rgb/1341848047.047884.png 1341848047.047899 depth/1341848047.047899.png +1341848047.089866 rgb/1341848047.089866.png 1341848047.090622 depth/1341848047.090622.png +1341848047.147565 rgb/1341848047.147565.png 1341848047.148403 depth/1341848047.148403.png +1341848047.214887 rgb/1341848047.214887.png 1341848047.214908 depth/1341848047.214908.png +1341848047.250668 rgb/1341848047.250668.png 1341848047.250958 depth/1341848047.250958.png +1341848047.282779 rgb/1341848047.282779.png 1341848047.283384 depth/1341848047.283384.png +1341848047.314815 rgb/1341848047.314815.png 1341848047.314838 depth/1341848047.314838.png +1341848047.350637 rgb/1341848047.350637.png 1341848047.350663 depth/1341848047.350663.png +1341848047.383038 rgb/1341848047.383038.png 1341848047.383072 depth/1341848047.383072.png +1341848047.414781 rgb/1341848047.414781.png 1341848047.414794 depth/1341848047.414794.png +1341848047.450847 rgb/1341848047.450847.png 1341848047.450870 depth/1341848047.450870.png +1341848047.482648 rgb/1341848047.482648.png 1341848047.482683 depth/1341848047.482683.png +1341848047.518733 rgb/1341848047.518733.png 1341848047.518985 depth/1341848047.518985.png +1341848047.550836 rgb/1341848047.550836.png 1341848047.551401 depth/1341848047.551401.png +1341848047.582955 rgb/1341848047.582955.png 1341848047.582975 depth/1341848047.582975.png +1341848047.618981 rgb/1341848047.618981.png 1341848047.619010 depth/1341848047.619010.png +1341848047.650752 rgb/1341848047.650752.png 1341848047.650786 depth/1341848047.650786.png +1341848047.689728 rgb/1341848047.689728.png 1341848047.686710 depth/1341848047.686710.png +1341848047.750845 rgb/1341848047.750845.png 1341848047.750865 depth/1341848047.750865.png +1341848047.786695 rgb/1341848047.786695.png 1341848047.786706 depth/1341848047.786706.png +1341848047.818804 rgb/1341848047.818804.png 1341848047.818832 depth/1341848047.818832.png +1341848047.850811 rgb/1341848047.850811.png 1341848047.850844 depth/1341848047.850844.png +1341848047.886853 rgb/1341848047.886853.png 1341848047.886871 depth/1341848047.886871.png +1341848047.918858 rgb/1341848047.918858.png 1341848047.918881 depth/1341848047.918881.png +1341848047.954723 rgb/1341848047.954723.png 1341848047.954736 depth/1341848047.954736.png +1341848047.986771 rgb/1341848047.986771.png 1341848047.986794 depth/1341848047.986794.png +1341848048.018897 rgb/1341848048.018897.png 1341848048.019427 depth/1341848048.019427.png +1341848048.054937 rgb/1341848048.054937.png 1341848048.054958 depth/1341848048.054958.png +1341848048.086776 rgb/1341848048.086776.png 1341848048.086796 depth/1341848048.086796.png +1341848048.118790 rgb/1341848048.118790.png 1341848048.119190 depth/1341848048.119190.png +1341848048.154692 rgb/1341848048.154692.png 1341848048.154706 depth/1341848048.154706.png +1341848048.186720 rgb/1341848048.186720.png 1341848048.186737 depth/1341848048.186737.png +1341848048.222966 rgb/1341848048.222966.png 1341848048.222998 depth/1341848048.222998.png +1341848048.254953 rgb/1341848048.254953.png 1341848048.254981 depth/1341848048.254981.png +1341848048.286640 rgb/1341848048.286640.png 1341848048.286675 depth/1341848048.286675.png +1341848048.322843 rgb/1341848048.322843.png 1341848048.322868 depth/1341848048.322868.png +1341848048.354699 rgb/1341848048.354699.png 1341848048.354767 depth/1341848048.354767.png +1341848048.386709 rgb/1341848048.386709.png 1341848048.387170 depth/1341848048.387170.png +1341848048.422649 rgb/1341848048.422649.png 1341848048.422664 depth/1341848048.422664.png +1341848048.454923 rgb/1341848048.454923.png 1341848048.454947 depth/1341848048.454947.png +1341848048.490668 rgb/1341848048.490668.png 1341848048.490748 depth/1341848048.490748.png +1341848048.522793 rgb/1341848048.522793.png 1341848048.522819 depth/1341848048.522819.png +1341848048.554990 rgb/1341848048.554990.png 1341848048.555714 depth/1341848048.555714.png +1341848048.590630 rgb/1341848048.590630.png 1341848048.590665 depth/1341848048.590665.png +1341848048.622652 rgb/1341848048.622652.png 1341848048.622669 depth/1341848048.622669.png +1341848048.658741 rgb/1341848048.658741.png 1341848048.658771 depth/1341848048.658771.png +1341848048.690791 rgb/1341848048.690791.png 1341848048.690804 depth/1341848048.690804.png +1341848048.722708 rgb/1341848048.722708.png 1341848048.722725 depth/1341848048.722725.png +1341848048.758833 rgb/1341848048.758833.png 1341848048.758865 depth/1341848048.758865.png +1341848048.791156 rgb/1341848048.791156.png 1341848048.791827 depth/1341848048.791827.png +1341848048.822736 rgb/1341848048.822736.png 1341848048.822751 depth/1341848048.822751.png +1341848048.858661 rgb/1341848048.858661.png 1341848048.858682 depth/1341848048.858682.png +1341848048.891041 rgb/1341848048.891041.png 1341848048.891115 depth/1341848048.891115.png +1341848048.926768 rgb/1341848048.926768.png 1341848048.926806 depth/1341848048.926806.png +1341848048.958953 rgb/1341848048.958953.png 1341848048.958976 depth/1341848048.958976.png +1341848048.990810 rgb/1341848048.990810.png 1341848048.990852 depth/1341848048.990852.png +1341848049.026707 rgb/1341848049.026707.png 1341848049.026726 depth/1341848049.026726.png +1341848049.058792 rgb/1341848049.058792.png 1341848049.058854 depth/1341848049.058854.png +1341848049.090709 rgb/1341848049.090709.png 1341848049.090734 depth/1341848049.090734.png +1341848049.126753 rgb/1341848049.126753.png 1341848049.126771 depth/1341848049.126771.png +1341848049.158854 rgb/1341848049.158854.png 1341848049.158868 depth/1341848049.158868.png +1341848049.194708 rgb/1341848049.194708.png 1341848049.194728 depth/1341848049.194728.png +1341848049.226742 rgb/1341848049.226742.png 1341848049.226785 depth/1341848049.226785.png +1341848049.258792 rgb/1341848049.258792.png 1341848049.258839 depth/1341848049.258839.png +1341848049.294747 rgb/1341848049.294747.png 1341848049.294771 depth/1341848049.294771.png +1341848049.326837 rgb/1341848049.326837.png 1341848049.326876 depth/1341848049.326876.png +1341848049.358802 rgb/1341848049.358802.png 1341848049.358834 depth/1341848049.358834.png +1341848049.394779 rgb/1341848049.394779.png 1341848049.394804 depth/1341848049.394804.png +1341848049.426763 rgb/1341848049.426763.png 1341848049.427229 depth/1341848049.427229.png +1341848049.462746 rgb/1341848049.462746.png 1341848049.462781 depth/1341848049.462781.png +1341848049.494728 rgb/1341848049.494728.png 1341848049.494750 depth/1341848049.494750.png +1341848049.526803 rgb/1341848049.526803.png 1341848049.526823 depth/1341848049.526823.png +1341848049.562799 rgb/1341848049.562799.png 1341848049.562822 depth/1341848049.562822.png +1341848049.594759 rgb/1341848049.594759.png 1341848049.594778 depth/1341848049.594778.png +1341848049.626829 rgb/1341848049.626829.png 1341848049.626847 depth/1341848049.626847.png +1341848049.662690 rgb/1341848049.662690.png 1341848049.662727 depth/1341848049.662727.png +1341848049.695064 rgb/1341848049.695064.png 1341848049.695078 depth/1341848049.695078.png +1341848049.730793 rgb/1341848049.730793.png 1341848049.730887 depth/1341848049.730887.png +1341848049.762702 rgb/1341848049.762702.png 1341848049.763163 depth/1341848049.763163.png +1341848049.794722 rgb/1341848049.794722.png 1341848049.794771 depth/1341848049.794771.png +1341848049.830816 rgb/1341848049.830816.png 1341848049.830836 depth/1341848049.830836.png +1341848049.869834 rgb/1341848049.869834.png 1341848049.862754 depth/1341848049.862754.png +1341848049.930835 rgb/1341848049.930835.png 1341848049.930867 depth/1341848049.930867.png +1341848049.963022 rgb/1341848049.963022.png 1341848049.963083 depth/1341848049.963083.png +1341848049.998757 rgb/1341848049.998757.png 1341848049.998810 depth/1341848049.998810.png +1341848050.030786 rgb/1341848050.030786.png 1341848050.030833 depth/1341848050.030833.png +1341848050.062661 rgb/1341848050.062661.png 1341848050.062676 depth/1341848050.062676.png +1341848050.098678 rgb/1341848050.098678.png 1341848050.098702 depth/1341848050.098702.png +1341848050.130710 rgb/1341848050.130710.png 1341848050.130726 depth/1341848050.130726.png +1341848050.166738 rgb/1341848050.166738.png 1341848050.167181 depth/1341848050.167181.png +1341848050.198726 rgb/1341848050.198726.png 1341848050.198752 depth/1341848050.198752.png +1341848050.230806 rgb/1341848050.230806.png 1341848050.230862 depth/1341848050.230862.png +1341848050.266732 rgb/1341848050.266732.png 1341848050.266756 depth/1341848050.266756.png +1341848050.298842 rgb/1341848050.298842.png 1341848050.298860 depth/1341848050.298860.png +1341848050.330688 rgb/1341848050.330688.png 1341848050.330736 depth/1341848050.330736.png +1341848050.366746 rgb/1341848050.366746.png 1341848050.366800 depth/1341848050.366800.png +1341848050.398693 rgb/1341848050.398693.png 1341848050.398776 depth/1341848050.398776.png +1341848050.434780 rgb/1341848050.434780.png 1341848050.434797 depth/1341848050.434797.png +1341848050.466655 rgb/1341848050.466655.png 1341848050.466671 depth/1341848050.466671.png +1341848050.498791 rgb/1341848050.498791.png 1341848050.499214 depth/1341848050.499214.png +1341848050.534849 rgb/1341848050.534849.png 1341848050.534897 depth/1341848050.534897.png +1341848050.566840 rgb/1341848050.566840.png 1341848050.566851 depth/1341848050.566851.png +1341848050.598790 rgb/1341848050.598790.png 1341848050.598800 depth/1341848050.598800.png +1341848050.634752 rgb/1341848050.634752.png 1341848050.634764 depth/1341848050.634764.png +1341848050.666816 rgb/1341848050.666816.png 1341848050.666834 depth/1341848050.666834.png +1341848050.702846 rgb/1341848050.702846.png 1341848050.702859 depth/1341848050.702859.png +1341848050.734789 rgb/1341848050.734789.png 1341848050.734804 depth/1341848050.734804.png +1341848050.766882 rgb/1341848050.766882.png 1341848050.766912 depth/1341848050.766912.png +1341848050.802875 rgb/1341848050.802875.png 1341848050.802891 depth/1341848050.802891.png +1341848050.834769 rgb/1341848050.834769.png 1341848050.834812 depth/1341848050.834812.png +1341848050.870719 rgb/1341848050.870719.png 1341848050.870939 depth/1341848050.870939.png +1341848050.902725 rgb/1341848050.902725.png 1341848050.902807 depth/1341848050.902807.png +1341848050.934794 rgb/1341848050.934794.png 1341848050.934824 depth/1341848050.934824.png +1341848050.970852 rgb/1341848050.970852.png 1341848050.970880 depth/1341848050.970880.png +1341848051.002763 rgb/1341848051.002763.png 1341848051.002816 depth/1341848051.002816.png +1341848051.035007 rgb/1341848051.035007.png 1341848051.035029 depth/1341848051.035029.png +1341848051.070784 rgb/1341848051.070784.png 1341848051.070827 depth/1341848051.070827.png +1341848051.102734 rgb/1341848051.102734.png 1341848051.102758 depth/1341848051.102758.png +1341848051.138713 rgb/1341848051.138713.png 1341848051.138744 depth/1341848051.138744.png +1341848051.170672 rgb/1341848051.170672.png 1341848051.170688 depth/1341848051.170688.png +1341848051.238747 rgb/1341848051.238747.png 1341848051.238791 depth/1341848051.238791.png +1341848051.270842 rgb/1341848051.270842.png 1341848051.270880 depth/1341848051.270880.png +1341848051.302718 rgb/1341848051.302718.png 1341848051.302805 depth/1341848051.302805.png +1341848051.338668 rgb/1341848051.338668.png 1341848051.338751 depth/1341848051.338751.png +1341848051.370895 rgb/1341848051.370895.png 1341848051.370907 depth/1341848051.370907.png +1341848051.406688 rgb/1341848051.406688.png 1341848051.406741 depth/1341848051.406741.png +1341848051.440006 rgb/1341848051.440006.png 1341848051.440034 depth/1341848051.440034.png +1341848051.470890 rgb/1341848051.470890.png 1341848051.470921 depth/1341848051.470921.png +1341848051.506718 rgb/1341848051.506718.png 1341848051.506733 depth/1341848051.506733.png +1341848051.538932 rgb/1341848051.538932.png 1341848051.538947 depth/1341848051.538947.png +1341848051.570738 rgb/1341848051.570738.png 1341848051.570784 depth/1341848051.570784.png +1341848051.606760 rgb/1341848051.606760.png 1341848051.606826 depth/1341848051.606826.png +1341848051.638863 rgb/1341848051.638863.png 1341848051.638893 depth/1341848051.638893.png +1341848051.674718 rgb/1341848051.674718.png 1341848051.674731 depth/1341848051.674731.png +1341848051.706714 rgb/1341848051.706714.png 1341848051.706731 depth/1341848051.706731.png +1341848051.738793 rgb/1341848051.738793.png 1341848051.738822 depth/1341848051.738822.png +1341848051.774823 rgb/1341848051.774823.png 1341848051.774838 depth/1341848051.774838.png +1341848051.806694 rgb/1341848051.806694.png 1341848051.806721 depth/1341848051.806721.png +1341848051.838757 rgb/1341848051.838757.png 1341848051.838774 depth/1341848051.838774.png +1341848051.874951 rgb/1341848051.874951.png 1341848051.875000 depth/1341848051.875000.png +1341848051.906707 rgb/1341848051.906707.png 1341848051.907209 depth/1341848051.907209.png +1341848051.942680 rgb/1341848051.942680.png 1341848051.942718 depth/1341848051.942718.png +1341848051.974762 rgb/1341848051.974762.png 1341848051.974829 depth/1341848051.974829.png +1341848052.006755 rgb/1341848052.006755.png 1341848052.006768 depth/1341848052.006768.png +1341848052.042751 rgb/1341848052.042751.png 1341848052.042793 depth/1341848052.042793.png +1341848052.074871 rgb/1341848052.074871.png 1341848052.074895 depth/1341848052.074895.png +1341848052.143014 rgb/1341848052.143014.png 1341848052.143046 depth/1341848052.143046.png +1341848052.178064 rgb/1341848052.178064.png 1341848052.179162 depth/1341848052.179162.png +1341848052.211397 rgb/1341848052.211397.png 1341848052.211672 depth/1341848052.211672.png +1341848052.242872 rgb/1341848052.242872.png 1341848052.243754 depth/1341848052.243754.png +1341848052.311125 rgb/1341848052.311125.png 1341848052.312593 depth/1341848052.312593.png +1341848052.342876 rgb/1341848052.342876.png 1341848052.342908 depth/1341848052.342908.png +1341848052.379476 rgb/1341848052.379476.png 1341848052.379633 depth/1341848052.379633.png +1341848052.412309 rgb/1341848052.412309.png 1341848052.413797 depth/1341848052.413797.png +1341848052.444722 rgb/1341848052.444722.png 1341848052.446183 depth/1341848052.446183.png +1341848052.481496 rgb/1341848052.481496.png 1341848052.481647 depth/1341848052.481647.png +1341848052.543277 rgb/1341848052.543277.png 1341848052.544440 depth/1341848052.544440.png +1341848052.579155 rgb/1341848052.579155.png 1341848052.579179 depth/1341848052.579179.png +1341848052.617750 rgb/1341848052.617750.png 1341848052.617779 depth/1341848052.617779.png +1341848052.678720 rgb/1341848052.678720.png 1341848052.678766 depth/1341848052.678766.png +1341848052.710822 rgb/1341848052.710822.png 1341848052.711174 depth/1341848052.711174.png +1341848052.746833 rgb/1341848052.746833.png 1341848052.746908 depth/1341848052.746908.png +1341848052.778710 rgb/1341848052.778710.png 1341848052.778723 depth/1341848052.778723.png +1341848052.810890 rgb/1341848052.810890.png 1341848052.810907 depth/1341848052.810907.png +1341848052.846856 rgb/1341848052.846856.png 1341848052.846871 depth/1341848052.846871.png +1341848052.878813 rgb/1341848052.878813.png 1341848052.878844 depth/1341848052.878844.png +1341848052.914694 rgb/1341848052.914694.png 1341848052.914725 depth/1341848052.914725.png +1341848052.946675 rgb/1341848052.946675.png 1341848052.946716 depth/1341848052.946716.png +1341848052.978684 rgb/1341848052.978684.png 1341848052.978840 depth/1341848052.978840.png +1341848053.014784 rgb/1341848053.014784.png 1341848053.014807 depth/1341848053.014807.png +1341848053.046693 rgb/1341848053.046693.png 1341848053.046724 depth/1341848053.046724.png +1341848053.082651 rgb/1341848053.082651.png 1341848053.082679 depth/1341848053.082679.png +1341848053.114846 rgb/1341848053.114846.png 1341848053.114860 depth/1341848053.114860.png +1341848053.146985 rgb/1341848053.146985.png 1341848053.148476 depth/1341848053.148476.png +1341848053.183210 rgb/1341848053.183210.png 1341848053.184337 depth/1341848053.184337.png +1341848053.214816 rgb/1341848053.214816.png 1341848053.214830 depth/1341848053.214830.png +1341848053.247961 rgb/1341848053.247961.png 1341848053.247980 depth/1341848053.247980.png +1341848053.289822 rgb/1341848053.289822.png 1341848053.292717 depth/1341848053.292717.png +1341848053.321709 rgb/1341848053.321709.png 1341848053.321732 depth/1341848053.321732.png +1341848053.353831 rgb/1341848053.353831.png 1341848053.356259 depth/1341848053.356259.png +1341848053.386096 rgb/1341848053.386096.png 1341848053.386732 depth/1341848053.386732.png +1341848053.421775 rgb/1341848053.421775.png 1341848053.421802 depth/1341848053.421802.png +1341848053.453749 rgb/1341848053.453749.png 1341848053.453759 depth/1341848053.453759.png +1341848053.485736 rgb/1341848053.485736.png 1341848053.485752 depth/1341848053.485752.png +1341848053.521747 rgb/1341848053.521747.png 1341848053.521768 depth/1341848053.521768.png +1341848053.553915 rgb/1341848053.553915.png 1341848053.553936 depth/1341848053.553936.png +1341848053.589737 rgb/1341848053.589737.png 1341848053.589767 depth/1341848053.589767.png +1341848053.621911 rgb/1341848053.621911.png 1341848053.621933 depth/1341848053.621933.png +1341848053.653792 rgb/1341848053.653792.png 1341848053.653842 depth/1341848053.653842.png +1341848053.689724 rgb/1341848053.689724.png 1341848053.689746 depth/1341848053.689746.png +1341848053.721697 rgb/1341848053.721697.png 1341848053.721712 depth/1341848053.721712.png +1341848053.758007 rgb/1341848053.758007.png 1341848053.758077 depth/1341848053.758077.png +1341848053.789882 rgb/1341848053.789882.png 1341848053.789892 depth/1341848053.789892.png +1341848053.821625 rgb/1341848053.821625.png 1341848053.821676 depth/1341848053.821676.png +1341848053.857784 rgb/1341848053.857784.png 1341848053.857801 depth/1341848053.857801.png +1341848053.889790 rgb/1341848053.889790.png 1341848053.889811 depth/1341848053.889811.png +1341848053.951067 rgb/1341848053.951067.png 1341848053.951082 depth/1341848053.951082.png +1341848053.986823 rgb/1341848053.986823.png 1341848053.986846 depth/1341848053.986846.png +1341848054.051032 rgb/1341848054.051032.png 1341848054.051048 depth/1341848054.051048.png +1341848054.086777 rgb/1341848054.086777.png 1341848054.086792 depth/1341848054.086792.png +1341848054.118853 rgb/1341848054.118853.png 1341848054.118865 depth/1341848054.118865.png +1341848054.155032 rgb/1341848054.155032.png 1341848054.155064 depth/1341848054.155064.png +1341848054.186687 rgb/1341848054.186687.png 1341848054.186722 depth/1341848054.186722.png +1341848054.219030 rgb/1341848054.219030.png 1341848054.219042 depth/1341848054.219042.png +1341848054.254827 rgb/1341848054.254827.png 1341848054.254842 depth/1341848054.254842.png +1341848054.286801 rgb/1341848054.286801.png 1341848054.286818 depth/1341848054.286818.png +1341848054.322895 rgb/1341848054.322895.png 1341848054.323319 depth/1341848054.323319.png +1341848054.354790 rgb/1341848054.354790.png 1341848054.354803 depth/1341848054.354803.png +1341848054.387103 rgb/1341848054.387103.png 1341848054.387855 depth/1341848054.387855.png +1341848054.422878 rgb/1341848054.422878.png 1341848054.423322 depth/1341848054.423322.png +1341848054.454739 rgb/1341848054.454739.png 1341848054.454751 depth/1341848054.454751.png +1341848054.486883 rgb/1341848054.486883.png 1341848054.486948 depth/1341848054.486948.png +1341848054.522689 rgb/1341848054.522689.png 1341848054.522735 depth/1341848054.522735.png +1341848054.554861 rgb/1341848054.554861.png 1341848054.554880 depth/1341848054.554880.png +1341848054.590790 rgb/1341848054.590790.png 1341848054.590808 depth/1341848054.590808.png +1341848054.622694 rgb/1341848054.622694.png 1341848054.622722 depth/1341848054.622722.png +1341848054.656449 rgb/1341848054.656449.png 1341848054.656477 depth/1341848054.656477.png +1341848054.691021 rgb/1341848054.691021.png 1341848054.691042 depth/1341848054.691042.png +1341848054.722739 rgb/1341848054.722739.png 1341848054.723258 depth/1341848054.723258.png +1341848054.754741 rgb/1341848054.754741.png 1341848054.755241 depth/1341848054.755241.png +1341848054.790887 rgb/1341848054.790887.png 1341848054.791409 depth/1341848054.791409.png +1341848054.822877 rgb/1341848054.822877.png 1341848054.823565 depth/1341848054.823565.png +1341848054.858903 rgb/1341848054.858903.png 1341848054.859037 depth/1341848054.859037.png +1341848054.890895 rgb/1341848054.890895.png 1341848054.890944 depth/1341848054.890944.png +1341848054.922754 rgb/1341848054.922754.png 1341848054.923230 depth/1341848054.923230.png +1341848054.958727 rgb/1341848054.958727.png 1341848054.958755 depth/1341848054.958755.png +1341848054.991052 rgb/1341848054.991052.png 1341848054.991085 depth/1341848054.991085.png +1341848055.023048 rgb/1341848055.023048.png 1341848055.023079 depth/1341848055.023079.png +1341848055.058739 rgb/1341848055.058739.png 1341848055.058760 depth/1341848055.058760.png +1341848055.090735 rgb/1341848055.090735.png 1341848055.090811 depth/1341848055.090811.png +1341848055.126977 rgb/1341848055.126977.png 1341848055.127018 depth/1341848055.127018.png +1341848055.159212 rgb/1341848055.159212.png 1341848055.159232 depth/1341848055.159232.png +1341848055.190986 rgb/1341848055.190986.png 1341848055.191010 depth/1341848055.191010.png +1341848055.226768 rgb/1341848055.226768.png 1341848055.226790 depth/1341848055.226790.png +1341848055.258881 rgb/1341848055.258881.png 1341848055.259331 depth/1341848055.259331.png +1341848055.294725 rgb/1341848055.294725.png 1341848055.294747 depth/1341848055.294747.png +1341848055.326795 rgb/1341848055.326795.png 1341848055.326811 depth/1341848055.326811.png +1341848055.358938 rgb/1341848055.358938.png 1341848055.359026 depth/1341848055.359026.png +1341848055.394711 rgb/1341848055.394711.png 1341848055.394755 depth/1341848055.394755.png +1341848055.426823 rgb/1341848055.426823.png 1341848055.426846 depth/1341848055.426846.png +1341848055.458813 rgb/1341848055.458813.png 1341848055.458862 depth/1341848055.458862.png +1341848055.494734 rgb/1341848055.494734.png 1341848055.494780 depth/1341848055.494780.png +1341848055.526713 rgb/1341848055.526713.png 1341848055.526772 depth/1341848055.526772.png +1341848055.562613 rgb/1341848055.562613.png 1341848055.562659 depth/1341848055.562659.png +1341848055.594685 rgb/1341848055.594685.png 1341848055.594704 depth/1341848055.594704.png +1341848055.626675 rgb/1341848055.626675.png 1341848055.626690 depth/1341848055.626690.png +1341848055.662951 rgb/1341848055.662951.png 1341848055.662971 depth/1341848055.662971.png +1341848055.694797 rgb/1341848055.694797.png 1341848055.694815 depth/1341848055.694815.png +1341848055.726774 rgb/1341848055.726774.png 1341848055.726799 depth/1341848055.726799.png +1341848055.762799 rgb/1341848055.762799.png 1341848055.762858 depth/1341848055.762858.png +1341848055.794951 rgb/1341848055.794951.png 1341848055.795020 depth/1341848055.795020.png +1341848055.830810 rgb/1341848055.830810.png 1341848055.830827 depth/1341848055.830827.png +1341848055.862804 rgb/1341848055.862804.png 1341848055.862847 depth/1341848055.862847.png +1341848055.894792 rgb/1341848055.894792.png 1341848055.894806 depth/1341848055.894806.png +1341848055.930676 rgb/1341848055.930676.png 1341848055.930688 depth/1341848055.930688.png +1341848055.962765 rgb/1341848055.962765.png 1341848055.962807 depth/1341848055.962807.png +1341848055.994709 rgb/1341848055.994709.png 1341848055.994743 depth/1341848055.994743.png +1341848056.030693 rgb/1341848056.030693.png 1341848056.030743 depth/1341848056.030743.png +1341848056.062776 rgb/1341848056.062776.png 1341848056.062796 depth/1341848056.062796.png +1341848056.098792 rgb/1341848056.098792.png 1341848056.098811 depth/1341848056.098811.png +1341848056.130649 rgb/1341848056.130649.png 1341848056.130661 depth/1341848056.130661.png +1341848056.162731 rgb/1341848056.162731.png 1341848056.162741 depth/1341848056.162741.png +1341848056.198744 rgb/1341848056.198744.png 1341848056.198760 depth/1341848056.198760.png +1341848056.230727 rgb/1341848056.230727.png 1341848056.230784 depth/1341848056.230784.png +1341848056.263915 rgb/1341848056.263915.png 1341848056.263942 depth/1341848056.263942.png +1341848056.298771 rgb/1341848056.298771.png 1341848056.298811 depth/1341848056.298811.png +1341848056.330676 rgb/1341848056.330676.png 1341848056.330687 depth/1341848056.330687.png +1341848056.366737 rgb/1341848056.366737.png 1341848056.366752 depth/1341848056.366752.png +1341848056.398744 rgb/1341848056.398744.png 1341848056.399274 depth/1341848056.399274.png +1341848056.430750 rgb/1341848056.430750.png 1341848056.430803 depth/1341848056.430803.png +1341848056.466830 rgb/1341848056.466830.png 1341848056.466874 depth/1341848056.466874.png +1341848056.498895 rgb/1341848056.498895.png 1341848056.498914 depth/1341848056.498914.png +1341848056.534778 rgb/1341848056.534778.png 1341848056.534856 depth/1341848056.534856.png +1341848056.566729 rgb/1341848056.566729.png 1341848056.566742 depth/1341848056.566742.png +1341848056.598948 rgb/1341848056.598948.png 1341848056.599048 depth/1341848056.599048.png +1341848056.634801 rgb/1341848056.634801.png 1341848056.635005 depth/1341848056.635005.png +1341848056.666759 rgb/1341848056.666759.png 1341848056.666800 depth/1341848056.666800.png +1341848056.698889 rgb/1341848056.698889.png 1341848056.698898 depth/1341848056.698898.png +1341848056.734784 rgb/1341848056.734784.png 1341848056.735297 depth/1341848056.735297.png +1341848056.766724 rgb/1341848056.766724.png 1341848056.766792 depth/1341848056.766792.png +1341848056.802861 rgb/1341848056.802861.png 1341848056.802899 depth/1341848056.802899.png +1341848056.834980 rgb/1341848056.834980.png 1341848056.835035 depth/1341848056.835035.png +1341848056.866661 rgb/1341848056.866661.png 1341848056.866671 depth/1341848056.866671.png +1341848056.902748 rgb/1341848056.902748.png 1341848056.902779 depth/1341848056.902779.png +1341848056.934715 rgb/1341848056.934715.png 1341848056.934953 depth/1341848056.934953.png +1341848056.966788 rgb/1341848056.966788.png 1341848056.966823 depth/1341848056.966823.png +1341848057.002703 rgb/1341848057.002703.png 1341848057.002763 depth/1341848057.002763.png +1341848057.034763 rgb/1341848057.034763.png 1341848057.035020 depth/1341848057.035020.png +1341848057.070964 rgb/1341848057.070964.png 1341848057.070988 depth/1341848057.070988.png +1341848057.102757 rgb/1341848057.102757.png 1341848057.102797 depth/1341848057.102797.png +1341848057.134714 rgb/1341848057.134714.png 1341848057.134974 depth/1341848057.134974.png +1341848057.170739 rgb/1341848057.170739.png 1341848057.170751 depth/1341848057.170751.png +1341848057.202641 rgb/1341848057.202641.png 1341848057.202667 depth/1341848057.202667.png +1341848057.234679 rgb/1341848057.234679.png 1341848057.234693 depth/1341848057.234693.png +1341848057.270814 rgb/1341848057.270814.png 1341848057.270823 depth/1341848057.270823.png +1341848057.302860 rgb/1341848057.302860.png 1341848057.302980 depth/1341848057.302980.png +1341848057.338756 rgb/1341848057.338756.png 1341848057.338780 depth/1341848057.338780.png +1341848057.370841 rgb/1341848057.370841.png 1341848057.370867 depth/1341848057.370867.png +1341848057.402722 rgb/1341848057.402722.png 1341848057.402756 depth/1341848057.402756.png +1341848057.438870 rgb/1341848057.438870.png 1341848057.438880 depth/1341848057.438880.png +1341848057.470699 rgb/1341848057.470699.png 1341848057.470718 depth/1341848057.470718.png +1341848057.506720 rgb/1341848057.506720.png 1341848057.506753 depth/1341848057.506753.png +1341848057.538788 rgb/1341848057.538788.png 1341848057.538804 depth/1341848057.538804.png +1341848057.571069 rgb/1341848057.571069.png 1341848057.571100 depth/1341848057.571100.png +1341848057.606668 rgb/1341848057.606668.png 1341848057.606677 depth/1341848057.606677.png +1341848057.638819 rgb/1341848057.638819.png 1341848057.638855 depth/1341848057.638855.png +1341848057.670943 rgb/1341848057.670943.png 1341848057.671015 depth/1341848057.671015.png +1341848057.706823 rgb/1341848057.706823.png 1341848057.706841 depth/1341848057.706841.png +1341848057.738890 rgb/1341848057.738890.png 1341848057.739645 depth/1341848057.739645.png +1341848057.774986 rgb/1341848057.774986.png 1341848057.775609 depth/1341848057.775609.png +1341848057.806842 rgb/1341848057.806842.png 1341848057.806912 depth/1341848057.806912.png +1341848057.838760 rgb/1341848057.838760.png 1341848057.838766 depth/1341848057.838766.png +1341848057.874817 rgb/1341848057.874817.png 1341848057.874847 depth/1341848057.874847.png +1341848057.906831 rgb/1341848057.906831.png 1341848057.906846 depth/1341848057.906846.png +1341848057.938847 rgb/1341848057.938847.png 1341848057.938888 depth/1341848057.938888.png +1341848057.975316 rgb/1341848057.975316.png 1341848057.975330 depth/1341848057.975330.png +1341848058.006833 rgb/1341848058.006833.png 1341848058.006850 depth/1341848058.006850.png +1341848058.042753 rgb/1341848058.042753.png 1341848058.042790 depth/1341848058.042790.png +1341848058.075970 rgb/1341848058.075970.png 1341848058.075985 depth/1341848058.075985.png +1341848058.106790 rgb/1341848058.106790.png 1341848058.106860 depth/1341848058.106860.png +1341848058.142699 rgb/1341848058.142699.png 1341848058.142719 depth/1341848058.142719.png +1341848058.174743 rgb/1341848058.174743.png 1341848058.174770 depth/1341848058.174770.png +1341848058.207081 rgb/1341848058.207081.png 1341848058.207102 depth/1341848058.207102.png +1341848058.242740 rgb/1341848058.242740.png 1341848058.242749 depth/1341848058.242749.png +1341848058.274694 rgb/1341848058.274694.png 1341848058.274839 depth/1341848058.274839.png +1341848058.310701 rgb/1341848058.310701.png 1341848058.310722 depth/1341848058.310722.png +1341848058.343169 rgb/1341848058.343169.png 1341848058.343218 depth/1341848058.343218.png +1341848058.374887 rgb/1341848058.374887.png 1341848058.374917 depth/1341848058.374917.png +1341848058.410669 rgb/1341848058.410669.png 1341848058.410676 depth/1341848058.410676.png +1341848058.442794 rgb/1341848058.442794.png 1341848058.442828 depth/1341848058.442828.png +1341848058.474732 rgb/1341848058.474732.png 1341848058.474753 depth/1341848058.474753.png +1341848058.542970 rgb/1341848058.542970.png 1341848058.542987 depth/1341848058.542987.png +1341848058.578948 rgb/1341848058.578948.png 1341848058.578964 depth/1341848058.578964.png +1341848058.610842 rgb/1341848058.610842.png 1341848058.610871 depth/1341848058.610871.png +1341848058.643060 rgb/1341848058.643060.png 1341848058.643076 depth/1341848058.643076.png +1341848058.678730 rgb/1341848058.678730.png 1341848058.678770 depth/1341848058.678770.png +1341848058.710728 rgb/1341848058.710728.png 1341848058.710766 depth/1341848058.710766.png +1341848058.746819 rgb/1341848058.746819.png 1341848058.746854 depth/1341848058.746854.png +1341848058.778710 rgb/1341848058.778710.png 1341848058.778785 depth/1341848058.778785.png +1341848058.810874 rgb/1341848058.810874.png 1341848058.811237 depth/1341848058.811237.png +1341848058.846829 rgb/1341848058.846829.png 1341848058.846867 depth/1341848058.846867.png +1341848058.879577 rgb/1341848058.879577.png 1341848058.880257 depth/1341848058.880257.png +1341848058.946807 rgb/1341848058.946807.png 1341848058.946831 depth/1341848058.946831.png +1341848058.978865 rgb/1341848058.978865.png 1341848058.978887 depth/1341848058.978887.png +1341848059.014660 rgb/1341848059.014660.png 1341848059.014688 depth/1341848059.014688.png +1341848059.046707 rgb/1341848059.046707.png 1341848059.046732 depth/1341848059.046732.png +1341848059.078771 rgb/1341848059.078771.png 1341848059.078837 depth/1341848059.078837.png +1341848059.114675 rgb/1341848059.114675.png 1341848059.114705 depth/1341848059.114705.png +1341848059.146706 rgb/1341848059.146706.png 1341848059.146722 depth/1341848059.146722.png +1341848059.178722 rgb/1341848059.178722.png 1341848059.178787 depth/1341848059.178787.png +1341848059.214738 rgb/1341848059.214738.png 1341848059.214758 depth/1341848059.214758.png +1341848059.246762 rgb/1341848059.246762.png 1341848059.246787 depth/1341848059.246787.png +1341848059.282693 rgb/1341848059.282693.png 1341848059.282764 depth/1341848059.282764.png +1341848059.314667 rgb/1341848059.314667.png 1341848059.314695 depth/1341848059.314695.png +1341848059.346758 rgb/1341848059.346758.png 1341848059.346817 depth/1341848059.346817.png +1341848059.382694 rgb/1341848059.382694.png 1341848059.382710 depth/1341848059.382710.png +1341848059.414736 rgb/1341848059.414736.png 1341848059.414763 depth/1341848059.414763.png +1341848059.446788 rgb/1341848059.446788.png 1341848059.446880 depth/1341848059.446880.png +1341848059.482693 rgb/1341848059.482693.png 1341848059.482709 depth/1341848059.482709.png +1341848059.514652 rgb/1341848059.514652.png 1341848059.514665 depth/1341848059.514665.png +1341848059.550754 rgb/1341848059.550754.png 1341848059.550789 depth/1341848059.550789.png +1341848059.582695 rgb/1341848059.582695.png 1341848059.582712 depth/1341848059.582712.png +1341848059.614734 rgb/1341848059.614734.png 1341848059.614760 depth/1341848059.614760.png +1341848059.650722 rgb/1341848059.650722.png 1341848059.650736 depth/1341848059.650736.png +1341848059.682731 rgb/1341848059.682731.png 1341848059.682765 depth/1341848059.682765.png +1341848059.718703 rgb/1341848059.718703.png 1341848059.718727 depth/1341848059.718727.png +1341848059.750904 rgb/1341848059.750904.png 1341848059.750937 depth/1341848059.750937.png +1341848059.782774 rgb/1341848059.782774.png 1341848059.782784 depth/1341848059.782784.png +1341848059.818759 rgb/1341848059.818759.png 1341848059.818786 depth/1341848059.818786.png +1341848059.850685 rgb/1341848059.850685.png 1341848059.850742 depth/1341848059.850742.png +1341848059.882730 rgb/1341848059.882730.png 1341848059.882739 depth/1341848059.882739.png +1341848059.918755 rgb/1341848059.918755.png 1341848059.918781 depth/1341848059.918781.png +1341848059.950805 rgb/1341848059.950805.png 1341848059.951468 depth/1341848059.951468.png +1341848059.986776 rgb/1341848059.986776.png 1341848059.986870 depth/1341848059.986870.png +1341848060.018660 rgb/1341848060.018660.png 1341848060.018699 depth/1341848060.018699.png +1341848060.050701 rgb/1341848060.050701.png 1341848060.050726 depth/1341848060.050726.png +1341848060.086783 rgb/1341848060.086783.png 1341848060.086804 depth/1341848060.086804.png +1341848060.118813 rgb/1341848060.118813.png 1341848060.118826 depth/1341848060.118826.png +1341848060.150800 rgb/1341848060.150800.png 1341848060.152187 depth/1341848060.152187.png +1341848060.186872 rgb/1341848060.186872.png 1341848060.186902 depth/1341848060.186902.png +1341848060.218851 rgb/1341848060.218851.png 1341848060.218926 depth/1341848060.218926.png +1341848060.254799 rgb/1341848060.254799.png 1341848060.255357 depth/1341848060.255357.png +1341848060.287466 rgb/1341848060.287466.png 1341848060.287482 depth/1341848060.287482.png +1341848060.318914 rgb/1341848060.318914.png 1341848060.318945 depth/1341848060.318945.png +1341848060.354641 rgb/1341848060.354641.png 1341848060.354688 depth/1341848060.354688.png +1341848060.387254 rgb/1341848060.387254.png 1341848060.387291 depth/1341848060.387291.png +1341848060.418639 rgb/1341848060.418639.png 1341848060.418684 depth/1341848060.418684.png +1341848060.454775 rgb/1341848060.454775.png 1341848060.454794 depth/1341848060.454794.png +1341848060.486697 rgb/1341848060.486697.png 1341848060.486771 depth/1341848060.486771.png +1341848060.522925 rgb/1341848060.522925.png 1341848060.523008 depth/1341848060.523008.png +1341848060.554710 rgb/1341848060.554710.png 1341848060.554724 depth/1341848060.554724.png +1341848060.586692 rgb/1341848060.586692.png 1341848060.586706 depth/1341848060.586706.png +1341848060.622697 rgb/1341848060.622697.png 1341848060.622721 depth/1341848060.622721.png +1341848060.656087 rgb/1341848060.656087.png 1341848060.656113 depth/1341848060.656113.png +1341848060.687258 rgb/1341848060.687258.png 1341848060.687324 depth/1341848060.687324.png +1341848060.723165 rgb/1341848060.723165.png 1341848060.724561 depth/1341848060.724561.png +1341848060.757863 rgb/1341848060.757863.png 1341848060.757889 depth/1341848060.757889.png +1341848060.790920 rgb/1341848060.790920.png 1341848060.791034 depth/1341848060.791034.png +1341848060.823967 rgb/1341848060.823967.png 1341848060.829094 depth/1341848060.829094.png +1341848060.862432 rgb/1341848060.862432.png 1341848060.863663 depth/1341848060.863663.png +1341848060.923126 rgb/1341848060.923126.png 1341848060.926419 depth/1341848060.926419.png +1341848060.960845 rgb/1341848060.960845.png 1341848060.961890 depth/1341848060.961890.png +1341848060.996857 rgb/1341848060.996857.png 1341848060.997593 depth/1341848060.997593.png +1341848061.030587 rgb/1341848061.030587.png 1341848061.031332 depth/1341848061.031332.png +1341848061.062246 rgb/1341848061.062246.png 1341848061.062516 depth/1341848061.062516.png +1341848061.100583 rgb/1341848061.100583.png 1341848061.101130 depth/1341848061.101130.png +1341848061.129837 rgb/1341848061.129837.png 1341848061.129853 depth/1341848061.129853.png +1341848061.197947 rgb/1341848061.197947.png 1341848061.197987 depth/1341848061.197987.png +1341848061.259408 rgb/1341848061.259408.png 1341848061.259586 depth/1341848061.259586.png +1341848061.290885 rgb/1341848061.290885.png 1341848061.290998 depth/1341848061.290998.png +1341848061.326612 rgb/1341848061.326612.png 1341848061.326647 depth/1341848061.326647.png +1341848061.358867 rgb/1341848061.358867.png 1341848061.358908 depth/1341848061.358908.png +1341848061.390845 rgb/1341848061.390845.png 1341848061.391495 depth/1341848061.391495.png +1341848061.426913 rgb/1341848061.426913.png 1341848061.426942 depth/1341848061.426942.png +1341848061.458837 rgb/1341848061.458837.png 1341848061.458854 depth/1341848061.458854.png +1341848061.494657 rgb/1341848061.494657.png 1341848061.495433 depth/1341848061.495433.png +1341848061.526736 rgb/1341848061.526736.png 1341848061.526886 depth/1341848061.526886.png +1341848061.558821 rgb/1341848061.558821.png 1341848061.558836 depth/1341848061.558836.png +1341848061.594750 rgb/1341848061.594750.png 1341848061.594776 depth/1341848061.594776.png +1341848061.626731 rgb/1341848061.626731.png 1341848061.626753 depth/1341848061.626753.png +1341848061.658831 rgb/1341848061.658831.png 1341848061.658845 depth/1341848061.658845.png +1341848061.694894 rgb/1341848061.694894.png 1341848061.694932 depth/1341848061.694932.png +1341848061.726726 rgb/1341848061.726726.png 1341848061.726750 depth/1341848061.726750.png +1341848061.762815 rgb/1341848061.762815.png 1341848061.762840 depth/1341848061.762840.png +1341848061.794816 rgb/1341848061.794816.png 1341848061.795285 depth/1341848061.795285.png +1341848061.826740 rgb/1341848061.826740.png 1341848061.826754 depth/1341848061.826754.png +1341848061.862883 rgb/1341848061.862883.png 1341848061.862902 depth/1341848061.862902.png +1341848061.894834 rgb/1341848061.894834.png 1341848061.894887 depth/1341848061.894887.png +1341848061.930667 rgb/1341848061.930667.png 1341848061.930754 depth/1341848061.930754.png +1341848061.962828 rgb/1341848061.962828.png 1341848061.962857 depth/1341848061.962857.png +1341848061.997188 rgb/1341848061.997188.png 1341848061.997201 depth/1341848061.997201.png +1341848062.030704 rgb/1341848062.030704.png 1341848062.030723 depth/1341848062.030723.png +1341848062.063265 rgb/1341848062.063265.png 1341848062.064058 depth/1341848062.064058.png +1341848062.094872 rgb/1341848062.094872.png 1341848062.094893 depth/1341848062.094893.png +1341848062.130773 rgb/1341848062.130773.png 1341848062.130816 depth/1341848062.130816.png +1341848062.163385 rgb/1341848062.163385.png 1341848062.163399 depth/1341848062.163399.png +1341848062.198718 rgb/1341848062.198718.png 1341848062.198960 depth/1341848062.198960.png +1341848062.230750 rgb/1341848062.230750.png 1341848062.230763 depth/1341848062.230763.png +1341848062.262814 rgb/1341848062.262814.png 1341848062.262858 depth/1341848062.262858.png +1341848062.299276 rgb/1341848062.299276.png 1341848062.299285 depth/1341848062.299285.png +1341848062.330839 rgb/1341848062.330839.png 1341848062.330968 depth/1341848062.330968.png +1341848062.362763 rgb/1341848062.362763.png 1341848062.362798 depth/1341848062.362798.png +1341848062.398825 rgb/1341848062.398825.png 1341848062.398836 depth/1341848062.398836.png +1341848062.430832 rgb/1341848062.430832.png 1341848062.430844 depth/1341848062.430844.png +1341848062.466855 rgb/1341848062.466855.png 1341848062.466879 depth/1341848062.466879.png +1341848062.498723 rgb/1341848062.498723.png 1341848062.498743 depth/1341848062.498743.png +1341848062.530743 rgb/1341848062.530743.png 1341848062.530759 depth/1341848062.530759.png +1341848062.566929 rgb/1341848062.566929.png 1341848062.566959 depth/1341848062.566959.png +1341848062.598817 rgb/1341848062.598817.png 1341848062.598829 depth/1341848062.598829.png +1341848062.630793 rgb/1341848062.630793.png 1341848062.630824 depth/1341848062.630824.png +1341848062.666740 rgb/1341848062.666740.png 1341848062.666771 depth/1341848062.666771.png +1341848062.698720 rgb/1341848062.698720.png 1341848062.698743 depth/1341848062.698743.png +1341848062.734924 rgb/1341848062.734924.png 1341848062.734939 depth/1341848062.734939.png +1341848062.766819 rgb/1341848062.766819.png 1341848062.766877 depth/1341848062.766877.png +1341848062.798717 rgb/1341848062.798717.png 1341848062.798764 depth/1341848062.798764.png +1341848062.834828 rgb/1341848062.834828.png 1341848062.834849 depth/1341848062.834849.png +1341848062.866781 rgb/1341848062.866781.png 1341848062.867238 depth/1341848062.867238.png +1341848062.899075 rgb/1341848062.899075.png 1341848062.899092 depth/1341848062.899092.png +1341848062.934962 rgb/1341848062.934962.png 1341848062.934977 depth/1341848062.934977.png +1341848062.966930 rgb/1341848062.966930.png 1341848062.966957 depth/1341848062.966957.png +1341848063.002905 rgb/1341848063.002905.png 1341848063.002915 depth/1341848063.002915.png +1341848063.034972 rgb/1341848063.034972.png 1341848063.035491 depth/1341848063.035491.png +1341848063.066737 rgb/1341848063.066737.png 1341848063.066749 depth/1341848063.066749.png +1341848063.102822 rgb/1341848063.102822.png 1341848063.102832 depth/1341848063.102832.png +1341848063.135045 rgb/1341848063.135045.png 1341848063.135160 depth/1341848063.135160.png +1341848063.170739 rgb/1341848063.170739.png 1341848063.170794 depth/1341848063.170794.png +1341848063.202662 rgb/1341848063.202662.png 1341848063.202765 depth/1341848063.202765.png +1341848063.234990 rgb/1341848063.234990.png 1341848063.235006 depth/1341848063.235006.png +1341848063.270800 rgb/1341848063.270800.png 1341848063.270816 depth/1341848063.270816.png +1341848063.302788 rgb/1341848063.302788.png 1341848063.302814 depth/1341848063.302814.png +1341848063.334854 rgb/1341848063.334854.png 1341848063.335470 depth/1341848063.335470.png +1341848063.370653 rgb/1341848063.370653.png 1341848063.370688 depth/1341848063.370688.png +1341848063.402698 rgb/1341848063.402698.png 1341848063.402728 depth/1341848063.402728.png +1341848063.439276 rgb/1341848063.439276.png 1341848063.439294 depth/1341848063.439294.png +1341848063.470742 rgb/1341848063.470742.png 1341848063.470764 depth/1341848063.470764.png +1341848063.502776 rgb/1341848063.502776.png 1341848063.502801 depth/1341848063.502801.png +1341848063.541802 rgb/1341848063.541802.png 1341848063.541821 depth/1341848063.541821.png +1341848063.577805 rgb/1341848063.577805.png 1341848063.577827 depth/1341848063.577827.png +1341848063.609732 rgb/1341848063.609732.png 1341848063.609780 depth/1341848063.609780.png +1341848063.643039 rgb/1341848063.643039.png 1341848063.643057 depth/1341848063.643057.png +1341848063.677955 rgb/1341848063.677955.png 1341848063.677981 depth/1341848063.677981.png +1341848063.709890 rgb/1341848063.709890.png 1341848063.709915 depth/1341848063.709915.png +1341848063.745768 rgb/1341848063.745768.png 1341848063.745783 depth/1341848063.745783.png +1341848063.777773 rgb/1341848063.777773.png 1341848063.777929 depth/1341848063.777929.png +1341848063.809840 rgb/1341848063.809840.png 1341848063.809857 depth/1341848063.809857.png +1341848063.845733 rgb/1341848063.845733.png 1341848063.845775 depth/1341848063.845775.png +1341848063.877902 rgb/1341848063.877902.png 1341848063.877913 depth/1341848063.877913.png +1341848063.913769 rgb/1341848063.913769.png 1341848063.913781 depth/1341848063.913781.png +1341848063.945802 rgb/1341848063.945802.png 1341848063.946407 depth/1341848063.946407.png +1341848063.977856 rgb/1341848063.977856.png 1341848063.977868 depth/1341848063.977868.png +1341848064.013951 rgb/1341848064.013951.png 1341848064.013963 depth/1341848064.013963.png +1341848064.045815 rgb/1341848064.045815.png 1341848064.045830 depth/1341848064.045830.png +1341848064.081699 rgb/1341848064.081699.png 1341848064.081716 depth/1341848064.081716.png +1341848064.113685 rgb/1341848064.113685.png 1341848064.113699 depth/1341848064.113699.png +1341848064.145823 rgb/1341848064.145823.png 1341848064.145896 depth/1341848064.145896.png +1341848064.181846 rgb/1341848064.181846.png 1341848064.181871 depth/1341848064.181871.png +1341848064.213863 rgb/1341848064.213863.png 1341848064.213916 depth/1341848064.213916.png +1341848064.249771 rgb/1341848064.249771.png 1341848064.249803 depth/1341848064.249803.png +1341848064.282977 rgb/1341848064.282977.png 1341848064.283921 depth/1341848064.283921.png +1341848064.313795 rgb/1341848064.313795.png 1341848064.313821 depth/1341848064.313821.png +1341848064.349790 rgb/1341848064.349790.png 1341848064.349800 depth/1341848064.349800.png +1341848064.382619 rgb/1341848064.382619.png 1341848064.382881 depth/1341848064.382881.png +1341848064.418063 rgb/1341848064.418063.png 1341848064.418076 depth/1341848064.418076.png +1341848064.449767 rgb/1341848064.449767.png 1341848064.449781 depth/1341848064.449781.png +1341848064.481773 rgb/1341848064.481773.png 1341848064.481794 depth/1341848064.481794.png +1341848064.518010 rgb/1341848064.518010.png 1341848064.518639 depth/1341848064.518639.png +1341848064.549704 rgb/1341848064.549704.png 1341848064.549726 depth/1341848064.549726.png +1341848064.581714 rgb/1341848064.581714.png 1341848064.581772 depth/1341848064.581772.png +1341848064.617693 rgb/1341848064.617693.png 1341848064.617728 depth/1341848064.617728.png +1341848064.649724 rgb/1341848064.649724.png 1341848064.649739 depth/1341848064.649739.png +1341848064.685821 rgb/1341848064.685821.png 1341848064.685871 depth/1341848064.685871.png +1341848064.749892 rgb/1341848064.749892.png 1341848064.749986 depth/1341848064.749986.png +1341848064.810737 rgb/1341848064.810737.png 1341848064.810771 depth/1341848064.810771.png +1341848064.842702 rgb/1341848064.842702.png 1341848064.842765 depth/1341848064.842765.png +1341848064.878850 rgb/1341848064.878850.png 1341848064.878871 depth/1341848064.878871.png +1341848064.910832 rgb/1341848064.910832.png 1341848064.910861 depth/1341848064.910861.png +1341848064.946850 rgb/1341848064.946850.png 1341848064.946870 depth/1341848064.946870.png +1341848064.978809 rgb/1341848064.978809.png 1341848064.978833 depth/1341848064.978833.png +1341848065.010770 rgb/1341848065.010770.png 1341848065.010849 depth/1341848065.010849.png +1341848065.046751 rgb/1341848065.046751.png 1341848065.046796 depth/1341848065.046796.png +1341848065.078713 rgb/1341848065.078713.png 1341848065.078740 depth/1341848065.078740.png +1341848065.110686 rgb/1341848065.110686.png 1341848065.110913 depth/1341848065.110913.png +1341848065.146689 rgb/1341848065.146689.png 1341848065.146705 depth/1341848065.146705.png +1341848065.178847 rgb/1341848065.178847.png 1341848065.178872 depth/1341848065.178872.png +1341848065.214760 rgb/1341848065.214760.png 1341848065.214817 depth/1341848065.214817.png +1341848065.246768 rgb/1341848065.246768.png 1341848065.246815 depth/1341848065.246815.png +1341848065.278735 rgb/1341848065.278735.png 1341848065.278785 depth/1341848065.278785.png +1341848065.314761 rgb/1341848065.314761.png 1341848065.314782 depth/1341848065.314782.png +1341848065.346776 rgb/1341848065.346776.png 1341848065.346874 depth/1341848065.346874.png +1341848065.382824 rgb/1341848065.382824.png 1341848065.382883 depth/1341848065.382883.png +1341848065.414914 rgb/1341848065.414914.png 1341848065.414947 depth/1341848065.414947.png +1341848065.446728 rgb/1341848065.446728.png 1341848065.447032 depth/1341848065.447032.png +1341848065.482830 rgb/1341848065.482830.png 1341848065.483011 depth/1341848065.483011.png +1341848065.514745 rgb/1341848065.514745.png 1341848065.515200 depth/1341848065.515200.png +1341848065.546916 rgb/1341848065.546916.png 1341848065.546929 depth/1341848065.546929.png +1341848065.582742 rgb/1341848065.582742.png 1341848065.582781 depth/1341848065.582781.png +1341848065.614763 rgb/1341848065.614763.png 1341848065.615224 depth/1341848065.615224.png +1341848065.682873 rgb/1341848065.682873.png 1341848065.682923 depth/1341848065.682923.png +1341848065.714808 rgb/1341848065.714808.png 1341848065.714841 depth/1341848065.714841.png +1341848065.750674 rgb/1341848065.750674.png 1341848065.750692 depth/1341848065.750692.png +1341848065.782722 rgb/1341848065.782722.png 1341848065.782781 depth/1341848065.782781.png +1341848065.814742 rgb/1341848065.814742.png 1341848065.814773 depth/1341848065.814773.png +1341848065.850746 rgb/1341848065.850746.png 1341848065.850775 depth/1341848065.850775.png +1341848065.918698 rgb/1341848065.918698.png 1341848065.918742 depth/1341848065.918742.png +1341848065.950762 rgb/1341848065.950762.png 1341848065.950803 depth/1341848065.950803.png +1341848065.982774 rgb/1341848065.982774.png 1341848065.982829 depth/1341848065.982829.png +1341848066.018773 rgb/1341848066.018773.png 1341848066.018836 depth/1341848066.018836.png +1341848066.050717 rgb/1341848066.050717.png 1341848066.050784 depth/1341848066.050784.png +1341848066.082818 rgb/1341848066.082818.png 1341848066.082851 depth/1341848066.082851.png +1341848066.118721 rgb/1341848066.118721.png 1341848066.118762 depth/1341848066.118762.png +1341848066.150964 rgb/1341848066.150964.png 1341848066.151663 depth/1341848066.151663.png +1341848066.186782 rgb/1341848066.186782.png 1341848066.186806 depth/1341848066.186806.png +1341848066.218688 rgb/1341848066.218688.png 1341848066.218701 depth/1341848066.218701.png +1341848066.250777 rgb/1341848066.250777.png 1341848066.250794 depth/1341848066.250794.png +1341848066.286736 rgb/1341848066.286736.png 1341848066.286752 depth/1341848066.286752.png +1341848066.318695 rgb/1341848066.318695.png 1341848066.318714 depth/1341848066.318714.png +1341848066.354797 rgb/1341848066.354797.png 1341848066.354854 depth/1341848066.354854.png +1341848066.386761 rgb/1341848066.386761.png 1341848066.386795 depth/1341848066.386795.png +1341848066.418820 rgb/1341848066.418820.png 1341848066.418853 depth/1341848066.418853.png +1341848066.454695 rgb/1341848066.454695.png 1341848066.454708 depth/1341848066.454708.png +1341848066.486874 rgb/1341848066.486874.png 1341848066.486902 depth/1341848066.486902.png +1341848066.522806 rgb/1341848066.522806.png 1341848066.523149 depth/1341848066.523149.png +1341848066.555107 rgb/1341848066.555107.png 1341848066.560526 depth/1341848066.560526.png +1341848066.623500 rgb/1341848066.623500.png 1341848066.624153 depth/1341848066.624153.png +1341848066.655239 rgb/1341848066.655239.png 1341848066.655262 depth/1341848066.655262.png +1341848066.697724 rgb/1341848066.697724.png 1341848066.698980 depth/1341848066.698980.png +1341848066.732527 rgb/1341848066.732527.png 1341848066.733333 depth/1341848066.733333.png +1341848066.764415 rgb/1341848066.764415.png 1341848066.765329 depth/1341848066.765329.png +1341848066.795253 rgb/1341848066.795253.png 1341848066.795567 depth/1341848066.795567.png +1341848066.833355 rgb/1341848066.833355.png 1341848066.834424 depth/1341848066.834424.png +1341848066.862103 rgb/1341848066.862103.png 1341848066.862114 depth/1341848066.862114.png +1341848066.905023 rgb/1341848066.905023.png 1341848066.905636 depth/1341848066.905636.png +1341848066.930221 rgb/1341848066.930221.png 1341848066.930239 depth/1341848066.930239.png +1341848066.997936 rgb/1341848066.997936.png 1341848066.998757 depth/1341848066.998757.png +1341848067.054702 rgb/1341848067.054702.png 1341848067.054719 depth/1341848067.054719.png +1341848067.090940 rgb/1341848067.090940.png 1341848067.090960 depth/1341848067.090960.png +1341848067.122963 rgb/1341848067.122963.png 1341848067.122977 depth/1341848067.122977.png +1341848067.158821 rgb/1341848067.158821.png 1341848067.158843 depth/1341848067.158843.png +1341848067.191143 rgb/1341848067.191143.png 1341848067.191172 depth/1341848067.191172.png +1341848067.222948 rgb/1341848067.222948.png 1341848067.223798 depth/1341848067.223798.png +1341848067.258733 rgb/1341848067.258733.png 1341848067.258827 depth/1341848067.258827.png +1341848067.322816 rgb/1341848067.322816.png 1341848067.322831 depth/1341848067.322831.png +1341848067.358674 rgb/1341848067.358674.png 1341848067.358740 depth/1341848067.358740.png +1341848067.390706 rgb/1341848067.390706.png 1341848067.390723 depth/1341848067.390723.png +1341848067.426869 rgb/1341848067.426869.png 1341848067.426896 depth/1341848067.426896.png +1341848067.458745 rgb/1341848067.458745.png 1341848067.458759 depth/1341848067.458759.png +1341848067.491527 rgb/1341848067.491527.png 1341848067.491567 depth/1341848067.491567.png +1341848067.526659 rgb/1341848067.526659.png 1341848067.526716 depth/1341848067.526716.png +1341848067.558770 rgb/1341848067.558770.png 1341848067.558783 depth/1341848067.558783.png +1341848067.594659 rgb/1341848067.594659.png 1341848067.594669 depth/1341848067.594669.png +1341848067.626656 rgb/1341848067.626656.png 1341848067.626667 depth/1341848067.626667.png +1341848067.658983 rgb/1341848067.658983.png 1341848067.659013 depth/1341848067.659013.png +1341848067.694893 rgb/1341848067.694893.png 1341848067.694912 depth/1341848067.694912.png +1341848067.726732 rgb/1341848067.726732.png 1341848067.727398 depth/1341848067.727398.png +1341848067.758667 rgb/1341848067.758667.png 1341848067.758683 depth/1341848067.758683.png +1341848067.794813 rgb/1341848067.794813.png 1341848067.794832 depth/1341848067.794832.png +1341848067.826795 rgb/1341848067.826795.png 1341848067.826810 depth/1341848067.826810.png +1341848067.862808 rgb/1341848067.862808.png 1341848067.862836 depth/1341848067.862836.png diff --git a/Examples/RGB-D/associations/fr3_str_tex_far.txt b/Examples/RGB-D/associations/fr3_str_tex_far.txt new file mode 100644 index 0000000000..ad3e5b7966 --- /dev/null +++ b/Examples/RGB-D/associations/fr3_str_tex_far.txt @@ -0,0 +1,907 @@ +1341839113.657637 rgb/1341839113.657637.png 1341839113.657663 depth/1341839113.657663.png +1341839113.693575 rgb/1341839113.693575.png 1341839113.693593 depth/1341839113.693593.png +1341839113.725606 rgb/1341839113.725606.png 1341839113.725630 depth/1341839113.725630.png +1341839113.793718 rgb/1341839113.793718.png 1341839113.793734 depth/1341839113.793734.png +1341839113.861553 rgb/1341839113.861553.png 1341839113.861564 depth/1341839113.861564.png +1341839113.894400 rgb/1341839113.894400.png 1341839113.894423 depth/1341839113.894423.png +1341839113.925550 rgb/1341839113.925550.png 1341839113.925567 depth/1341839113.925567.png +1341839113.961614 rgb/1341839113.961614.png 1341839113.961650 depth/1341839113.961650.png +1341839113.993616 rgb/1341839113.993616.png 1341839113.993637 depth/1341839113.993637.png +1341839114.025642 rgb/1341839114.025642.png 1341839114.025656 depth/1341839114.025656.png +1341839114.061534 rgb/1341839114.061534.png 1341839114.061547 depth/1341839114.061547.png +1341839114.093617 rgb/1341839114.093617.png 1341839114.093656 depth/1341839114.093656.png +1341839114.129556 rgb/1341839114.129556.png 1341839114.129568 depth/1341839114.129568.png +1341839114.161678 rgb/1341839114.161678.png 1341839114.161687 depth/1341839114.161687.png +1341839114.229673 rgb/1341839114.229673.png 1341839114.229696 depth/1341839114.229696.png +1341839114.261690 rgb/1341839114.261690.png 1341839114.261732 depth/1341839114.261732.png +1341839114.293564 rgb/1341839114.293564.png 1341839114.293581 depth/1341839114.293581.png +1341839114.329671 rgb/1341839114.329671.png 1341839114.329683 depth/1341839114.329683.png +1341839114.361622 rgb/1341839114.361622.png 1341839114.361642 depth/1341839114.361642.png +1341839114.397666 rgb/1341839114.397666.png 1341839114.397683 depth/1341839114.397683.png +1341839114.429583 rgb/1341839114.429583.png 1341839114.429612 depth/1341839114.429612.png +1341839114.461610 rgb/1341839114.461610.png 1341839114.461625 depth/1341839114.461625.png +1341839114.497561 rgb/1341839114.497561.png 1341839114.497571 depth/1341839114.497571.png +1341839114.529492 rgb/1341839114.529492.png 1341839114.529521 depth/1341839114.529521.png +1341839114.565482 rgb/1341839114.565482.png 1341839114.565492 depth/1341839114.565492.png +1341839114.597648 rgb/1341839114.597648.png 1341839114.597672 depth/1341839114.597672.png +1341839114.629596 rgb/1341839114.629596.png 1341839114.629605 depth/1341839114.629605.png +1341839114.665607 rgb/1341839114.665607.png 1341839114.665620 depth/1341839114.665620.png +1341839114.697721 rgb/1341839114.697721.png 1341839114.697742 depth/1341839114.697742.png +1341839114.730054 rgb/1341839114.730054.png 1341839114.730075 depth/1341839114.730075.png +1341839114.765560 rgb/1341839114.765560.png 1341839114.765588 depth/1341839114.765588.png +1341839114.797510 rgb/1341839114.797510.png 1341839114.797529 depth/1341839114.797529.png +1341839114.833570 rgb/1341839114.833570.png 1341839114.833611 depth/1341839114.833611.png +1341839114.865530 rgb/1341839114.865530.png 1341839114.865552 depth/1341839114.865552.png +1341839114.897742 rgb/1341839114.897742.png 1341839114.897759 depth/1341839114.897759.png +1341839114.933721 rgb/1341839114.933721.png 1341839114.933735 depth/1341839114.933735.png +1341839114.965565 rgb/1341839114.965565.png 1341839114.965577 depth/1341839114.965577.png +1341839114.997678 rgb/1341839114.997678.png 1341839114.997693 depth/1341839114.997693.png +1341839115.033675 rgb/1341839115.033675.png 1341839115.033696 depth/1341839115.033696.png +1341839115.065634 rgb/1341839115.065634.png 1341839115.065650 depth/1341839115.065650.png +1341839115.101577 rgb/1341839115.101577.png 1341839115.101593 depth/1341839115.101593.png +1341839115.133455 rgb/1341839115.133455.png 1341839115.133522 depth/1341839115.133522.png +1341839115.165699 rgb/1341839115.165699.png 1341839115.165734 depth/1341839115.165734.png +1341839115.201542 rgb/1341839115.201542.png 1341839115.201580 depth/1341839115.201580.png +1341839115.233600 rgb/1341839115.233600.png 1341839115.233615 depth/1341839115.233615.png +1341839115.265499 rgb/1341839115.265499.png 1341839115.265508 depth/1341839115.265508.png +1341839115.301699 rgb/1341839115.301699.png 1341839115.301713 depth/1341839115.301713.png +1341839115.333616 rgb/1341839115.333616.png 1341839115.333623 depth/1341839115.333623.png +1341839115.369483 rgb/1341839115.369483.png 1341839115.369499 depth/1341839115.369499.png +1341839115.401613 rgb/1341839115.401613.png 1341839115.401633 depth/1341839115.401633.png +1341839115.469819 rgb/1341839115.469819.png 1341839115.469842 depth/1341839115.469842.png +1341839115.533671 rgb/1341839115.533671.png 1341839115.533679 depth/1341839115.533679.png +1341839115.569633 rgb/1341839115.569633.png 1341839115.569790 depth/1341839115.569790.png +1341839115.601623 rgb/1341839115.601623.png 1341839115.601639 depth/1341839115.601639.png +1341839115.637954 rgb/1341839115.637954.png 1341839115.637973 depth/1341839115.637973.png +1341839115.669467 rgb/1341839115.669467.png 1341839115.669503 depth/1341839115.669503.png +1341839115.701635 rgb/1341839115.701635.png 1341839115.701664 depth/1341839115.701664.png +1341839115.737552 rgb/1341839115.737552.png 1341839115.737567 depth/1341839115.737567.png +1341839115.769579 rgb/1341839115.769579.png 1341839115.769589 depth/1341839115.769589.png +1341839115.805533 rgb/1341839115.805533.png 1341839115.805545 depth/1341839115.805545.png +1341839115.837641 rgb/1341839115.837641.png 1341839115.837655 depth/1341839115.837655.png +1341839115.869594 rgb/1341839115.869594.png 1341839115.869610 depth/1341839115.869610.png +1341839115.905464 rgb/1341839115.905464.png 1341839115.905477 depth/1341839115.905477.png +1341839115.937926 rgb/1341839115.937926.png 1341839115.937940 depth/1341839115.937940.png +1341839115.976772 rgb/1341839115.976772.png 1341839115.976803 depth/1341839115.976803.png +1341839116.037844 rgb/1341839116.037844.png 1341839116.037863 depth/1341839116.037863.png +1341839116.073614 rgb/1341839116.073614.png 1341839116.073625 depth/1341839116.073625.png +1341839116.105551 rgb/1341839116.105551.png 1341839116.105562 depth/1341839116.105562.png +1341839116.137629 rgb/1341839116.137629.png 1341839116.137643 depth/1341839116.137643.png +1341839116.173741 rgb/1341839116.173741.png 1341839116.173765 depth/1341839116.173765.png +1341839116.205705 rgb/1341839116.205705.png 1341839116.205729 depth/1341839116.205729.png +1341839116.237744 rgb/1341839116.237744.png 1341839116.237753 depth/1341839116.237753.png +1341839116.273644 rgb/1341839116.273644.png 1341839116.273652 depth/1341839116.273652.png +1341839116.305590 rgb/1341839116.305590.png 1341839116.305631 depth/1341839116.305631.png +1341839116.341693 rgb/1341839116.341693.png 1341839116.341705 depth/1341839116.341705.png +1341839116.374159 rgb/1341839116.374159.png 1341839116.374180 depth/1341839116.374180.png +1341839116.405626 rgb/1341839116.405626.png 1341839116.405654 depth/1341839116.405654.png +1341839116.441448 rgb/1341839116.441448.png 1341839116.441468 depth/1341839116.441468.png +1341839116.473792 rgb/1341839116.473792.png 1341839116.473807 depth/1341839116.473807.png +1341839116.505559 rgb/1341839116.505559.png 1341839116.505628 depth/1341839116.505628.png +1341839116.541530 rgb/1341839116.541530.png 1341839116.541549 depth/1341839116.541549.png +1341839116.573449 rgb/1341839116.573449.png 1341839116.573467 depth/1341839116.573467.png +1341839116.609629 rgb/1341839116.609629.png 1341839116.609652 depth/1341839116.609652.png +1341839116.642092 rgb/1341839116.642092.png 1341839116.642102 depth/1341839116.642102.png +1341839116.673494 rgb/1341839116.673494.png 1341839116.673509 depth/1341839116.673509.png +1341839116.709491 rgb/1341839116.709491.png 1341839116.709501 depth/1341839116.709501.png +1341839116.741798 rgb/1341839116.741798.png 1341839116.741832 depth/1341839116.741832.png +1341839116.777780 rgb/1341839116.777780.png 1341839116.777815 depth/1341839116.777815.png +1341839116.809493 rgb/1341839116.809493.png 1341839116.809672 depth/1341839116.809672.png +1341839116.841577 rgb/1341839116.841577.png 1341839116.841609 depth/1341839116.841609.png +1341839116.877541 rgb/1341839116.877541.png 1341839116.877569 depth/1341839116.877569.png +1341839116.909607 rgb/1341839116.909607.png 1341839116.909614 depth/1341839116.909614.png +1341839116.941574 rgb/1341839116.941574.png 1341839116.941962 depth/1341839116.941962.png +1341839116.977669 rgb/1341839116.977669.png 1341839116.977741 depth/1341839116.977741.png +1341839117.009692 rgb/1341839117.009692.png 1341839117.010335 depth/1341839117.010335.png +1341839117.045446 rgb/1341839117.045446.png 1341839117.045473 depth/1341839117.045473.png +1341839117.077581 rgb/1341839117.077581.png 1341839117.077610 depth/1341839117.077610.png +1341839117.109633 rgb/1341839117.109633.png 1341839117.109645 depth/1341839117.109645.png +1341839117.145451 rgb/1341839117.145451.png 1341839117.145488 depth/1341839117.145488.png +1341839117.177591 rgb/1341839117.177591.png 1341839117.177601 depth/1341839117.177601.png +1341839117.209585 rgb/1341839117.209585.png 1341839117.209615 depth/1341839117.209615.png +1341839117.245753 rgb/1341839117.245753.png 1341839117.245784 depth/1341839117.245784.png +1341839117.278976 rgb/1341839117.278976.png 1341839117.279032 depth/1341839117.279032.png +1341839117.313580 rgb/1341839117.313580.png 1341839117.313591 depth/1341839117.313591.png +1341839117.345623 rgb/1341839117.345623.png 1341839117.345648 depth/1341839117.345648.png +1341839117.377641 rgb/1341839117.377641.png 1341839117.378160 depth/1341839117.378160.png +1341839117.413568 rgb/1341839117.413568.png 1341839117.413600 depth/1341839117.413600.png +1341839117.445717 rgb/1341839117.445717.png 1341839117.445739 depth/1341839117.445739.png +1341839117.477601 rgb/1341839117.477601.png 1341839117.478035 depth/1341839117.478035.png +1341839117.513635 rgb/1341839117.513635.png 1341839117.513644 depth/1341839117.513644.png +1341839117.545603 rgb/1341839117.545603.png 1341839117.545628 depth/1341839117.545628.png +1341839117.581707 rgb/1341839117.581707.png 1341839117.581832 depth/1341839117.581832.png +1341839117.613653 rgb/1341839117.613653.png 1341839117.613672 depth/1341839117.613672.png +1341839117.645887 rgb/1341839117.645887.png 1341839117.646046 depth/1341839117.646046.png +1341839117.681569 rgb/1341839117.681569.png 1341839117.681589 depth/1341839117.681589.png +1341839117.713639 rgb/1341839117.713639.png 1341839117.713657 depth/1341839117.713657.png +1341839117.745712 rgb/1341839117.745712.png 1341839117.746254 depth/1341839117.746254.png +1341839117.781725 rgb/1341839117.781725.png 1341839117.781733 depth/1341839117.781733.png +1341839117.813499 rgb/1341839117.813499.png 1341839117.813509 depth/1341839117.813509.png +1341839117.849617 rgb/1341839117.849617.png 1341839117.849630 depth/1341839117.849630.png +1341839117.881610 rgb/1341839117.881610.png 1341839117.881622 depth/1341839117.881622.png +1341839117.913581 rgb/1341839117.913581.png 1341839117.913608 depth/1341839117.913608.png +1341839117.949521 rgb/1341839117.949521.png 1341839117.949533 depth/1341839117.949533.png +1341839117.981586 rgb/1341839117.981586.png 1341839117.981600 depth/1341839117.981600.png +1341839118.017504 rgb/1341839118.017504.png 1341839118.017560 depth/1341839118.017560.png +1341839118.049478 rgb/1341839118.049478.png 1341839118.049521 depth/1341839118.049521.png +1341839118.081566 rgb/1341839118.081566.png 1341839118.081579 depth/1341839118.081579.png +1341839118.117532 rgb/1341839118.117532.png 1341839118.117557 depth/1341839118.117557.png +1341839118.149476 rgb/1341839118.149476.png 1341839118.149510 depth/1341839118.149510.png +1341839118.182394 rgb/1341839118.182394.png 1341839118.182891 depth/1341839118.182891.png +1341839118.217697 rgb/1341839118.217697.png 1341839118.217718 depth/1341839118.217718.png +1341839118.249595 rgb/1341839118.249595.png 1341839118.249607 depth/1341839118.249607.png +1341839118.285581 rgb/1341839118.285581.png 1341839118.285635 depth/1341839118.285635.png +1341839118.317574 rgb/1341839118.317574.png 1341839118.318164 depth/1341839118.318164.png +1341839118.349685 rgb/1341839118.349685.png 1341839118.349699 depth/1341839118.349699.png +1341839118.385618 rgb/1341839118.385618.png 1341839118.385634 depth/1341839118.385634.png +1341839118.417611 rgb/1341839118.417611.png 1341839118.417702 depth/1341839118.417702.png +1341839118.449697 rgb/1341839118.449697.png 1341839118.449705 depth/1341839118.449705.png +1341839118.485493 rgb/1341839118.485493.png 1341839118.485527 depth/1341839118.485527.png +1341839118.517623 rgb/1341839118.517623.png 1341839118.517638 depth/1341839118.517638.png +1341839118.554050 rgb/1341839118.554050.png 1341839118.554701 depth/1341839118.554701.png +1341839118.585668 rgb/1341839118.585668.png 1341839118.585694 depth/1341839118.585694.png +1341839118.617700 rgb/1341839118.617700.png 1341839118.618254 depth/1341839118.618254.png +1341839118.653714 rgb/1341839118.653714.png 1341839118.653800 depth/1341839118.653800.png +1341839118.717504 rgb/1341839118.717504.png 1341839118.717532 depth/1341839118.717532.png +1341839118.753742 rgb/1341839118.753742.png 1341839118.753754 depth/1341839118.753754.png +1341839118.785566 rgb/1341839118.785566.png 1341839118.785590 depth/1341839118.785590.png +1341839118.821695 rgb/1341839118.821695.png 1341839118.821704 depth/1341839118.821704.png +1341839118.853833 rgb/1341839118.853833.png 1341839118.853844 depth/1341839118.853844.png +1341839118.921740 rgb/1341839118.921740.png 1341839118.921789 depth/1341839118.921789.png +1341839118.953665 rgb/1341839118.953665.png 1341839118.953675 depth/1341839118.953675.png +1341839118.989622 rgb/1341839118.989622.png 1341839118.989643 depth/1341839118.989643.png +1341839119.021687 rgb/1341839119.021687.png 1341839119.021704 depth/1341839119.021704.png +1341839119.054550 rgb/1341839119.054550.png 1341839119.054708 depth/1341839119.054708.png +1341839119.089581 rgb/1341839119.089581.png 1341839119.089606 depth/1341839119.089606.png +1341839119.121679 rgb/1341839119.121679.png 1341839119.121693 depth/1341839119.121693.png +1341839119.153810 rgb/1341839119.153810.png 1341839119.153827 depth/1341839119.153827.png +1341839119.190466 rgb/1341839119.190466.png 1341839119.190502 depth/1341839119.190502.png +1341839119.221601 rgb/1341839119.221601.png 1341839119.222133 depth/1341839119.222133.png +1341839119.257728 rgb/1341839119.257728.png 1341839119.257789 depth/1341839119.257789.png +1341839119.289455 rgb/1341839119.289455.png 1341839119.289469 depth/1341839119.289469.png +1341839119.321569 rgb/1341839119.321569.png 1341839119.321579 depth/1341839119.321579.png +1341839119.357502 rgb/1341839119.357502.png 1341839119.357517 depth/1341839119.357517.png +1341839119.389594 rgb/1341839119.389594.png 1341839119.389633 depth/1341839119.389633.png +1341839119.421517 rgb/1341839119.421517.png 1341839119.421544 depth/1341839119.421544.png +1341839119.457571 rgb/1341839119.457571.png 1341839119.457590 depth/1341839119.457590.png +1341839119.489537 rgb/1341839119.489537.png 1341839119.489563 depth/1341839119.489563.png +1341839119.525734 rgb/1341839119.525734.png 1341839119.525800 depth/1341839119.525800.png +1341839119.557461 rgb/1341839119.557461.png 1341839119.557474 depth/1341839119.557474.png +1341839119.589618 rgb/1341839119.589618.png 1341839119.589631 depth/1341839119.589631.png +1341839119.625979 rgb/1341839119.625979.png 1341839119.626045 depth/1341839119.626045.png +1341839119.657625 rgb/1341839119.657625.png 1341839119.657647 depth/1341839119.657647.png +1341839119.689899 rgb/1341839119.689899.png 1341839119.689921 depth/1341839119.689921.png +1341839119.725735 rgb/1341839119.725735.png 1341839119.725747 depth/1341839119.725747.png +1341839119.757807 rgb/1341839119.757807.png 1341839119.757831 depth/1341839119.757831.png +1341839119.793744 rgb/1341839119.793744.png 1341839119.793779 depth/1341839119.793779.png +1341839119.825500 rgb/1341839119.825500.png 1341839119.825516 depth/1341839119.825516.png +1341839119.857554 rgb/1341839119.857554.png 1341839119.858150 depth/1341839119.858150.png +1341839119.893748 rgb/1341839119.893748.png 1341839119.893763 depth/1341839119.893763.png +1341839119.925601 rgb/1341839119.925601.png 1341839119.926093 depth/1341839119.926093.png +1341839119.957678 rgb/1341839119.957678.png 1341839119.958406 depth/1341839119.958406.png +1341839119.993679 rgb/1341839119.993679.png 1341839119.993686 depth/1341839119.993686.png +1341839120.025666 rgb/1341839120.025666.png 1341839120.025686 depth/1341839120.025686.png +1341839120.061576 rgb/1341839120.061576.png 1341839120.062082 depth/1341839120.062082.png +1341839120.093515 rgb/1341839120.093515.png 1341839120.093523 depth/1341839120.093523.png +1341839120.125657 rgb/1341839120.125657.png 1341839120.125669 depth/1341839120.125669.png +1341839120.161703 rgb/1341839120.161703.png 1341839120.162177 depth/1341839120.162177.png +1341839120.193590 rgb/1341839120.193590.png 1341839120.193629 depth/1341839120.193629.png +1341839120.229713 rgb/1341839120.229713.png 1341839120.229734 depth/1341839120.229734.png +1341839120.261506 rgb/1341839120.261506.png 1341839120.261531 depth/1341839120.261531.png +1341839120.293457 rgb/1341839120.293457.png 1341839120.293477 depth/1341839120.293477.png +1341839120.329588 rgb/1341839120.329588.png 1341839120.329608 depth/1341839120.329608.png +1341839120.361629 rgb/1341839120.361629.png 1341839120.361652 depth/1341839120.361652.png +1341839120.393790 rgb/1341839120.393790.png 1341839120.393811 depth/1341839120.393811.png +1341839120.429559 rgb/1341839120.429559.png 1341839120.429594 depth/1341839120.429594.png +1341839120.461550 rgb/1341839120.461550.png 1341839120.461562 depth/1341839120.461562.png +1341839120.497665 rgb/1341839120.497665.png 1341839120.498550 depth/1341839120.498550.png +1341839120.561630 rgb/1341839120.561630.png 1341839120.561638 depth/1341839120.561638.png +1341839120.597681 rgb/1341839120.597681.png 1341839120.598284 depth/1341839120.598284.png +1341839120.629503 rgb/1341839120.629503.png 1341839120.629533 depth/1341839120.629533.png +1341839120.661993 rgb/1341839120.661993.png 1341839120.662049 depth/1341839120.662049.png +1341839120.697745 rgb/1341839120.697745.png 1341839120.697843 depth/1341839120.697843.png +1341839120.729566 rgb/1341839120.729566.png 1341839120.729590 depth/1341839120.729590.png +1341839120.765550 rgb/1341839120.765550.png 1341839120.765569 depth/1341839120.765569.png +1341839120.797761 rgb/1341839120.797761.png 1341839120.797781 depth/1341839120.797781.png +1341839120.829557 rgb/1341839120.829557.png 1341839120.829571 depth/1341839120.829571.png +1341839120.865525 rgb/1341839120.865525.png 1341839120.865538 depth/1341839120.865538.png +1341839120.897669 rgb/1341839120.897669.png 1341839120.897682 depth/1341839120.897682.png +1341839120.929785 rgb/1341839120.929785.png 1341839120.929849 depth/1341839120.929849.png +1341839120.965555 rgb/1341839120.965555.png 1341839120.965578 depth/1341839120.965578.png +1341839120.997581 rgb/1341839120.997581.png 1341839120.998014 depth/1341839120.998014.png +1341839121.033744 rgb/1341839121.033744.png 1341839121.033752 depth/1341839121.033752.png +1341839121.065604 rgb/1341839121.065604.png 1341839121.065660 depth/1341839121.065660.png +1341839121.097656 rgb/1341839121.097656.png 1341839121.097688 depth/1341839121.097688.png +1341839121.133691 rgb/1341839121.133691.png 1341839121.133718 depth/1341839121.133718.png +1341839121.165530 rgb/1341839121.165530.png 1341839121.165544 depth/1341839121.165544.png +1341839121.201575 rgb/1341839121.201575.png 1341839121.201584 depth/1341839121.201584.png +1341839121.233546 rgb/1341839121.233546.png 1341839121.233558 depth/1341839121.233558.png +1341839121.265498 rgb/1341839121.265498.png 1341839121.265521 depth/1341839121.265521.png +1341839121.301532 rgb/1341839121.301532.png 1341839121.301543 depth/1341839121.301543.png +1341839121.333608 rgb/1341839121.333608.png 1341839121.333879 depth/1341839121.333879.png +1341839121.365570 rgb/1341839121.365570.png 1341839121.365588 depth/1341839121.365588.png +1341839121.401586 rgb/1341839121.401586.png 1341839121.401600 depth/1341839121.401600.png +1341839121.433568 rgb/1341839121.433568.png 1341839121.434084 depth/1341839121.434084.png +1341839121.470470 rgb/1341839121.470470.png 1341839121.470493 depth/1341839121.470493.png +1341839121.501558 rgb/1341839121.501558.png 1341839121.501577 depth/1341839121.501577.png +1341839121.533669 rgb/1341839121.533669.png 1341839121.533709 depth/1341839121.533709.png +1341839121.569551 rgb/1341839121.569551.png 1341839121.569571 depth/1341839121.569571.png +1341839121.601594 rgb/1341839121.601594.png 1341839121.601606 depth/1341839121.601606.png +1341839121.633518 rgb/1341839121.633518.png 1341839121.633582 depth/1341839121.633582.png +1341839121.676759 rgb/1341839121.676759.png 1341839121.676801 depth/1341839121.676801.png +1341839121.737794 rgb/1341839121.737794.png 1341839121.737834 depth/1341839121.737834.png +1341839121.769806 rgb/1341839121.769806.png 1341839121.770350 depth/1341839121.770350.png +1341839121.801610 rgb/1341839121.801610.png 1341839121.801621 depth/1341839121.801621.png +1341839121.837558 rgb/1341839121.837558.png 1341839121.837588 depth/1341839121.837588.png +1341839121.869640 rgb/1341839121.869640.png 1341839121.869902 depth/1341839121.869902.png +1341839121.901603 rgb/1341839121.901603.png 1341839121.901614 depth/1341839121.901614.png +1341839121.937642 rgb/1341839121.937642.png 1341839121.937650 depth/1341839121.937650.png +1341839121.969593 rgb/1341839121.969593.png 1341839121.969901 depth/1341839121.969901.png +1341839122.005447 rgb/1341839122.005447.png 1341839122.005490 depth/1341839122.005490.png +1341839122.037577 rgb/1341839122.037577.png 1341839122.037600 depth/1341839122.037600.png +1341839122.069508 rgb/1341839122.069508.png 1341839122.069517 depth/1341839122.069517.png +1341839122.105677 rgb/1341839122.105677.png 1341839122.105701 depth/1341839122.105701.png +1341839122.137560 rgb/1341839122.137560.png 1341839122.137572 depth/1341839122.137572.png +1341839122.169506 rgb/1341839122.169506.png 1341839122.169531 depth/1341839122.169531.png +1341839122.205699 rgb/1341839122.205699.png 1341839122.206115 depth/1341839122.206115.png +1341839122.237714 rgb/1341839122.237714.png 1341839122.237733 depth/1341839122.237733.png +1341839122.273692 rgb/1341839122.273692.png 1341839122.273705 depth/1341839122.273705.png +1341839122.305536 rgb/1341839122.305536.png 1341839122.305570 depth/1341839122.305570.png +1341839122.337539 rgb/1341839122.337539.png 1341839122.337640 depth/1341839122.337640.png +1341839122.373595 rgb/1341839122.373595.png 1341839122.373679 depth/1341839122.373679.png +1341839122.405534 rgb/1341839122.405534.png 1341839122.405550 depth/1341839122.405550.png +1341839122.441566 rgb/1341839122.441566.png 1341839122.441583 depth/1341839122.441583.png +1341839122.476666 rgb/1341839122.476666.png 1341839122.476743 depth/1341839122.476743.png +1341839122.541642 rgb/1341839122.541642.png 1341839122.541663 depth/1341839122.541663.png +1341839122.605781 rgb/1341839122.605781.png 1341839122.605887 depth/1341839122.605887.png +1341839122.641573 rgb/1341839122.641573.png 1341839122.641592 depth/1341839122.641592.png +1341839122.673585 rgb/1341839122.673585.png 1341839122.674153 depth/1341839122.674153.png +1341839122.709612 rgb/1341839122.709612.png 1341839122.709650 depth/1341839122.709650.png +1341839122.744481 rgb/1341839122.744481.png 1341839122.744517 depth/1341839122.744517.png +1341839122.809572 rgb/1341839122.809572.png 1341839122.809587 depth/1341839122.809587.png +1341839122.841637 rgb/1341839122.841637.png 1341839122.842331 depth/1341839122.842331.png +1341839122.873612 rgb/1341839122.873612.png 1341839122.873662 depth/1341839122.873662.png +1341839122.909624 rgb/1341839122.909624.png 1341839122.909687 depth/1341839122.909687.png +1341839122.941543 rgb/1341839122.941543.png 1341839122.941589 depth/1341839122.941589.png +1341839122.977575 rgb/1341839122.977575.png 1341839122.977601 depth/1341839122.977601.png +1341839123.009572 rgb/1341839123.009572.png 1341839123.009587 depth/1341839123.009587.png +1341839123.041702 rgb/1341839123.041702.png 1341839123.041727 depth/1341839123.041727.png +1341839123.077583 rgb/1341839123.077583.png 1341839123.077612 depth/1341839123.077612.png +1341839123.109751 rgb/1341839123.109751.png 1341839123.109774 depth/1341839123.109774.png +1341839123.141926 rgb/1341839123.141926.png 1341839123.142716 depth/1341839123.142716.png +1341839123.177759 rgb/1341839123.177759.png 1341839123.178137 depth/1341839123.178137.png +1341839123.209570 rgb/1341839123.209570.png 1341839123.209585 depth/1341839123.209585.png +1341839123.245725 rgb/1341839123.245725.png 1341839123.245749 depth/1341839123.245749.png +1341839123.277647 rgb/1341839123.277647.png 1341839123.277667 depth/1341839123.277667.png +1341839123.309620 rgb/1341839123.309620.png 1341839123.309634 depth/1341839123.309634.png +1341839123.345630 rgb/1341839123.345630.png 1341839123.345650 depth/1341839123.345650.png +1341839123.378204 rgb/1341839123.378204.png 1341839123.378227 depth/1341839123.378227.png +1341839123.413605 rgb/1341839123.413605.png 1341839123.413625 depth/1341839123.413625.png +1341839123.445605 rgb/1341839123.445605.png 1341839123.445618 depth/1341839123.445618.png +1341839123.477524 rgb/1341839123.477524.png 1341839123.477537 depth/1341839123.477537.png +1341839123.513569 rgb/1341839123.513569.png 1341839123.513609 depth/1341839123.513609.png +1341839123.545681 rgb/1341839123.545681.png 1341839123.545736 depth/1341839123.545736.png +1341839123.577643 rgb/1341839123.577643.png 1341839123.577657 depth/1341839123.577657.png +1341839123.613598 rgb/1341839123.613598.png 1341839123.613606 depth/1341839123.613606.png +1341839123.645669 rgb/1341839123.645669.png 1341839123.645678 depth/1341839123.645678.png +1341839123.681751 rgb/1341839123.681751.png 1341839123.681788 depth/1341839123.681788.png +1341839123.713662 rgb/1341839123.713662.png 1341839123.713688 depth/1341839123.713688.png +1341839123.745702 rgb/1341839123.745702.png 1341839123.745715 depth/1341839123.745715.png +1341839123.781632 rgb/1341839123.781632.png 1341839123.781644 depth/1341839123.781644.png +1341839123.813710 rgb/1341839123.813710.png 1341839123.813763 depth/1341839123.813763.png +1341839123.845656 rgb/1341839123.845656.png 1341839123.845672 depth/1341839123.845672.png +1341839123.881576 rgb/1341839123.881576.png 1341839123.881630 depth/1341839123.881630.png +1341839123.913827 rgb/1341839123.913827.png 1341839123.913850 depth/1341839123.913850.png +1341839123.949667 rgb/1341839123.949667.png 1341839123.949682 depth/1341839123.949682.png +1341839123.981668 rgb/1341839123.981668.png 1341839123.981687 depth/1341839123.981687.png +1341839124.013726 rgb/1341839124.013726.png 1341839124.013749 depth/1341839124.013749.png +1341839124.049634 rgb/1341839124.049634.png 1341839124.049715 depth/1341839124.049715.png +1341839124.081682 rgb/1341839124.081682.png 1341839124.081734 depth/1341839124.081734.png +1341839124.113596 rgb/1341839124.113596.png 1341839124.113604 depth/1341839124.113604.png +1341839124.149548 rgb/1341839124.149548.png 1341839124.149574 depth/1341839124.149574.png +1341839124.181547 rgb/1341839124.181547.png 1341839124.181563 depth/1341839124.181563.png +1341839124.217783 rgb/1341839124.217783.png 1341839124.217814 depth/1341839124.217814.png +1341839124.256572 rgb/1341839124.256572.png 1341839124.249849 depth/1341839124.249849.png +1341839124.317542 rgb/1341839124.317542.png 1341839124.317575 depth/1341839124.317575.png +1341839124.349622 rgb/1341839124.349622.png 1341839124.349673 depth/1341839124.349673.png +1341839124.417782 rgb/1341839124.417782.png 1341839124.417797 depth/1341839124.417797.png +1341839124.449587 rgb/1341839124.449587.png 1341839124.449597 depth/1341839124.449597.png +1341839124.485711 rgb/1341839124.485711.png 1341839124.485734 depth/1341839124.485734.png +1341839124.549607 rgb/1341839124.549607.png 1341839124.550027 depth/1341839124.550027.png +1341839124.585623 rgb/1341839124.585623.png 1341839124.585651 depth/1341839124.585651.png +1341839124.617614 rgb/1341839124.617614.png 1341839124.617783 depth/1341839124.617783.png +1341839124.653561 rgb/1341839124.653561.png 1341839124.653573 depth/1341839124.653573.png +1341839124.685611 rgb/1341839124.685611.png 1341839124.685623 depth/1341839124.685623.png +1341839124.717580 rgb/1341839124.717580.png 1341839124.717702 depth/1341839124.717702.png +1341839124.753621 rgb/1341839124.753621.png 1341839124.753651 depth/1341839124.753651.png +1341839124.785678 rgb/1341839124.785678.png 1341839124.785724 depth/1341839124.785724.png +1341839124.817558 rgb/1341839124.817558.png 1341839124.817580 depth/1341839124.817580.png +1341839124.885712 rgb/1341839124.885712.png 1341839124.885730 depth/1341839124.885730.png +1341839124.921721 rgb/1341839124.921721.png 1341839124.921744 depth/1341839124.921744.png +1341839124.953580 rgb/1341839124.953580.png 1341839124.953591 depth/1341839124.953591.png +1341839124.985862 rgb/1341839124.985862.png 1341839124.985870 depth/1341839124.985870.png +1341839125.021660 rgb/1341839125.021660.png 1341839125.021865 depth/1341839125.021865.png +1341839125.053606 rgb/1341839125.053606.png 1341839125.053630 depth/1341839125.053630.png +1341839125.086082 rgb/1341839125.086082.png 1341839125.086101 depth/1341839125.086101.png +1341839125.121616 rgb/1341839125.121616.png 1341839125.121631 depth/1341839125.121631.png +1341839125.153540 rgb/1341839125.153540.png 1341839125.153551 depth/1341839125.153551.png +1341839125.189545 rgb/1341839125.189545.png 1341839125.189564 depth/1341839125.189564.png +1341839125.221519 rgb/1341839125.221519.png 1341839125.221564 depth/1341839125.221564.png +1341839125.253620 rgb/1341839125.253620.png 1341839125.253665 depth/1341839125.253665.png +1341839125.289646 rgb/1341839125.289646.png 1341839125.289666 depth/1341839125.289666.png +1341839125.321651 rgb/1341839125.321651.png 1341839125.321674 depth/1341839125.321674.png +1341839125.353612 rgb/1341839125.353612.png 1341839125.353627 depth/1341839125.353627.png +1341839125.389732 rgb/1341839125.389732.png 1341839125.389760 depth/1341839125.389760.png +1341839125.421568 rgb/1341839125.421568.png 1341839125.421575 depth/1341839125.421575.png +1341839125.457605 rgb/1341839125.457605.png 1341839125.457644 depth/1341839125.457644.png +1341839125.489491 rgb/1341839125.489491.png 1341839125.489501 depth/1341839125.489501.png +1341839125.521521 rgb/1341839125.521521.png 1341839125.521569 depth/1341839125.521569.png +1341839125.557578 rgb/1341839125.557578.png 1341839125.557591 depth/1341839125.557591.png +1341839125.596685 rgb/1341839125.596685.png 1341839125.596729 depth/1341839125.596729.png +1341839125.657655 rgb/1341839125.657655.png 1341839125.657797 depth/1341839125.657797.png +1341839125.689599 rgb/1341839125.689599.png 1341839125.690072 depth/1341839125.690072.png +1341839125.725674 rgb/1341839125.725674.png 1341839125.725693 depth/1341839125.725693.png +1341839125.757650 rgb/1341839125.757650.png 1341839125.757671 depth/1341839125.757671.png +1341839125.789697 rgb/1341839125.789697.png 1341839125.789738 depth/1341839125.789738.png +1341839125.825554 rgb/1341839125.825554.png 1341839125.825570 depth/1341839125.825570.png +1341839125.857601 rgb/1341839125.857601.png 1341839125.857614 depth/1341839125.857614.png +1341839125.893542 rgb/1341839125.893542.png 1341839125.893553 depth/1341839125.893553.png +1341839125.925748 rgb/1341839125.925748.png 1341839125.925756 depth/1341839125.925756.png +1341839125.957565 rgb/1341839125.957565.png 1341839125.957592 depth/1341839125.957592.png +1341839125.993528 rgb/1341839125.993528.png 1341839125.993600 depth/1341839125.993600.png +1341839126.025584 rgb/1341839126.025584.png 1341839126.025601 depth/1341839126.025601.png +1341839126.057677 rgb/1341839126.057677.png 1341839126.057694 depth/1341839126.057694.png +1341839126.093586 rgb/1341839126.093586.png 1341839126.093647 depth/1341839126.093647.png +1341839126.125584 rgb/1341839126.125584.png 1341839126.125605 depth/1341839126.125605.png +1341839126.161675 rgb/1341839126.161675.png 1341839126.161697 depth/1341839126.161697.png +1341839126.193566 rgb/1341839126.193566.png 1341839126.193590 depth/1341839126.193590.png +1341839126.225494 rgb/1341839126.225494.png 1341839126.225527 depth/1341839126.225527.png +1341839126.262252 rgb/1341839126.262252.png 1341839126.262271 depth/1341839126.262271.png +1341839126.293564 rgb/1341839126.293564.png 1341839126.293586 depth/1341839126.293586.png +1341839126.325643 rgb/1341839126.325643.png 1341839126.325656 depth/1341839126.325656.png +1341839126.361562 rgb/1341839126.361562.png 1341839126.361590 depth/1341839126.361590.png +1341839126.393475 rgb/1341839126.393475.png 1341839126.393517 depth/1341839126.393517.png +1341839126.429534 rgb/1341839126.429534.png 1341839126.429545 depth/1341839126.429545.png +1341839126.461585 rgb/1341839126.461585.png 1341839126.461608 depth/1341839126.461608.png +1341839126.493573 rgb/1341839126.493573.png 1341839126.494019 depth/1341839126.494019.png +1341839126.529589 rgb/1341839126.529589.png 1341839126.529605 depth/1341839126.529605.png +1341839126.561488 rgb/1341839126.561488.png 1341839126.561522 depth/1341839126.561522.png +1341839126.593549 rgb/1341839126.593549.png 1341839126.593587 depth/1341839126.593587.png +1341839126.629751 rgb/1341839126.629751.png 1341839126.629764 depth/1341839126.629764.png +1341839126.661503 rgb/1341839126.661503.png 1341839126.661581 depth/1341839126.661581.png +1341839126.697561 rgb/1341839126.697561.png 1341839126.697574 depth/1341839126.697574.png +1341839126.729517 rgb/1341839126.729517.png 1341839126.729533 depth/1341839126.729533.png +1341839126.761554 rgb/1341839126.761554.png 1341839126.761749 depth/1341839126.761749.png +1341839126.797734 rgb/1341839126.797734.png 1341839126.797746 depth/1341839126.797746.png +1341839126.829608 rgb/1341839126.829608.png 1341839126.829633 depth/1341839126.829633.png +1341839126.865650 rgb/1341839126.865650.png 1341839126.865668 depth/1341839126.865668.png +1341839126.897640 rgb/1341839126.897640.png 1341839126.897660 depth/1341839126.897660.png +1341839126.929680 rgb/1341839126.929680.png 1341839126.929767 depth/1341839126.929767.png +1341839126.965564 rgb/1341839126.965564.png 1341839126.965600 depth/1341839126.965600.png +1341839126.997665 rgb/1341839126.997665.png 1341839126.997674 depth/1341839126.997674.png +1341839127.029597 rgb/1341839127.029597.png 1341839127.029615 depth/1341839127.029615.png +1341839127.065594 rgb/1341839127.065594.png 1341839127.065615 depth/1341839127.065615.png +1341839127.097689 rgb/1341839127.097689.png 1341839127.097715 depth/1341839127.097715.png +1341839127.133571 rgb/1341839127.133571.png 1341839127.133618 depth/1341839127.133618.png +1341839127.165684 rgb/1341839127.165684.png 1341839127.165733 depth/1341839127.165733.png +1341839127.197636 rgb/1341839127.197636.png 1341839127.197663 depth/1341839127.197663.png +1341839127.233596 rgb/1341839127.233596.png 1341839127.233621 depth/1341839127.233621.png +1341839127.265755 rgb/1341839127.265755.png 1341839127.265775 depth/1341839127.265775.png +1341839127.297673 rgb/1341839127.297673.png 1341839127.297695 depth/1341839127.297695.png +1341839127.333679 rgb/1341839127.333679.png 1341839127.333702 depth/1341839127.333702.png +1341839127.372174 rgb/1341839127.372174.png 1341839127.372929 depth/1341839127.372929.png +1341839127.401871 rgb/1341839127.401871.png 1341839127.403014 depth/1341839127.403014.png +1341839127.434153 rgb/1341839127.434153.png 1341839127.435026 depth/1341839127.435026.png +1341839127.465725 rgb/1341839127.465725.png 1341839127.465735 depth/1341839127.465735.png +1341839127.502087 rgb/1341839127.502087.png 1341839127.502101 depth/1341839127.502101.png +1341839127.533614 rgb/1341839127.533614.png 1341839127.533637 depth/1341839127.533637.png +1341839127.565666 rgb/1341839127.565666.png 1341839127.565871 depth/1341839127.565871.png +1341839127.601497 rgb/1341839127.601497.png 1341839127.601511 depth/1341839127.601511.png +1341839127.633641 rgb/1341839127.633641.png 1341839127.633657 depth/1341839127.633657.png +1341839127.669721 rgb/1341839127.669721.png 1341839127.669739 depth/1341839127.669739.png +1341839127.701590 rgb/1341839127.701590.png 1341839127.701606 depth/1341839127.701606.png +1341839127.733628 rgb/1341839127.733628.png 1341839127.733638 depth/1341839127.733638.png +1341839127.769756 rgb/1341839127.769756.png 1341839127.769782 depth/1341839127.769782.png +1341839127.801629 rgb/1341839127.801629.png 1341839127.802181 depth/1341839127.802181.png +1341839127.837525 rgb/1341839127.837525.png 1341839127.837534 depth/1341839127.837534.png +1341839127.869904 rgb/1341839127.869904.png 1341839127.870065 depth/1341839127.870065.png +1341839127.901787 rgb/1341839127.901787.png 1341839127.901846 depth/1341839127.901846.png +1341839127.937458 rgb/1341839127.937458.png 1341839127.937489 depth/1341839127.937489.png +1341839127.970000 rgb/1341839127.970000.png 1341839127.970627 depth/1341839127.970627.png +1341839128.001556 rgb/1341839128.001556.png 1341839128.001579 depth/1341839128.001579.png +1341839128.037646 rgb/1341839128.037646.png 1341839128.037671 depth/1341839128.037671.png +1341839128.069528 rgb/1341839128.069528.png 1341839128.069541 depth/1341839128.069541.png +1341839128.105485 rgb/1341839128.105485.png 1341839128.105501 depth/1341839128.105501.png +1341839128.137556 rgb/1341839128.137556.png 1341839128.138295 depth/1341839128.138295.png +1341839128.169766 rgb/1341839128.169766.png 1341839128.169799 depth/1341839128.169799.png +1341839128.205769 rgb/1341839128.205769.png 1341839128.205784 depth/1341839128.205784.png +1341839128.237693 rgb/1341839128.237693.png 1341839128.237713 depth/1341839128.237713.png +1341839128.269778 rgb/1341839128.269778.png 1341839128.269799 depth/1341839128.269799.png +1341839128.305489 rgb/1341839128.305489.png 1341839128.305502 depth/1341839128.305502.png +1341839128.337488 rgb/1341839128.337488.png 1341839128.337510 depth/1341839128.337510.png +1341839128.373648 rgb/1341839128.373648.png 1341839128.373669 depth/1341839128.373669.png +1341839128.405628 rgb/1341839128.405628.png 1341839128.405639 depth/1341839128.405639.png +1341839128.438499 rgb/1341839128.438499.png 1341839128.438573 depth/1341839128.438573.png +1341839128.473696 rgb/1341839128.473696.png 1341839128.473733 depth/1341839128.473733.png +1341839128.505546 rgb/1341839128.505546.png 1341839128.505612 depth/1341839128.505612.png +1341839128.537583 rgb/1341839128.537583.png 1341839128.537658 depth/1341839128.537658.png +1341839128.573515 rgb/1341839128.573515.png 1341839128.573552 depth/1341839128.573552.png +1341839128.605707 rgb/1341839128.605707.png 1341839128.605727 depth/1341839128.605727.png +1341839128.641615 rgb/1341839128.641615.png 1341839128.641632 depth/1341839128.641632.png +1341839128.674297 rgb/1341839128.674297.png 1341839128.674920 depth/1341839128.674920.png +1341839128.705724 rgb/1341839128.705724.png 1341839128.705740 depth/1341839128.705740.png +1341839128.741577 rgb/1341839128.741577.png 1341839128.742207 depth/1341839128.742207.png +1341839128.773449 rgb/1341839128.773449.png 1341839128.773460 depth/1341839128.773460.png +1341839128.805626 rgb/1341839128.805626.png 1341839128.805641 depth/1341839128.805641.png +1341839128.841524 rgb/1341839128.841524.png 1341839128.841539 depth/1341839128.841539.png +1341839128.873613 rgb/1341839128.873613.png 1341839128.873656 depth/1341839128.873656.png +1341839128.909718 rgb/1341839128.909718.png 1341839128.909735 depth/1341839128.909735.png +1341839128.941487 rgb/1341839128.941487.png 1341839128.941495 depth/1341839128.941495.png +1341839128.973556 rgb/1341839128.973556.png 1341839128.973591 depth/1341839128.973591.png +1341839129.009679 rgb/1341839129.009679.png 1341839129.009689 depth/1341839129.009689.png +1341839129.041584 rgb/1341839129.041584.png 1341839129.041607 depth/1341839129.041607.png +1341839129.077533 rgb/1341839129.077533.png 1341839129.077558 depth/1341839129.077558.png +1341839129.109520 rgb/1341839129.109520.png 1341839129.109556 depth/1341839129.109556.png +1341839129.141619 rgb/1341839129.141619.png 1341839129.141627 depth/1341839129.141627.png +1341839129.177574 rgb/1341839129.177574.png 1341839129.177582 depth/1341839129.177582.png +1341839129.209655 rgb/1341839129.209655.png 1341839129.209674 depth/1341839129.209674.png +1341839129.241510 rgb/1341839129.241510.png 1341839129.241519 depth/1341839129.241519.png +1341839129.277541 rgb/1341839129.277541.png 1341839129.277553 depth/1341839129.277553.png +1341839129.309548 rgb/1341839129.309548.png 1341839129.309565 depth/1341839129.309565.png +1341839129.345615 rgb/1341839129.345615.png 1341839129.345627 depth/1341839129.345627.png +1341839129.377515 rgb/1341839129.377515.png 1341839129.377530 depth/1341839129.377530.png +1341839129.409635 rgb/1341839129.409635.png 1341839129.409649 depth/1341839129.409649.png +1341839129.445518 rgb/1341839129.445518.png 1341839129.445529 depth/1341839129.445529.png +1341839129.477523 rgb/1341839129.477523.png 1341839129.477534 depth/1341839129.477534.png +1341839129.509566 rgb/1341839129.509566.png 1341839129.509582 depth/1341839129.509582.png +1341839129.545536 rgb/1341839129.545536.png 1341839129.545555 depth/1341839129.545555.png +1341839129.577541 rgb/1341839129.577541.png 1341839129.577559 depth/1341839129.577559.png +1341839129.613707 rgb/1341839129.613707.png 1341839129.613729 depth/1341839129.613729.png +1341839129.645497 rgb/1341839129.645497.png 1341839129.645519 depth/1341839129.645519.png +1341839129.677529 rgb/1341839129.677529.png 1341839129.677690 depth/1341839129.677690.png +1341839129.713807 rgb/1341839129.713807.png 1341839129.713820 depth/1341839129.713820.png +1341839129.745656 rgb/1341839129.745656.png 1341839129.745670 depth/1341839129.745670.png +1341839129.777553 rgb/1341839129.777553.png 1341839129.777564 depth/1341839129.777564.png +1341839129.813668 rgb/1341839129.813668.png 1341839129.813737 depth/1341839129.813737.png +1341839129.845557 rgb/1341839129.845557.png 1341839129.845703 depth/1341839129.845703.png +1341839129.881595 rgb/1341839129.881595.png 1341839129.881622 depth/1341839129.881622.png +1341839129.913656 rgb/1341839129.913656.png 1341839129.913673 depth/1341839129.913673.png +1341839129.945668 rgb/1341839129.945668.png 1341839129.945681 depth/1341839129.945681.png +1341839129.981581 rgb/1341839129.981581.png 1341839129.981601 depth/1341839129.981601.png +1341839130.013837 rgb/1341839130.013837.png 1341839130.013849 depth/1341839130.013849.png +1341839130.049672 rgb/1341839130.049672.png 1341839130.049686 depth/1341839130.049686.png +1341839130.081470 rgb/1341839130.081470.png 1341839130.081559 depth/1341839130.081559.png +1341839130.113580 rgb/1341839130.113580.png 1341839130.113635 depth/1341839130.113635.png +1341839130.149498 rgb/1341839130.149498.png 1341839130.149505 depth/1341839130.149505.png +1341839130.181614 rgb/1341839130.181614.png 1341839130.181637 depth/1341839130.181637.png +1341839130.213597 rgb/1341839130.213597.png 1341839130.213610 depth/1341839130.213610.png +1341839130.249495 rgb/1341839130.249495.png 1341839130.249536 depth/1341839130.249536.png +1341839130.281707 rgb/1341839130.281707.png 1341839130.281723 depth/1341839130.281723.png +1341839130.317659 rgb/1341839130.317659.png 1341839130.317710 depth/1341839130.317710.png +1341839130.349604 rgb/1341839130.349604.png 1341839130.349627 depth/1341839130.349627.png +1341839130.382034 rgb/1341839130.382034.png 1341839130.382042 depth/1341839130.382042.png +1341839130.417728 rgb/1341839130.417728.png 1341839130.417741 depth/1341839130.417741.png +1341839130.481948 rgb/1341839130.481948.png 1341839130.481966 depth/1341839130.481966.png +1341839130.517772 rgb/1341839130.517772.png 1341839130.517798 depth/1341839130.517798.png +1341839130.549519 rgb/1341839130.549519.png 1341839130.549528 depth/1341839130.549528.png +1341839130.585696 rgb/1341839130.585696.png 1341839130.585714 depth/1341839130.585714.png +1341839130.617684 rgb/1341839130.617684.png 1341839130.617718 depth/1341839130.617718.png +1341839130.649566 rgb/1341839130.649566.png 1341839130.649594 depth/1341839130.649594.png +1341839130.685466 rgb/1341839130.685466.png 1341839130.685514 depth/1341839130.685514.png +1341839130.717517 rgb/1341839130.717517.png 1341839130.717526 depth/1341839130.717526.png +1341839130.749572 rgb/1341839130.749572.png 1341839130.749585 depth/1341839130.749585.png +1341839130.785686 rgb/1341839130.785686.png 1341839130.785731 depth/1341839130.785731.png +1341839130.817796 rgb/1341839130.817796.png 1341839130.817808 depth/1341839130.817808.png +1341839130.854788 rgb/1341839130.854788.png 1341839130.854839 depth/1341839130.854839.png +1341839130.885541 rgb/1341839130.885541.png 1341839130.885562 depth/1341839130.885562.png +1341839130.917632 rgb/1341839130.917632.png 1341839130.917661 depth/1341839130.917661.png +1341839130.953712 rgb/1341839130.953712.png 1341839130.953729 depth/1341839130.953729.png +1341839130.985630 rgb/1341839130.985630.png 1341839130.985652 depth/1341839130.985652.png +1341839131.017560 rgb/1341839131.017560.png 1341839131.017580 depth/1341839131.017580.png +1341839131.053526 rgb/1341839131.053526.png 1341839131.053539 depth/1341839131.053539.png +1341839131.085681 rgb/1341839131.085681.png 1341839131.085696 depth/1341839131.085696.png +1341839131.121737 rgb/1341839131.121737.png 1341839131.121752 depth/1341839131.121752.png +1341839131.153629 rgb/1341839131.153629.png 1341839131.153653 depth/1341839131.153653.png +1341839131.185722 rgb/1341839131.185722.png 1341839131.185748 depth/1341839131.185748.png +1341839131.221649 rgb/1341839131.221649.png 1341839131.221694 depth/1341839131.221694.png +1341839131.253615 rgb/1341839131.253615.png 1341839131.253631 depth/1341839131.253631.png +1341839131.289544 rgb/1341839131.289544.png 1341839131.289561 depth/1341839131.289561.png +1341839131.321742 rgb/1341839131.321742.png 1341839131.322248 depth/1341839131.322248.png +1341839131.353559 rgb/1341839131.353559.png 1341839131.353573 depth/1341839131.353573.png +1341839131.389563 rgb/1341839131.389563.png 1341839131.389669 depth/1341839131.389669.png +1341839131.422027 rgb/1341839131.422027.png 1341839131.422054 depth/1341839131.422054.png +1341839131.453618 rgb/1341839131.453618.png 1341839131.453637 depth/1341839131.453637.png +1341839131.489531 rgb/1341839131.489531.png 1341839131.490178 depth/1341839131.490178.png +1341839131.521613 rgb/1341839131.521613.png 1341839131.521627 depth/1341839131.521627.png +1341839131.557577 rgb/1341839131.557577.png 1341839131.557635 depth/1341839131.557635.png +1341839131.589573 rgb/1341839131.589573.png 1341839131.589595 depth/1341839131.589595.png +1341839131.621822 rgb/1341839131.621822.png 1341839131.621841 depth/1341839131.621841.png +1341839131.657680 rgb/1341839131.657680.png 1341839131.657733 depth/1341839131.657733.png +1341839131.689554 rgb/1341839131.689554.png 1341839131.689567 depth/1341839131.689567.png +1341839131.721592 rgb/1341839131.721592.png 1341839131.721604 depth/1341839131.721604.png +1341839131.757613 rgb/1341839131.757613.png 1341839131.757626 depth/1341839131.757626.png +1341839131.789523 rgb/1341839131.789523.png 1341839131.789543 depth/1341839131.789543.png +1341839131.825565 rgb/1341839131.825565.png 1341839131.825591 depth/1341839131.825591.png +1341839131.857572 rgb/1341839131.857572.png 1341839131.857658 depth/1341839131.857658.png +1341839131.889513 rgb/1341839131.889513.png 1341839131.889551 depth/1341839131.889551.png +1341839131.925750 rgb/1341839131.925750.png 1341839131.925782 depth/1341839131.925782.png +1341839131.964633 rgb/1341839131.964633.png 1341839131.964702 depth/1341839131.964702.png +1341839132.025660 rgb/1341839132.025660.png 1341839132.025687 depth/1341839132.025687.png +1341839132.057881 rgb/1341839132.057881.png 1341839132.057902 depth/1341839132.057902.png +1341839132.093669 rgb/1341839132.093669.png 1341839132.093693 depth/1341839132.093693.png +1341839132.125565 rgb/1341839132.125565.png 1341839132.125577 depth/1341839132.125577.png +1341839132.157636 rgb/1341839132.157636.png 1341839132.157647 depth/1341839132.157647.png +1341839132.193673 rgb/1341839132.193673.png 1341839132.193681 depth/1341839132.193681.png +1341839132.225804 rgb/1341839132.225804.png 1341839132.225817 depth/1341839132.225817.png +1341839132.261812 rgb/1341839132.261812.png 1341839132.262262 depth/1341839132.262262.png +1341839132.293590 rgb/1341839132.293590.png 1341839132.293623 depth/1341839132.293623.png +1341839132.325554 rgb/1341839132.325554.png 1341839132.325679 depth/1341839132.325679.png +1341839132.361528 rgb/1341839132.361528.png 1341839132.361535 depth/1341839132.361535.png +1341839132.393650 rgb/1341839132.393650.png 1341839132.393667 depth/1341839132.393667.png +1341839132.425622 rgb/1341839132.425622.png 1341839132.425634 depth/1341839132.425634.png +1341839132.461663 rgb/1341839132.461663.png 1341839132.461671 depth/1341839132.461671.png +1341839132.493798 rgb/1341839132.493798.png 1341839132.493835 depth/1341839132.493835.png +1341839132.529690 rgb/1341839132.529690.png 1341839132.529728 depth/1341839132.529728.png +1341839132.561519 rgb/1341839132.561519.png 1341839132.561537 depth/1341839132.561537.png +1341839132.593700 rgb/1341839132.593700.png 1341839132.593905 depth/1341839132.593905.png +1341839132.629507 rgb/1341839132.629507.png 1341839132.629758 depth/1341839132.629758.png +1341839132.661576 rgb/1341839132.661576.png 1341839132.661595 depth/1341839132.661595.png +1341839132.693571 rgb/1341839132.693571.png 1341839132.693604 depth/1341839132.693604.png +1341839132.729515 rgb/1341839132.729515.png 1341839132.729524 depth/1341839132.729524.png +1341839132.761625 rgb/1341839132.761625.png 1341839132.761643 depth/1341839132.761643.png +1341839132.797547 rgb/1341839132.797547.png 1341839132.797561 depth/1341839132.797561.png +1341839132.829637 rgb/1341839132.829637.png 1341839132.829675 depth/1341839132.829675.png +1341839132.861592 rgb/1341839132.861592.png 1341839132.861615 depth/1341839132.861615.png +1341839132.897486 rgb/1341839132.897486.png 1341839132.897498 depth/1341839132.897498.png +1341839132.929713 rgb/1341839132.929713.png 1341839132.929749 depth/1341839132.929749.png +1341839132.961705 rgb/1341839132.961705.png 1341839132.961719 depth/1341839132.961719.png +1341839132.997927 rgb/1341839132.997927.png 1341839132.997942 depth/1341839132.997942.png +1341839133.029816 rgb/1341839133.029816.png 1341839133.029824 depth/1341839133.029824.png +1341839133.065602 rgb/1341839133.065602.png 1341839133.065673 depth/1341839133.065673.png +1341839133.097540 rgb/1341839133.097540.png 1341839133.097620 depth/1341839133.097620.png +1341839133.129508 rgb/1341839133.129508.png 1341839133.129523 depth/1341839133.129523.png +1341839133.165630 rgb/1341839133.165630.png 1341839133.165642 depth/1341839133.165642.png +1341839133.197576 rgb/1341839133.197576.png 1341839133.197583 depth/1341839133.197583.png +1341839133.229574 rgb/1341839133.229574.png 1341839133.229594 depth/1341839133.229594.png +1341839133.265549 rgb/1341839133.265549.png 1341839133.265591 depth/1341839133.265591.png +1341839133.297600 rgb/1341839133.297600.png 1341839133.297609 depth/1341839133.297609.png +1341839133.333601 rgb/1341839133.333601.png 1341839133.333647 depth/1341839133.333647.png +1341839133.365789 rgb/1341839133.365789.png 1341839133.365812 depth/1341839133.365812.png +1341839133.397692 rgb/1341839133.397692.png 1341839133.397732 depth/1341839133.397732.png +1341839133.433673 rgb/1341839133.433673.png 1341839133.433740 depth/1341839133.433740.png +1341839133.465589 rgb/1341839133.465589.png 1341839133.465597 depth/1341839133.465597.png +1341839133.501571 rgb/1341839133.501571.png 1341839133.501580 depth/1341839133.501580.png +1341839133.533533 rgb/1341839133.533533.png 1341839133.533554 depth/1341839133.533554.png +1341839133.565553 rgb/1341839133.565553.png 1341839133.565575 depth/1341839133.565575.png +1341839133.633642 rgb/1341839133.633642.png 1341839133.633671 depth/1341839133.633671.png +1341839133.672597 rgb/1341839133.672597.png 1341839133.672610 depth/1341839133.672610.png +1341839133.708834 rgb/1341839133.708834.png 1341839133.708869 depth/1341839133.708869.png +1341839133.740662 rgb/1341839133.740662.png 1341839133.740680 depth/1341839133.740680.png +1341839133.776632 rgb/1341839133.776632.png 1341839133.776655 depth/1341839133.776655.png +1341839133.808566 rgb/1341839133.808566.png 1341839133.808578 depth/1341839133.808578.png +1341839133.842375 rgb/1341839133.842375.png 1341839133.842385 depth/1341839133.842385.png +1341839133.876620 rgb/1341839133.876620.png 1341839133.876627 depth/1341839133.876627.png +1341839133.908528 rgb/1341839133.908528.png 1341839133.908540 depth/1341839133.908540.png +1341839133.940713 rgb/1341839133.940713.png 1341839133.940728 depth/1341839133.940728.png +1341839133.976740 rgb/1341839133.976740.png 1341839133.976761 depth/1341839133.976761.png +1341839134.008547 rgb/1341839134.008547.png 1341839134.008597 depth/1341839134.008597.png +1341839134.040599 rgb/1341839134.040599.png 1341839134.040610 depth/1341839134.040610.png +1341839134.076583 rgb/1341839134.076583.png 1341839134.076596 depth/1341839134.076596.png +1341839134.108666 rgb/1341839134.108666.png 1341839134.108678 depth/1341839134.108678.png +1341839134.145583 rgb/1341839134.145583.png 1341839134.145596 depth/1341839134.145596.png +1341839134.177037 rgb/1341839134.177037.png 1341839134.177059 depth/1341839134.177059.png +1341839134.208585 rgb/1341839134.208585.png 1341839134.208602 depth/1341839134.208602.png +1341839134.245077 rgb/1341839134.245077.png 1341839134.245208 depth/1341839134.245208.png +1341839134.276660 rgb/1341839134.276660.png 1341839134.276724 depth/1341839134.276724.png +1341839134.344596 rgb/1341839134.344596.png 1341839134.344691 depth/1341839134.344691.png +1341839134.405658 rgb/1341839134.405658.png 1341839134.405677 depth/1341839134.405677.png +1341839134.437582 rgb/1341839134.437582.png 1341839134.437603 depth/1341839134.437603.png +1341839134.473570 rgb/1341839134.473570.png 1341839134.473580 depth/1341839134.473580.png +1341839134.505576 rgb/1341839134.505576.png 1341839134.505609 depth/1341839134.505609.png +1341839134.537527 rgb/1341839134.537527.png 1341839134.537537 depth/1341839134.537537.png +1341839134.573575 rgb/1341839134.573575.png 1341839134.573591 depth/1341839134.573591.png +1341839134.605581 rgb/1341839134.605581.png 1341839134.605594 depth/1341839134.605594.png +1341839134.637613 rgb/1341839134.637613.png 1341839134.637630 depth/1341839134.637630.png +1341839134.673530 rgb/1341839134.673530.png 1341839134.673545 depth/1341839134.673545.png +1341839134.705768 rgb/1341839134.705768.png 1341839134.705781 depth/1341839134.705781.png +1341839134.741672 rgb/1341839134.741672.png 1341839134.741751 depth/1341839134.741751.png +1341839134.773479 rgb/1341839134.773479.png 1341839134.773494 depth/1341839134.773494.png +1341839134.805757 rgb/1341839134.805757.png 1341839134.805770 depth/1341839134.805770.png +1341839134.841632 rgb/1341839134.841632.png 1341839134.841655 depth/1341839134.841655.png +1341839134.873616 rgb/1341839134.873616.png 1341839134.873632 depth/1341839134.873632.png +1341839134.905696 rgb/1341839134.905696.png 1341839134.905704 depth/1341839134.905704.png +1341839134.941552 rgb/1341839134.941552.png 1341839134.941561 depth/1341839134.941561.png +1341839134.974666 rgb/1341839134.974666.png 1341839134.974739 depth/1341839134.974739.png +1341839135.009601 rgb/1341839135.009601.png 1341839135.009614 depth/1341839135.009614.png +1341839135.042135 rgb/1341839135.042135.png 1341839135.042147 depth/1341839135.042147.png +1341839135.073504 rgb/1341839135.073504.png 1341839135.073516 depth/1341839135.073516.png +1341839135.109696 rgb/1341839135.109696.png 1341839135.109714 depth/1341839135.109714.png +1341839135.141720 rgb/1341839135.141720.png 1341839135.141729 depth/1341839135.141729.png +1341839135.173566 rgb/1341839135.173566.png 1341839135.173615 depth/1341839135.173615.png +1341839135.209553 rgb/1341839135.209553.png 1341839135.209575 depth/1341839135.209575.png +1341839135.241688 rgb/1341839135.241688.png 1341839135.241697 depth/1341839135.241697.png +1341839135.277641 rgb/1341839135.277641.png 1341839135.277681 depth/1341839135.277681.png +1341839135.309842 rgb/1341839135.309842.png 1341839135.310691 depth/1341839135.310691.png +1341839135.341555 rgb/1341839135.341555.png 1341839135.341637 depth/1341839135.341637.png +1341839135.377558 rgb/1341839135.377558.png 1341839135.378308 depth/1341839135.378308.png +1341839135.409554 rgb/1341839135.409554.png 1341839135.409570 depth/1341839135.409570.png +1341839135.441588 rgb/1341839135.441588.png 1341839135.441604 depth/1341839135.441604.png +1341839135.477530 rgb/1341839135.477530.png 1341839135.477542 depth/1341839135.477542.png +1341839135.509758 rgb/1341839135.509758.png 1341839135.509777 depth/1341839135.509777.png +1341839135.545510 rgb/1341839135.545510.png 1341839135.545525 depth/1341839135.545525.png +1341839135.577577 rgb/1341839135.577577.png 1341839135.577594 depth/1341839135.577594.png +1341839135.609596 rgb/1341839135.609596.png 1341839135.609617 depth/1341839135.609617.png +1341839135.645470 rgb/1341839135.645470.png 1341839135.645480 depth/1341839135.645480.png +1341839135.677567 rgb/1341839135.677567.png 1341839135.677577 depth/1341839135.677577.png +1341839135.713508 rgb/1341839135.713508.png 1341839135.713519 depth/1341839135.713519.png +1341839135.745626 rgb/1341839135.745626.png 1341839135.745644 depth/1341839135.745644.png +1341839135.777556 rgb/1341839135.777556.png 1341839135.777565 depth/1341839135.777565.png +1341839135.813582 rgb/1341839135.813582.png 1341839135.813599 depth/1341839135.813599.png +1341839135.845539 rgb/1341839135.845539.png 1341839135.845556 depth/1341839135.845556.png +1341839135.877786 rgb/1341839135.877786.png 1341839135.877808 depth/1341839135.877808.png +1341839135.913620 rgb/1341839135.913620.png 1341839135.913634 depth/1341839135.913634.png +1341839135.945920 rgb/1341839135.945920.png 1341839135.947125 depth/1341839135.947125.png +1341839135.981913 rgb/1341839135.981913.png 1341839135.981941 depth/1341839135.981941.png +1341839136.014297 rgb/1341839136.014297.png 1341839136.014341 depth/1341839136.014341.png +1341839136.059226 rgb/1341839136.059226.png 1341839136.062945 depth/1341839136.062945.png +1341839136.120606 rgb/1341839136.120606.png 1341839136.120805 depth/1341839136.120805.png +1341839136.181673 rgb/1341839136.181673.png 1341839136.181696 depth/1341839136.181696.png +1341839136.214507 rgb/1341839136.214507.png 1341839136.215196 depth/1341839136.215196.png +1341839136.249624 rgb/1341839136.249624.png 1341839136.249642 depth/1341839136.249642.png +1341839136.281495 rgb/1341839136.281495.png 1341839136.281541 depth/1341839136.281541.png +1341839136.314066 rgb/1341839136.314066.png 1341839136.314093 depth/1341839136.314093.png +1341839136.349787 rgb/1341839136.349787.png 1341839136.349833 depth/1341839136.349833.png +1341839136.388618 rgb/1341839136.388618.png 1341839136.388647 depth/1341839136.388647.png +1341839136.449733 rgb/1341839136.449733.png 1341839136.449782 depth/1341839136.449782.png +1341839136.481697 rgb/1341839136.481697.png 1341839136.481996 depth/1341839136.481996.png +1341839136.517624 rgb/1341839136.517624.png 1341839136.518264 depth/1341839136.518264.png +1341839136.549505 rgb/1341839136.549505.png 1341839136.549533 depth/1341839136.549533.png +1341839136.581632 rgb/1341839136.581632.png 1341839136.581692 depth/1341839136.581692.png +1341839136.617613 rgb/1341839136.617613.png 1341839136.617621 depth/1341839136.617621.png +1341839136.649571 rgb/1341839136.649571.png 1341839136.649580 depth/1341839136.649580.png +1341839136.685554 rgb/1341839136.685554.png 1341839136.685653 depth/1341839136.685653.png +1341839136.717527 rgb/1341839136.717527.png 1341839136.717542 depth/1341839136.717542.png +1341839136.749496 rgb/1341839136.749496.png 1341839136.749506 depth/1341839136.749506.png +1341839136.785674 rgb/1341839136.785674.png 1341839136.785703 depth/1341839136.785703.png +1341839136.817542 rgb/1341839136.817542.png 1341839136.817555 depth/1341839136.817555.png +1341839136.849615 rgb/1341839136.849615.png 1341839136.849622 depth/1341839136.849622.png +1341839136.892657 rgb/1341839136.892657.png 1341839136.892705 depth/1341839136.892705.png +1341839136.953615 rgb/1341839136.953615.png 1341839136.953652 depth/1341839136.953652.png +1341839136.985942 rgb/1341839136.985942.png 1341839136.986038 depth/1341839136.986038.png +1341839137.017616 rgb/1341839137.017616.png 1341839137.017720 depth/1341839137.017720.png +1341839137.053572 rgb/1341839137.053572.png 1341839137.053657 depth/1341839137.053657.png +1341839137.085843 rgb/1341839137.085843.png 1341839137.086406 depth/1341839137.086406.png +1341839137.117537 rgb/1341839137.117537.png 1341839137.117619 depth/1341839137.117619.png +1341839137.153707 rgb/1341839137.153707.png 1341839137.153722 depth/1341839137.153722.png +1341839137.186296 rgb/1341839137.186296.png 1341839137.186313 depth/1341839137.186313.png +1341839137.221759 rgb/1341839137.221759.png 1341839137.221832 depth/1341839137.221832.png +1341839137.253565 rgb/1341839137.253565.png 1341839137.253576 depth/1341839137.253576.png +1341839137.285736 rgb/1341839137.285736.png 1341839137.285764 depth/1341839137.285764.png +1341839137.321642 rgb/1341839137.321642.png 1341839137.321686 depth/1341839137.321686.png +1341839137.353692 rgb/1341839137.353692.png 1341839137.353712 depth/1341839137.353712.png +1341839137.386256 rgb/1341839137.386256.png 1341839137.386271 depth/1341839137.386271.png +1341839137.421671 rgb/1341839137.421671.png 1341839137.421704 depth/1341839137.421704.png +1341839137.453657 rgb/1341839137.453657.png 1341839137.453673 depth/1341839137.453673.png +1341839137.489830 rgb/1341839137.489830.png 1341839137.490198 depth/1341839137.490198.png +1341839137.521652 rgb/1341839137.521652.png 1341839137.522084 depth/1341839137.522084.png +1341839137.553558 rgb/1341839137.553558.png 1341839137.553568 depth/1341839137.553568.png +1341839137.592577 rgb/1341839137.592577.png 1341839137.592649 depth/1341839137.592649.png +1341839137.628551 rgb/1341839137.628551.png 1341839137.628567 depth/1341839137.628567.png +1341839137.660598 rgb/1341839137.660598.png 1341839137.660617 depth/1341839137.660617.png +1341839137.692612 rgb/1341839137.692612.png 1341839137.692623 depth/1341839137.692623.png +1341839137.728532 rgb/1341839137.728532.png 1341839137.728545 depth/1341839137.728545.png +1341839137.760497 rgb/1341839137.760497.png 1341839137.760532 depth/1341839137.760532.png +1341839137.796681 rgb/1341839137.796681.png 1341839137.797171 depth/1341839137.797171.png +1341839137.828611 rgb/1341839137.828611.png 1341839137.828636 depth/1341839137.828636.png +1341839137.860523 rgb/1341839137.860523.png 1341839137.860532 depth/1341839137.860532.png +1341839137.896603 rgb/1341839137.896603.png 1341839137.896632 depth/1341839137.896632.png +1341839137.928510 rgb/1341839137.928510.png 1341839137.928525 depth/1341839137.928525.png +1341839137.964534 rgb/1341839137.964534.png 1341839137.964556 depth/1341839137.964556.png +1341839137.996524 rgb/1341839137.996524.png 1341839137.996611 depth/1341839137.996611.png +1341839138.028640 rgb/1341839138.028640.png 1341839138.028652 depth/1341839138.028652.png +1341839138.064541 rgb/1341839138.064541.png 1341839138.064555 depth/1341839138.064555.png +1341839138.096479 rgb/1341839138.096479.png 1341839138.096493 depth/1341839138.096493.png +1341839138.132550 rgb/1341839138.132550.png 1341839138.132565 depth/1341839138.132565.png +1341839138.164623 rgb/1341839138.164623.png 1341839138.164634 depth/1341839138.164634.png +1341839138.196431 rgb/1341839138.196431.png 1341839138.196452 depth/1341839138.196452.png +1341839138.232704 rgb/1341839138.232704.png 1341839138.232713 depth/1341839138.232713.png +1341839138.264578 rgb/1341839138.264578.png 1341839138.264590 depth/1341839138.264590.png +1341839138.300697 rgb/1341839138.300697.png 1341839138.300786 depth/1341839138.300786.png +1341839138.332541 rgb/1341839138.332541.png 1341839138.332563 depth/1341839138.332563.png +1341839138.364517 rgb/1341839138.364517.png 1341839138.364600 depth/1341839138.364600.png +1341839138.400834 rgb/1341839138.400834.png 1341839138.400865 depth/1341839138.400865.png +1341839138.432562 rgb/1341839138.432562.png 1341839138.432578 depth/1341839138.432578.png +1341839138.469017 rgb/1341839138.469017.png 1341839138.469050 depth/1341839138.469050.png +1341839138.500623 rgb/1341839138.500623.png 1341839138.500638 depth/1341839138.500638.png +1341839138.532584 rgb/1341839138.532584.png 1341839138.532604 depth/1341839138.532604.png +1341839138.568521 rgb/1341839138.568521.png 1341839138.568539 depth/1341839138.568539.png +1341839138.600559 rgb/1341839138.600559.png 1341839138.600568 depth/1341839138.600568.png +1341839138.637679 rgb/1341839138.637679.png 1341839138.637699 depth/1341839138.637699.png +1341839138.668579 rgb/1341839138.668579.png 1341839138.668589 depth/1341839138.668589.png +1341839138.700570 rgb/1341839138.700570.png 1341839138.700581 depth/1341839138.700581.png +1341839138.736618 rgb/1341839138.736618.png 1341839138.736629 depth/1341839138.736629.png +1341839138.768580 rgb/1341839138.768580.png 1341839138.768589 depth/1341839138.768589.png +1341839138.800591 rgb/1341839138.800591.png 1341839138.800600 depth/1341839138.800600.png +1341839138.836668 rgb/1341839138.836668.png 1341839138.836676 depth/1341839138.836676.png +1341839138.868631 rgb/1341839138.868631.png 1341839138.868645 depth/1341839138.868645.png +1341839138.900591 rgb/1341839138.900591.png 1341839138.900602 depth/1341839138.900602.png +1341839138.936751 rgb/1341839138.936751.png 1341839138.936770 depth/1341839138.936770.png +1341839138.968925 rgb/1341839138.968925.png 1341839138.968948 depth/1341839138.968948.png +1341839139.004685 rgb/1341839139.004685.png 1341839139.004813 depth/1341839139.004813.png +1341839139.036835 rgb/1341839139.036835.png 1341839139.036847 depth/1341839139.036847.png +1341839139.069010 rgb/1341839139.069010.png 1341839139.070300 depth/1341839139.070300.png +1341839139.105164 rgb/1341839139.105164.png 1341839139.106306 depth/1341839139.106306.png +1341839139.137964 rgb/1341839139.137964.png 1341839139.138489 depth/1341839139.138489.png +1341839139.168993 rgb/1341839139.168993.png 1341839139.169907 depth/1341839139.169907.png +1341839139.208632 rgb/1341839139.208632.png 1341839139.209438 depth/1341839139.209438.png +1341839139.237233 rgb/1341839139.237233.png 1341839139.238326 depth/1341839139.238326.png +1341839139.269740 rgb/1341839139.269740.png 1341839139.271376 depth/1341839139.271376.png +1341839139.305090 rgb/1341839139.305090.png 1341839139.305552 depth/1341839139.305552.png +1341839139.336872 rgb/1341839139.336872.png 1341839139.337515 depth/1341839139.337515.png +1341839139.404779 rgb/1341839139.404779.png 1341839139.405486 depth/1341839139.405486.png +1341839139.436967 rgb/1341839139.436967.png 1341839139.437404 depth/1341839139.437404.png +1341839139.479384 rgb/1341839139.479384.png 1341839139.480479 depth/1341839139.480479.png +1341839139.504961 rgb/1341839139.504961.png 1341839139.505005 depth/1341839139.505005.png +1341839139.572716 rgb/1341839139.572716.png 1341839139.572945 depth/1341839139.572945.png +1341839139.633776 rgb/1341839139.633776.png 1341839139.633799 depth/1341839139.633799.png +1341839139.665625 rgb/1341839139.665625.png 1341839139.665653 depth/1341839139.665653.png +1341839139.701587 rgb/1341839139.701587.png 1341839139.701596 depth/1341839139.701596.png +1341839139.733553 rgb/1341839139.733553.png 1341839139.733611 depth/1341839139.733611.png +1341839139.765553 rgb/1341839139.765553.png 1341839139.765574 depth/1341839139.765574.png +1341839139.801543 rgb/1341839139.801543.png 1341839139.801605 depth/1341839139.801605.png +1341839139.833756 rgb/1341839139.833756.png 1341839139.833768 depth/1341839139.833768.png +1341839139.865591 rgb/1341839139.865591.png 1341839139.865601 depth/1341839139.865601.png +1341839139.901631 rgb/1341839139.901631.png 1341839139.901643 depth/1341839139.901643.png +1341839139.933716 rgb/1341839139.933716.png 1341839139.933753 depth/1341839139.933753.png +1341839139.969603 rgb/1341839139.969603.png 1341839139.969635 depth/1341839139.969635.png +1341839140.001567 rgb/1341839140.001567.png 1341839140.001587 depth/1341839140.001587.png +1341839140.033569 rgb/1341839140.033569.png 1341839140.033598 depth/1341839140.033598.png +1341839140.069602 rgb/1341839140.069602.png 1341839140.069614 depth/1341839140.069614.png +1341839140.101607 rgb/1341839140.101607.png 1341839140.101621 depth/1341839140.101621.png +1341839140.137593 rgb/1341839140.137593.png 1341839140.137615 depth/1341839140.137615.png +1341839140.169583 rgb/1341839140.169583.png 1341839140.169652 depth/1341839140.169652.png +1341839140.201678 rgb/1341839140.201678.png 1341839140.201687 depth/1341839140.201687.png +1341839140.237641 rgb/1341839140.237641.png 1341839140.238134 depth/1341839140.238134.png +1341839140.269632 rgb/1341839140.269632.png 1341839140.269703 depth/1341839140.269703.png +1341839140.301538 rgb/1341839140.301538.png 1341839140.301552 depth/1341839140.301552.png +1341839140.337608 rgb/1341839140.337608.png 1341839140.338185 depth/1341839140.338185.png +1341839140.369503 rgb/1341839140.369503.png 1341839140.369514 depth/1341839140.369514.png +1341839140.405652 rgb/1341839140.405652.png 1341839140.405699 depth/1341839140.405699.png +1341839140.437622 rgb/1341839140.437622.png 1341839140.437643 depth/1341839140.437643.png +1341839140.469802 rgb/1341839140.469802.png 1341839140.469827 depth/1341839140.469827.png +1341839140.505600 rgb/1341839140.505600.png 1341839140.505608 depth/1341839140.505608.png +1341839140.537508 rgb/1341839140.537508.png 1341839140.537516 depth/1341839140.537516.png +1341839140.569631 rgb/1341839140.569631.png 1341839140.569669 depth/1341839140.569669.png +1341839140.605614 rgb/1341839140.605614.png 1341839140.605628 depth/1341839140.605628.png +1341839140.637520 rgb/1341839140.637520.png 1341839140.637540 depth/1341839140.637540.png +1341839140.673589 rgb/1341839140.673589.png 1341839140.673608 depth/1341839140.673608.png +1341839140.705526 rgb/1341839140.705526.png 1341839140.705539 depth/1341839140.705539.png +1341839140.737690 rgb/1341839140.737690.png 1341839140.737704 depth/1341839140.737704.png +1341839140.780691 rgb/1341839140.780691.png 1341839140.780735 depth/1341839140.780735.png +1341839140.837561 rgb/1341839140.837561.png 1341839140.837578 depth/1341839140.837578.png +1341839140.873616 rgb/1341839140.873616.png 1341839140.873620 depth/1341839140.873620.png +1341839140.905496 rgb/1341839140.905496.png 1341839140.905503 depth/1341839140.905503.png +1341839140.941764 rgb/1341839140.941764.png 1341839140.941788 depth/1341839140.941788.png +1341839140.973483 rgb/1341839140.973483.png 1341839140.973496 depth/1341839140.973496.png +1341839141.005687 rgb/1341839141.005687.png 1341839141.005702 depth/1341839141.005702.png +1341839141.041564 rgb/1341839141.041564.png 1341839141.041580 depth/1341839141.041580.png +1341839141.074063 rgb/1341839141.074063.png 1341839141.074113 depth/1341839141.074113.png +1341839141.110271 rgb/1341839141.110271.png 1341839141.111227 depth/1341839141.111227.png +1341839141.141854 rgb/1341839141.141854.png 1341839141.143041 depth/1341839141.143041.png +1341839141.176858 rgb/1341839141.176858.png 1341839141.178116 depth/1341839141.178116.png +1341839141.209658 rgb/1341839141.209658.png 1341839141.210052 depth/1341839141.210052.png +1341839141.241623 rgb/1341839141.241623.png 1341839141.241640 depth/1341839141.241640.png +1341839141.273659 rgb/1341839141.273659.png 1341839141.273677 depth/1341839141.273677.png +1341839141.309576 rgb/1341839141.309576.png 1341839141.309585 depth/1341839141.309585.png +1341839141.341687 rgb/1341839141.341687.png 1341839141.341778 depth/1341839141.341778.png +1341839141.378026 rgb/1341839141.378026.png 1341839141.378158 depth/1341839141.378158.png +1341839141.409623 rgb/1341839141.409623.png 1341839141.409665 depth/1341839141.409665.png +1341839141.441571 rgb/1341839141.441571.png 1341839141.441583 depth/1341839141.441583.png +1341839141.477635 rgb/1341839141.477635.png 1341839141.477651 depth/1341839141.477651.png +1341839141.509696 rgb/1341839141.509696.png 1341839141.509729 depth/1341839141.509729.png +1341839141.541659 rgb/1341839141.541659.png 1341839141.541710 depth/1341839141.541710.png +1341839141.577526 rgb/1341839141.577526.png 1341839141.577573 depth/1341839141.577573.png +1341839141.645706 rgb/1341839141.645706.png 1341839141.645797 depth/1341839141.645797.png +1341839141.677487 rgb/1341839141.677487.png 1341839141.677499 depth/1341839141.677499.png +1341839141.709572 rgb/1341839141.709572.png 1341839141.709590 depth/1341839141.709590.png +1341839141.745638 rgb/1341839141.745638.png 1341839141.745654 depth/1341839141.745654.png +1341839141.777895 rgb/1341839141.777895.png 1341839141.778356 depth/1341839141.778356.png +1341839141.809561 rgb/1341839141.809561.png 1341839141.809573 depth/1341839141.809573.png +1341839141.845701 rgb/1341839141.845701.png 1341839141.845720 depth/1341839141.845720.png +1341839141.877530 rgb/1341839141.877530.png 1341839141.877549 depth/1341839141.877549.png +1341839141.913569 rgb/1341839141.913569.png 1341839141.913591 depth/1341839141.913591.png +1341839141.945636 rgb/1341839141.945636.png 1341839141.945649 depth/1341839141.945649.png +1341839141.977668 rgb/1341839141.977668.png 1341839141.977695 depth/1341839141.977695.png +1341839142.013466 rgb/1341839142.013466.png 1341839142.013492 depth/1341839142.013492.png +1341839142.048866 rgb/1341839142.048866.png 1341839142.048888 depth/1341839142.048888.png +1341839142.116693 rgb/1341839142.116693.png 1341839142.116751 depth/1341839142.116751.png +1341839142.181588 rgb/1341839142.181588.png 1341839142.181631 depth/1341839142.181631.png +1341839142.213523 rgb/1341839142.213523.png 1341839142.213533 depth/1341839142.213533.png +1341839142.245657 rgb/1341839142.245657.png 1341839142.245678 depth/1341839142.245678.png +1341839142.281484 rgb/1341839142.281484.png 1341839142.281493 depth/1341839142.281493.png +1341839142.313501 rgb/1341839142.313501.png 1341839142.313509 depth/1341839142.313509.png +1341839142.349595 rgb/1341839142.349595.png 1341839142.349620 depth/1341839142.349620.png +1341839142.413736 rgb/1341839142.413736.png 1341839142.413767 depth/1341839142.413767.png +1341839142.449600 rgb/1341839142.449600.png 1341839142.449618 depth/1341839142.449618.png +1341839142.481586 rgb/1341839142.481586.png 1341839142.481606 depth/1341839142.481606.png +1341839142.513495 rgb/1341839142.513495.png 1341839142.513509 depth/1341839142.513509.png +1341839142.549621 rgb/1341839142.549621.png 1341839142.549634 depth/1341839142.549634.png +1341839142.581646 rgb/1341839142.581646.png 1341839142.582088 depth/1341839142.582088.png +1341839142.617733 rgb/1341839142.617733.png 1341839142.618319 depth/1341839142.618319.png +1341839142.649501 rgb/1341839142.649501.png 1341839142.649517 depth/1341839142.649517.png +1341839142.681490 rgb/1341839142.681490.png 1341839142.681506 depth/1341839142.681506.png +1341839142.717648 rgb/1341839142.717648.png 1341839142.717673 depth/1341839142.717673.png +1341839142.749655 rgb/1341839142.749655.png 1341839142.750498 depth/1341839142.750498.png +1341839142.781698 rgb/1341839142.781698.png 1341839142.781971 depth/1341839142.781971.png +1341839142.817748 rgb/1341839142.817748.png 1341839142.817777 depth/1341839142.817777.png +1341839142.849646 rgb/1341839142.849646.png 1341839142.849670 depth/1341839142.849670.png +1341839142.885615 rgb/1341839142.885615.png 1341839142.885630 depth/1341839142.885630.png +1341839142.917485 rgb/1341839142.917485.png 1341839142.917510 depth/1341839142.917510.png +1341839142.949726 rgb/1341839142.949726.png 1341839142.949748 depth/1341839142.949748.png +1341839142.985900 rgb/1341839142.985900.png 1341839142.985931 depth/1341839142.985931.png +1341839143.025376 rgb/1341839143.025376.png 1341839143.026222 depth/1341839143.026222.png +1341839143.056750 rgb/1341839143.056750.png 1341839143.056780 depth/1341839143.056780.png +1341839143.092610 rgb/1341839143.092610.png 1341839143.092659 depth/1341839143.092659.png +1341839143.124560 rgb/1341839143.124560.png 1341839143.124570 depth/1341839143.124570.png +1341839143.160701 rgb/1341839143.160701.png 1341839143.161188 depth/1341839143.161188.png +1341839143.224815 rgb/1341839143.224815.png 1341839143.224874 depth/1341839143.224874.png +1341839143.285789 rgb/1341839143.285789.png 1341839143.285858 depth/1341839143.285858.png +1341839143.321671 rgb/1341839143.321671.png 1341839143.321694 depth/1341839143.321694.png +1341839143.353517 rgb/1341839143.353517.png 1341839143.353534 depth/1341839143.353534.png +1341839143.385603 rgb/1341839143.385603.png 1341839143.385625 depth/1341839143.385625.png +1341839143.421529 rgb/1341839143.421529.png 1341839143.421572 depth/1341839143.421572.png +1341839143.453645 rgb/1341839143.453645.png 1341839143.453688 depth/1341839143.453688.png +1341839143.485734 rgb/1341839143.485734.png 1341839143.485756 depth/1341839143.485756.png +1341839143.521668 rgb/1341839143.521668.png 1341839143.521684 depth/1341839143.521684.png +1341839143.553630 rgb/1341839143.553630.png 1341839143.553660 depth/1341839143.553660.png +1341839143.590154 rgb/1341839143.590154.png 1341839143.590166 depth/1341839143.590166.png +1341839143.621854 rgb/1341839143.621854.png 1341839143.621867 depth/1341839143.621867.png +1341839143.653546 rgb/1341839143.653546.png 1341839143.653560 depth/1341839143.653560.png +1341839143.689669 rgb/1341839143.689669.png 1341839143.689685 depth/1341839143.689685.png +1341839143.721563 rgb/1341839143.721563.png 1341839143.721578 depth/1341839143.721578.png +1341839143.753557 rgb/1341839143.753557.png 1341839143.753575 depth/1341839143.753575.png +1341839143.789597 rgb/1341839143.789597.png 1341839143.789627 depth/1341839143.789627.png +1341839143.821488 rgb/1341839143.821488.png 1341839143.821505 depth/1341839143.821505.png +1341839143.857691 rgb/1341839143.857691.png 1341839143.857712 depth/1341839143.857712.png +1341839143.889668 rgb/1341839143.889668.png 1341839143.889711 depth/1341839143.889711.png +1341839143.921613 rgb/1341839143.921613.png 1341839143.921625 depth/1341839143.921625.png +1341839143.957679 rgb/1341839143.957679.png 1341839143.957695 depth/1341839143.957695.png +1341839143.989692 rgb/1341839143.989692.png 1341839143.989707 depth/1341839143.989707.png +1341839144.021612 rgb/1341839144.021612.png 1341839144.021623 depth/1341839144.021623.png +1341839144.057581 rgb/1341839144.057581.png 1341839144.057682 depth/1341839144.057682.png +1341839144.089682 rgb/1341839144.089682.png 1341839144.090414 depth/1341839144.090414.png +1341839144.125588 rgb/1341839144.125588.png 1341839144.125627 depth/1341839144.125627.png +1341839144.157579 rgb/1341839144.157579.png 1341839144.157593 depth/1341839144.157593.png +1341839144.189633 rgb/1341839144.189633.png 1341839144.189686 depth/1341839144.189686.png +1341839144.225642 rgb/1341839144.225642.png 1341839144.225712 depth/1341839144.225712.png +1341839144.257760 rgb/1341839144.257760.png 1341839144.257782 depth/1341839144.257782.png +1341839144.289779 rgb/1341839144.289779.png 1341839144.289825 depth/1341839144.289825.png +1341839144.325641 rgb/1341839144.325641.png 1341839144.325658 depth/1341839144.325658.png +1341839144.357603 rgb/1341839144.357603.png 1341839144.357629 depth/1341839144.357629.png +1341839144.393630 rgb/1341839144.393630.png 1341839144.393670 depth/1341839144.393670.png +1341839144.425526 rgb/1341839144.425526.png 1341839144.425538 depth/1341839144.425538.png +1341839144.457696 rgb/1341839144.457696.png 1341839144.458734 depth/1341839144.458734.png +1341839144.493799 rgb/1341839144.493799.png 1341839144.493809 depth/1341839144.493809.png +1341839144.525996 rgb/1341839144.525996.png 1341839144.526031 depth/1341839144.526031.png +1341839144.561696 rgb/1341839144.561696.png 1341839144.561705 depth/1341839144.561705.png +1341839144.593602 rgb/1341839144.593602.png 1341839144.594287 depth/1341839144.594287.png +1341839144.627771 rgb/1341839144.627771.png 1341839144.627802 depth/1341839144.627802.png +1341839144.661818 rgb/1341839144.661818.png 1341839144.663741 depth/1341839144.663741.png +1341839144.732548 rgb/1341839144.732548.png 1341839144.732583 depth/1341839144.732583.png +1341839144.793602 rgb/1341839144.793602.png 1341839144.793614 depth/1341839144.793614.png +1341839144.829602 rgb/1341839144.829602.png 1341839144.829617 depth/1341839144.829617.png +1341839144.861614 rgb/1341839144.861614.png 1341839144.861628 depth/1341839144.861628.png +1341839144.893704 rgb/1341839144.893704.png 1341839144.893753 depth/1341839144.893753.png +1341839144.929498 rgb/1341839144.929498.png 1341839144.929511 depth/1341839144.929511.png +1341839144.961563 rgb/1341839144.961563.png 1341839144.961580 depth/1341839144.961580.png +1341839144.993581 rgb/1341839144.993581.png 1341839144.993599 depth/1341839144.993599.png +1341839145.029623 rgb/1341839145.029623.png 1341839145.029664 depth/1341839145.029664.png +1341839145.061626 rgb/1341839145.061626.png 1341839145.061641 depth/1341839145.061641.png +1341839145.097529 rgb/1341839145.097529.png 1341839145.097551 depth/1341839145.097551.png +1341839145.129540 rgb/1341839145.129540.png 1341839145.129551 depth/1341839145.129551.png +1341839145.161548 rgb/1341839145.161548.png 1341839145.161615 depth/1341839145.161615.png +1341839145.197472 rgb/1341839145.197472.png 1341839145.197504 depth/1341839145.197504.png +1341839145.229600 rgb/1341839145.229600.png 1341839145.230231 depth/1341839145.230231.png +1341839145.262518 rgb/1341839145.262518.png 1341839145.262530 depth/1341839145.262530.png +1341839145.297552 rgb/1341839145.297552.png 1341839145.297620 depth/1341839145.297620.png +1341839145.329591 rgb/1341839145.329591.png 1341839145.329622 depth/1341839145.329622.png diff --git a/Examples/RGB-D/associations/fr3_str_tex_near.txt b/Examples/RGB-D/associations/fr3_str_tex_near.txt new file mode 100644 index 0000000000..7cd13ab122 --- /dev/null +++ b/Examples/RGB-D/associations/fr3_str_tex_near.txt @@ -0,0 +1,1057 @@ +1341839327.392692 rgb/1341839327.392692.png 1341839327.392719 depth/1341839327.392719.png +1341839327.424683 rgb/1341839327.424683.png 1341839327.424732 depth/1341839327.424732.png +1341839327.460744 rgb/1341839327.460744.png 1341839327.460763 depth/1341839327.460763.png +1341839327.492713 rgb/1341839327.492713.png 1341839327.492724 depth/1341839327.492724.png +1341839327.524801 rgb/1341839327.524801.png 1341839327.524824 depth/1341839327.524824.png +1341839327.560844 rgb/1341839327.560844.png 1341839327.560867 depth/1341839327.560867.png +1341839327.592601 rgb/1341839327.592601.png 1341839327.592616 depth/1341839327.592616.png +1341839327.624910 rgb/1341839327.624910.png 1341839327.625438 depth/1341839327.625438.png +1341839327.660734 rgb/1341839327.660734.png 1341839327.660773 depth/1341839327.660773.png +1341839327.692726 rgb/1341839327.692726.png 1341839327.693149 depth/1341839327.693149.png +1341839327.728746 rgb/1341839327.728746.png 1341839327.728770 depth/1341839327.728770.png +1341839327.760684 rgb/1341839327.760684.png 1341839327.760693 depth/1341839327.760693.png +1341839327.792848 rgb/1341839327.792848.png 1341839327.792870 depth/1341839327.792870.png +1341839327.828735 rgb/1341839327.828735.png 1341839327.828764 depth/1341839327.828764.png +1341839327.860775 rgb/1341839327.860775.png 1341839327.861088 depth/1341839327.861088.png +1341839327.892707 rgb/1341839327.892707.png 1341839327.892736 depth/1341839327.892736.png +1341839327.928885 rgb/1341839327.928885.png 1341839327.928913 depth/1341839327.928913.png +1341839327.960681 rgb/1341839327.960681.png 1341839327.960709 depth/1341839327.960709.png +1341839327.992694 rgb/1341839327.992694.png 1341839327.993314 depth/1341839327.993314.png +1341839328.028635 rgb/1341839328.028635.png 1341839328.028650 depth/1341839328.028650.png +1341839328.060669 rgb/1341839328.060669.png 1341839328.060694 depth/1341839328.060694.png +1341839328.096628 rgb/1341839328.096628.png 1341839328.096649 depth/1341839328.096649.png +1341839328.128788 rgb/1341839328.128788.png 1341839328.128874 depth/1341839328.128874.png +1341839328.160826 rgb/1341839328.160826.png 1341839328.160854 depth/1341839328.160854.png +1341839328.196725 rgb/1341839328.196725.png 1341839328.196745 depth/1341839328.196745.png +1341839328.228674 rgb/1341839328.228674.png 1341839328.229156 depth/1341839328.229156.png +1341839328.260676 rgb/1341839328.260676.png 1341839328.261208 depth/1341839328.261208.png +1341839328.296667 rgb/1341839328.296667.png 1341839328.297137 depth/1341839328.297137.png +1341839328.328755 rgb/1341839328.328755.png 1341839328.328784 depth/1341839328.328784.png +1341839328.360635 rgb/1341839328.360635.png 1341839328.360665 depth/1341839328.360665.png +1341839328.396819 rgb/1341839328.396819.png 1341839328.396926 depth/1341839328.396926.png +1341839328.428710 rgb/1341839328.428710.png 1341839328.429370 depth/1341839328.429370.png +1341839328.464835 rgb/1341839328.464835.png 1341839328.464846 depth/1341839328.464846.png +1341839328.496659 rgb/1341839328.496659.png 1341839328.496692 depth/1341839328.496692.png +1341839328.528673 rgb/1341839328.528673.png 1341839328.528687 depth/1341839328.528687.png +1341839328.564728 rgb/1341839328.564728.png 1341839328.564740 depth/1341839328.564740.png +1341839328.625878 rgb/1341839328.625878.png 1341839328.625940 depth/1341839328.625940.png +1341839328.657644 rgb/1341839328.657644.png 1341839328.657766 depth/1341839328.657766.png +1341839328.693566 rgb/1341839328.693566.png 1341839328.693593 depth/1341839328.693593.png +1341839328.725884 rgb/1341839328.725884.png 1341839328.726559 depth/1341839328.726559.png +1341839328.757668 rgb/1341839328.757668.png 1341839328.757898 depth/1341839328.757898.png +1341839328.793500 rgb/1341839328.793500.png 1341839328.793518 depth/1341839328.793518.png +1341839328.826689 rgb/1341839328.826689.png 1341839328.826770 depth/1341839328.826770.png +1341839328.861628 rgb/1341839328.861628.png 1341839328.861644 depth/1341839328.861644.png +1341839328.893838 rgb/1341839328.893838.png 1341839328.893849 depth/1341839328.893849.png +1341839328.925828 rgb/1341839328.925828.png 1341839328.925868 depth/1341839328.925868.png +1341839328.961597 rgb/1341839328.961597.png 1341839328.961613 depth/1341839328.961613.png +1341839328.993736 rgb/1341839328.993736.png 1341839328.993792 depth/1341839328.993792.png +1341839329.026046 rgb/1341839329.026046.png 1341839329.026055 depth/1341839329.026055.png +1341839329.061681 rgb/1341839329.061681.png 1341839329.062092 depth/1341839329.062092.png +1341839329.093651 rgb/1341839329.093651.png 1341839329.093661 depth/1341839329.093661.png +1341839329.129705 rgb/1341839329.129705.png 1341839329.129714 depth/1341839329.129714.png +1341839329.161766 rgb/1341839329.161766.png 1341839329.161805 depth/1341839329.161805.png +1341839329.193630 rgb/1341839329.193630.png 1341839329.193646 depth/1341839329.193646.png +1341839329.229958 rgb/1341839329.229958.png 1341839329.229989 depth/1341839329.229989.png +1341839329.261621 rgb/1341839329.261621.png 1341839329.261633 depth/1341839329.261633.png +1341839329.293826 rgb/1341839329.293826.png 1341839329.294019 depth/1341839329.294019.png +1341839329.330161 rgb/1341839329.330161.png 1341839329.330182 depth/1341839329.330182.png +1341839329.361576 rgb/1341839329.361576.png 1341839329.361588 depth/1341839329.361588.png +1341839329.397677 rgb/1341839329.397677.png 1341839329.397693 depth/1341839329.397693.png +1341839329.429794 rgb/1341839329.429794.png 1341839329.429824 depth/1341839329.429824.png +1341839329.462095 rgb/1341839329.462095.png 1341839329.462140 depth/1341839329.462140.png +1341839329.497776 rgb/1341839329.497776.png 1341839329.497817 depth/1341839329.497817.png +1341839329.529609 rgb/1341839329.529609.png 1341839329.529623 depth/1341839329.529623.png +1341839329.565820 rgb/1341839329.565820.png 1341839329.565832 depth/1341839329.565832.png +1341839329.597604 rgb/1341839329.597604.png 1341839329.597657 depth/1341839329.597657.png +1341839329.629668 rgb/1341839329.629668.png 1341839329.629682 depth/1341839329.629682.png +1341839329.665800 rgb/1341839329.665800.png 1341839329.665817 depth/1341839329.665817.png +1341839329.697644 rgb/1341839329.697644.png 1341839329.697655 depth/1341839329.697655.png +1341839329.729773 rgb/1341839329.729773.png 1341839329.729794 depth/1341839329.729794.png +1341839329.765624 rgb/1341839329.765624.png 1341839329.765645 depth/1341839329.765645.png +1341839329.797643 rgb/1341839329.797643.png 1341839329.797665 depth/1341839329.797665.png +1341839329.833722 rgb/1341839329.833722.png 1341839329.833742 depth/1341839329.833742.png +1341839329.865810 rgb/1341839329.865810.png 1341839329.865832 depth/1341839329.865832.png +1341839329.897566 rgb/1341839329.897566.png 1341839329.897578 depth/1341839329.897578.png +1341839329.933593 rgb/1341839329.933593.png 1341839329.933601 depth/1341839329.933601.png +1341839329.965703 rgb/1341839329.965703.png 1341839329.965721 depth/1341839329.965721.png +1341839329.997622 rgb/1341839329.997622.png 1341839329.997659 depth/1341839329.997659.png +1341839330.033691 rgb/1341839330.033691.png 1341839330.033740 depth/1341839330.033740.png +1341839330.065682 rgb/1341839330.065682.png 1341839330.065737 depth/1341839330.065737.png +1341839330.101720 rgb/1341839330.101720.png 1341839330.101744 depth/1341839330.101744.png +1341839330.133799 rgb/1341839330.133799.png 1341839330.133824 depth/1341839330.133824.png +1341839330.165594 rgb/1341839330.165594.png 1341839330.165634 depth/1341839330.165634.png +1341839330.201660 rgb/1341839330.201660.png 1341839330.201705 depth/1341839330.201705.png +1341839330.233709 rgb/1341839330.233709.png 1341839330.233722 depth/1341839330.233722.png +1341839330.265739 rgb/1341839330.265739.png 1341839330.266312 depth/1341839330.266312.png +1341839330.301821 rgb/1341839330.301821.png 1341839330.302347 depth/1341839330.302347.png +1341839330.333763 rgb/1341839330.333763.png 1341839330.333775 depth/1341839330.333775.png +1341839330.369586 rgb/1341839330.369586.png 1341839330.369606 depth/1341839330.369606.png +1341839330.401592 rgb/1341839330.401592.png 1341839330.401603 depth/1341839330.401603.png +1341839330.433755 rgb/1341839330.433755.png 1341839330.433788 depth/1341839330.433788.png +1341839330.469655 rgb/1341839330.469655.png 1341839330.469667 depth/1341839330.469667.png +1341839330.501951 rgb/1341839330.501951.png 1341839330.501975 depth/1341839330.501975.png +1341839330.533811 rgb/1341839330.533811.png 1341839330.533857 depth/1341839330.533857.png +1341839330.569658 rgb/1341839330.569658.png 1341839330.569675 depth/1341839330.569675.png +1341839330.601587 rgb/1341839330.601587.png 1341839330.601595 depth/1341839330.601595.png +1341839330.637700 rgb/1341839330.637700.png 1341839330.638143 depth/1341839330.638143.png +1341839330.669658 rgb/1341839330.669658.png 1341839330.669672 depth/1341839330.669672.png +1341839330.701704 rgb/1341839330.701704.png 1341839330.701788 depth/1341839330.701788.png +1341839330.737621 rgb/1341839330.737621.png 1341839330.737650 depth/1341839330.737650.png +1341839330.769669 rgb/1341839330.769669.png 1341839330.769683 depth/1341839330.769683.png +1341839330.805848 rgb/1341839330.805848.png 1341839330.805857 depth/1341839330.805857.png +1341839330.837580 rgb/1341839330.837580.png 1341839330.837591 depth/1341839330.837591.png +1341839330.869617 rgb/1341839330.869617.png 1341839330.869625 depth/1341839330.869625.png +1341839330.905589 rgb/1341839330.905589.png 1341839330.905598 depth/1341839330.905598.png +1341839330.937600 rgb/1341839330.937600.png 1341839330.937608 depth/1341839330.937608.png +1341839330.969715 rgb/1341839330.969715.png 1341839330.969732 depth/1341839330.969732.png +1341839331.005663 rgb/1341839331.005663.png 1341839331.005686 depth/1341839331.005686.png +1341839331.037575 rgb/1341839331.037575.png 1341839331.037590 depth/1341839331.037590.png +1341839331.073681 rgb/1341839331.073681.png 1341839331.073709 depth/1341839331.073709.png +1341839331.105674 rgb/1341839331.105674.png 1341839331.105691 depth/1341839331.105691.png +1341839331.137723 rgb/1341839331.137723.png 1341839331.137734 depth/1341839331.137734.png +1341839331.173604 rgb/1341839331.173604.png 1341839331.173665 depth/1341839331.173665.png +1341839331.206025 rgb/1341839331.206025.png 1341839331.206108 depth/1341839331.206108.png +1341839331.237569 rgb/1341839331.237569.png 1341839331.237591 depth/1341839331.237591.png +1341839331.273666 rgb/1341839331.273666.png 1341839331.273677 depth/1341839331.273677.png +1341839331.305627 rgb/1341839331.305627.png 1341839331.305666 depth/1341839331.305666.png +1341839331.341607 rgb/1341839331.341607.png 1341839331.341623 depth/1341839331.341623.png +1341839331.373735 rgb/1341839331.373735.png 1341839331.373753 depth/1341839331.373753.png +1341839331.405705 rgb/1341839331.405705.png 1341839331.405723 depth/1341839331.405723.png +1341839331.473794 rgb/1341839331.473794.png 1341839331.473871 depth/1341839331.473871.png +1341839331.505887 rgb/1341839331.505887.png 1341839331.505920 depth/1341839331.505920.png +1341839331.541633 rgb/1341839331.541633.png 1341839331.541699 depth/1341839331.541699.png +1341839331.573588 rgb/1341839331.573588.png 1341839331.573605 depth/1341839331.573605.png +1341839331.609760 rgb/1341839331.609760.png 1341839331.609775 depth/1341839331.609775.png +1341839331.641625 rgb/1341839331.641625.png 1341839331.641636 depth/1341839331.641636.png +1341839331.673616 rgb/1341839331.673616.png 1341839331.673645 depth/1341839331.673645.png +1341839331.709625 rgb/1341839331.709625.png 1341839331.709686 depth/1341839331.709686.png +1341839331.741634 rgb/1341839331.741634.png 1341839331.741643 depth/1341839331.741643.png +1341839331.777583 rgb/1341839331.777583.png 1341839331.777603 depth/1341839331.777603.png +1341839331.809615 rgb/1341839331.809615.png 1341839331.809647 depth/1341839331.809647.png +1341839331.841790 rgb/1341839331.841790.png 1341839331.841801 depth/1341839331.841801.png +1341839331.877680 rgb/1341839331.877680.png 1341839331.878215 depth/1341839331.878215.png +1341839331.909730 rgb/1341839331.909730.png 1341839331.909748 depth/1341839331.909748.png +1341839331.941711 rgb/1341839331.941711.png 1341839331.941725 depth/1341839331.941725.png +1341839331.977710 rgb/1341839331.977710.png 1341839331.977728 depth/1341839331.977728.png +1341839332.045792 rgb/1341839332.045792.png 1341839332.045816 depth/1341839332.045816.png +1341839332.077575 rgb/1341839332.077575.png 1341839332.077582 depth/1341839332.077582.png +1341839332.116871 rgb/1341839332.116871.png 1341839332.116893 depth/1341839332.116893.png +1341839332.152604 rgb/1341839332.152604.png 1341839332.152616 depth/1341839332.152616.png +1341839332.184662 rgb/1341839332.184662.png 1341839332.184678 depth/1341839332.184678.png +1341839332.216752 rgb/1341839332.216752.png 1341839332.216770 depth/1341839332.216770.png +1341839332.252770 rgb/1341839332.252770.png 1341839332.252784 depth/1341839332.252784.png +1341839332.284701 rgb/1341839332.284701.png 1341839332.284720 depth/1341839332.284720.png +1341839332.320752 rgb/1341839332.320752.png 1341839332.320763 depth/1341839332.320763.png +1341839332.352704 rgb/1341839332.352704.png 1341839332.352725 depth/1341839332.352725.png +1341839332.384789 rgb/1341839332.384789.png 1341839332.384802 depth/1341839332.384802.png +1341839332.420694 rgb/1341839332.420694.png 1341839332.420707 depth/1341839332.420707.png +1341839332.453030 rgb/1341839332.453030.png 1341839332.453040 depth/1341839332.453040.png +1341839332.484688 rgb/1341839332.484688.png 1341839332.484707 depth/1341839332.484707.png +1341839332.520706 rgb/1341839332.520706.png 1341839332.520728 depth/1341839332.520728.png +1341839332.552671 rgb/1341839332.552671.png 1341839332.552694 depth/1341839332.552694.png +1341839332.584673 rgb/1341839332.584673.png 1341839332.584689 depth/1341839332.584689.png +1341839332.620880 rgb/1341839332.620880.png 1341839332.620915 depth/1341839332.620915.png +1341839332.652689 rgb/1341839332.652689.png 1341839332.652728 depth/1341839332.652728.png +1341839332.688723 rgb/1341839332.688723.png 1341839332.688741 depth/1341839332.688741.png +1341839332.720653 rgb/1341839332.720653.png 1341839332.720665 depth/1341839332.720665.png +1341839332.752651 rgb/1341839332.752651.png 1341839332.752666 depth/1341839332.752666.png +1341839332.788721 rgb/1341839332.788721.png 1341839332.788766 depth/1341839332.788766.png +1341839332.820842 rgb/1341839332.820842.png 1341839332.820854 depth/1341839332.820854.png +1341839332.852685 rgb/1341839332.852685.png 1341839332.852703 depth/1341839332.852703.png +1341839332.888848 rgb/1341839332.888848.png 1341839332.889321 depth/1341839332.889321.png +1341839332.920995 rgb/1341839332.920995.png 1341839332.921019 depth/1341839332.921019.png +1341839332.952682 rgb/1341839332.952682.png 1341839332.952691 depth/1341839332.952691.png +1341839332.988738 rgb/1341839332.988738.png 1341839332.988751 depth/1341839332.988751.png +1341839333.020623 rgb/1341839333.020623.png 1341839333.020647 depth/1341839333.020647.png +1341839333.056704 rgb/1341839333.056704.png 1341839333.056724 depth/1341839333.056724.png +1341839333.088657 rgb/1341839333.088657.png 1341839333.089114 depth/1341839333.089114.png +1341839333.120706 rgb/1341839333.120706.png 1341839333.120718 depth/1341839333.120718.png +1341839333.156633 rgb/1341839333.156633.png 1341839333.156704 depth/1341839333.156704.png +1341839333.188765 rgb/1341839333.188765.png 1341839333.188815 depth/1341839333.188815.png +1341839333.220616 rgb/1341839333.220616.png 1341839333.220628 depth/1341839333.220628.png +1341839333.256627 rgb/1341839333.256627.png 1341839333.256670 depth/1341839333.256670.png +1341839333.288720 rgb/1341839333.288720.png 1341839333.288740 depth/1341839333.288740.png +1341839333.320582 rgb/1341839333.320582.png 1341839333.320602 depth/1341839333.320602.png +1341839333.356732 rgb/1341839333.356732.png 1341839333.356748 depth/1341839333.356748.png +1341839333.388697 rgb/1341839333.388697.png 1341839333.388710 depth/1341839333.388710.png +1341839333.420710 rgb/1341839333.420710.png 1341839333.420733 depth/1341839333.420733.png +1341839333.456775 rgb/1341839333.456775.png 1341839333.456800 depth/1341839333.456800.png +1341839333.488704 rgb/1341839333.488704.png 1341839333.489161 depth/1341839333.489161.png +1341839333.524711 rgb/1341839333.524711.png 1341839333.524754 depth/1341839333.524754.png +1341839333.556624 rgb/1341839333.556624.png 1341839333.556641 depth/1341839333.556641.png +1341839333.588625 rgb/1341839333.588625.png 1341839333.588635 depth/1341839333.588635.png +1341839333.624629 rgb/1341839333.624629.png 1341839333.624660 depth/1341839333.624660.png +1341839333.656568 rgb/1341839333.656568.png 1341839333.656582 depth/1341839333.656582.png +1341839333.692659 rgb/1341839333.692659.png 1341839333.692674 depth/1341839333.692674.png +1341839333.724668 rgb/1341839333.724668.png 1341839333.724684 depth/1341839333.724684.png +1341839333.756687 rgb/1341839333.756687.png 1341839333.756705 depth/1341839333.756705.png +1341839333.792785 rgb/1341839333.792785.png 1341839333.792811 depth/1341839333.792811.png +1341839333.824592 rgb/1341839333.824592.png 1341839333.824607 depth/1341839333.824607.png +1341839333.860713 rgb/1341839333.860713.png 1341839333.860727 depth/1341839333.860727.png +1341839333.892664 rgb/1341839333.892664.png 1341839333.892675 depth/1341839333.892675.png +1341839333.924772 rgb/1341839333.924772.png 1341839333.924793 depth/1341839333.924793.png +1341839333.960800 rgb/1341839333.960800.png 1341839333.960816 depth/1341839333.960816.png +1341839333.992556 rgb/1341839333.992556.png 1341839333.992565 depth/1341839333.992565.png +1341839334.028677 rgb/1341839334.028677.png 1341839334.028692 depth/1341839334.028692.png +1341839334.060751 rgb/1341839334.060751.png 1341839334.061278 depth/1341839334.061278.png +1341839334.092709 rgb/1341839334.092709.png 1341839334.092728 depth/1341839334.092728.png +1341839334.128631 rgb/1341839334.128631.png 1341839334.128644 depth/1341839334.128644.png +1341839334.160667 rgb/1341839334.160667.png 1341839334.160704 depth/1341839334.160704.png +1341839334.196648 rgb/1341839334.196648.png 1341839334.197146 depth/1341839334.197146.png +1341839334.228784 rgb/1341839334.228784.png 1341839334.228803 depth/1341839334.228803.png +1341839334.260936 rgb/1341839334.260936.png 1341839334.260959 depth/1341839334.260959.png +1341839334.328751 rgb/1341839334.328751.png 1341839334.328809 depth/1341839334.328809.png +1341839334.389793 rgb/1341839334.389793.png 1341839334.389836 depth/1341839334.389836.png +1341839334.421707 rgb/1341839334.421707.png 1341839334.421774 depth/1341839334.421774.png +1341839334.458010 rgb/1341839334.458010.png 1341839334.458070 depth/1341839334.458070.png +1341839334.489685 rgb/1341839334.489685.png 1341839334.489716 depth/1341839334.489716.png +1341839334.525784 rgb/1341839334.525784.png 1341839334.525791 depth/1341839334.525791.png +1341839334.557792 rgb/1341839334.557792.png 1341839334.557800 depth/1341839334.557800.png +1341839334.589872 rgb/1341839334.589872.png 1341839334.589879 depth/1341839334.589879.png +1341839334.625782 rgb/1341839334.625782.png 1341839334.625795 depth/1341839334.625795.png +1341839334.657843 rgb/1341839334.657843.png 1341839334.657857 depth/1341839334.657857.png +1341839334.689637 rgb/1341839334.689637.png 1341839334.689650 depth/1341839334.689650.png +1341839334.725841 rgb/1341839334.725841.png 1341839334.725913 depth/1341839334.725913.png +1341839334.757940 rgb/1341839334.757940.png 1341839334.758001 depth/1341839334.758001.png +1341839334.793688 rgb/1341839334.793688.png 1341839334.794398 depth/1341839334.794398.png +1341839334.826159 rgb/1341839334.826159.png 1341839334.826176 depth/1341839334.826176.png +1341839334.857927 rgb/1341839334.857927.png 1341839334.858001 depth/1341839334.858001.png +1341839334.893837 rgb/1341839334.893837.png 1341839334.893846 depth/1341839334.893846.png +1341839334.925643 rgb/1341839334.925643.png 1341839334.925663 depth/1341839334.925663.png +1341839334.958884 rgb/1341839334.958884.png 1341839334.958897 depth/1341839334.958897.png +1341839334.993773 rgb/1341839334.993773.png 1341839334.993786 depth/1341839334.993786.png +1341839335.025708 rgb/1341839335.025708.png 1341839335.025736 depth/1341839335.025736.png +1341839335.061854 rgb/1341839335.061854.png 1341839335.062376 depth/1341839335.062376.png +1341839335.093687 rgb/1341839335.093687.png 1341839335.093705 depth/1341839335.093705.png +1341839335.125723 rgb/1341839335.125723.png 1341839335.125749 depth/1341839335.125749.png +1341839335.161765 rgb/1341839335.161765.png 1341839335.161801 depth/1341839335.161801.png +1341839335.193620 rgb/1341839335.193620.png 1341839335.193634 depth/1341839335.193634.png +1341839335.229620 rgb/1341839335.229620.png 1341839335.229637 depth/1341839335.229637.png +1341839335.261647 rgb/1341839335.261647.png 1341839335.261672 depth/1341839335.261672.png +1341839335.293594 rgb/1341839335.293594.png 1341839335.293601 depth/1341839335.293601.png +1341839335.330288 rgb/1341839335.330288.png 1341839335.330337 depth/1341839335.330337.png +1341839335.361768 rgb/1341839335.361768.png 1341839335.361795 depth/1341839335.361795.png +1341839335.393779 rgb/1341839335.393779.png 1341839335.393789 depth/1341839335.393789.png +1341839335.429685 rgb/1341839335.429685.png 1341839335.429852 depth/1341839335.429852.png +1341839335.461748 rgb/1341839335.461748.png 1341839335.461797 depth/1341839335.461797.png +1341839335.497763 rgb/1341839335.497763.png 1341839335.497824 depth/1341839335.497824.png +1341839335.529696 rgb/1341839335.529696.png 1341839335.529703 depth/1341839335.529703.png +1341839335.561678 rgb/1341839335.561678.png 1341839335.561688 depth/1341839335.561688.png +1341839335.597774 rgb/1341839335.597774.png 1341839335.597785 depth/1341839335.597785.png +1341839335.629668 rgb/1341839335.629668.png 1341839335.629720 depth/1341839335.629720.png +1341839335.661725 rgb/1341839335.661725.png 1341839335.661751 depth/1341839335.661751.png +1341839335.698267 rgb/1341839335.698267.png 1341839335.698291 depth/1341839335.698291.png +1341839335.729842 rgb/1341839335.729842.png 1341839335.729860 depth/1341839335.729860.png +1341839335.765671 rgb/1341839335.765671.png 1341839335.765694 depth/1341839335.765694.png +1341839335.798008 rgb/1341839335.798008.png 1341839335.798139 depth/1341839335.798139.png +1341839335.829597 rgb/1341839335.829597.png 1341839335.829611 depth/1341839335.829611.png +1341839335.865741 rgb/1341839335.865741.png 1341839335.865786 depth/1341839335.865786.png +1341839335.929801 rgb/1341839335.929801.png 1341839335.929832 depth/1341839335.929832.png +1341839335.965821 rgb/1341839335.965821.png 1341839335.965832 depth/1341839335.965832.png +1341839335.997645 rgb/1341839335.997645.png 1341839335.997676 depth/1341839335.997676.png +1341839336.033633 rgb/1341839336.033633.png 1341839336.033647 depth/1341839336.033647.png +1341839336.065708 rgb/1341839336.065708.png 1341839336.065734 depth/1341839336.065734.png +1341839336.097620 rgb/1341839336.097620.png 1341839336.097631 depth/1341839336.097631.png +1341839336.133580 rgb/1341839336.133580.png 1341839336.133597 depth/1341839336.133597.png +1341839336.165684 rgb/1341839336.165684.png 1341839336.165702 depth/1341839336.165702.png +1341839336.201770 rgb/1341839336.201770.png 1341839336.202267 depth/1341839336.202267.png +1341839336.234199 rgb/1341839336.234199.png 1341839336.234214 depth/1341839336.234214.png +1341839336.265733 rgb/1341839336.265733.png 1341839336.265756 depth/1341839336.265756.png +1341839336.301605 rgb/1341839336.301605.png 1341839336.301613 depth/1341839336.301613.png +1341839336.333617 rgb/1341839336.333617.png 1341839336.333632 depth/1341839336.333632.png +1341839336.365711 rgb/1341839336.365711.png 1341839336.365718 depth/1341839336.365718.png +1341839336.401651 rgb/1341839336.401651.png 1341839336.401664 depth/1341839336.401664.png +1341839336.433661 rgb/1341839336.433661.png 1341839336.433672 depth/1341839336.433672.png +1341839336.469753 rgb/1341839336.469753.png 1341839336.469794 depth/1341839336.469794.png +1341839336.501527 rgb/1341839336.501527.png 1341839336.501620 depth/1341839336.501620.png +1341839336.533643 rgb/1341839336.533643.png 1341839336.533664 depth/1341839336.533664.png +1341839336.569834 rgb/1341839336.569834.png 1341839336.569844 depth/1341839336.569844.png +1341839336.633720 rgb/1341839336.633720.png 1341839336.633742 depth/1341839336.633742.png +1341839336.669774 rgb/1341839336.669774.png 1341839336.669786 depth/1341839336.669786.png +1341839336.701623 rgb/1341839336.701623.png 1341839336.701630 depth/1341839336.701630.png +1341839336.737703 rgb/1341839336.737703.png 1341839336.737715 depth/1341839336.737715.png +1341839336.769713 rgb/1341839336.769713.png 1341839336.769724 depth/1341839336.769724.png +1341839336.801896 rgb/1341839336.801896.png 1341839336.801932 depth/1341839336.801932.png +1341839336.837710 rgb/1341839336.837710.png 1341839336.837725 depth/1341839336.837725.png +1341839336.869698 rgb/1341839336.869698.png 1341839336.869709 depth/1341839336.869709.png +1341839336.901648 rgb/1341839336.901648.png 1341839336.901683 depth/1341839336.901683.png +1341839336.937590 rgb/1341839336.937590.png 1341839336.937604 depth/1341839336.937604.png +1341839336.969791 rgb/1341839336.969791.png 1341839336.969803 depth/1341839336.969803.png +1341839337.005670 rgb/1341839337.005670.png 1341839337.005683 depth/1341839337.005683.png +1341839337.037737 rgb/1341839337.037737.png 1341839337.037752 depth/1341839337.037752.png +1341839337.069784 rgb/1341839337.069784.png 1341839337.069797 depth/1341839337.069797.png +1341839337.105703 rgb/1341839337.105703.png 1341839337.105718 depth/1341839337.105718.png +1341839337.137668 rgb/1341839337.137668.png 1341839337.137797 depth/1341839337.137797.png +1341839337.169654 rgb/1341839337.169654.png 1341839337.169667 depth/1341839337.169667.png +1341839337.205717 rgb/1341839337.205717.png 1341839337.205734 depth/1341839337.205734.png +1341839337.237736 rgb/1341839337.237736.png 1341839337.237749 depth/1341839337.237749.png +1341839337.273717 rgb/1341839337.273717.png 1341839337.273741 depth/1341839337.273741.png +1341839337.305689 rgb/1341839337.305689.png 1341839337.305704 depth/1341839337.305704.png +1341839337.337586 rgb/1341839337.337586.png 1341839337.337595 depth/1341839337.337595.png +1341839337.373728 rgb/1341839337.373728.png 1341839337.373961 depth/1341839337.373961.png +1341839337.405771 rgb/1341839337.405771.png 1341839337.405787 depth/1341839337.405787.png +1341839337.441982 rgb/1341839337.441982.png 1341839337.442004 depth/1341839337.442004.png +1341839337.473977 rgb/1341839337.473977.png 1341839337.474958 depth/1341839337.474958.png +1341839337.508609 rgb/1341839337.508609.png 1341839337.509733 depth/1341839337.509733.png +1341839337.543918 rgb/1341839337.543918.png 1341839337.544700 depth/1341839337.544700.png +1341839337.606146 rgb/1341839337.606146.png 1341839337.606582 depth/1341839337.606582.png +1341839337.641814 rgb/1341839337.641814.png 1341839337.643191 depth/1341839337.643191.png +1341839337.675262 rgb/1341839337.675262.png 1341839337.675557 depth/1341839337.675557.png +1341839337.709810 rgb/1341839337.709810.png 1341839337.709823 depth/1341839337.709823.png +1341839337.741912 rgb/1341839337.741912.png 1341839337.741931 depth/1341839337.741931.png +1341839337.774188 rgb/1341839337.774188.png 1341839337.775641 depth/1341839337.775641.png +1341839337.809638 rgb/1341839337.809638.png 1341839337.809663 depth/1341839337.809663.png +1341839337.841586 rgb/1341839337.841586.png 1341839337.841607 depth/1341839337.841607.png +1341839337.873743 rgb/1341839337.873743.png 1341839337.873966 depth/1341839337.873966.png +1341839337.909675 rgb/1341839337.909675.png 1341839337.909686 depth/1341839337.909686.png +1341839337.941639 rgb/1341839337.941639.png 1341839337.941649 depth/1341839337.941649.png +1341839337.977798 rgb/1341839337.977798.png 1341839337.978034 depth/1341839337.978034.png +1341839338.010031 rgb/1341839338.010031.png 1341839338.010055 depth/1341839338.010055.png +1341839338.041702 rgb/1341839338.041702.png 1341839338.041796 depth/1341839338.041796.png +1341839338.077694 rgb/1341839338.077694.png 1341839338.077718 depth/1341839338.077718.png +1341839338.109774 rgb/1341839338.109774.png 1341839338.109796 depth/1341839338.109796.png +1341839338.141722 rgb/1341839338.141722.png 1341839338.141788 depth/1341839338.141788.png +1341839338.177697 rgb/1341839338.177697.png 1341839338.177722 depth/1341839338.177722.png +1341839338.209836 rgb/1341839338.209836.png 1341839338.209855 depth/1341839338.209855.png +1341839338.245657 rgb/1341839338.245657.png 1341839338.245667 depth/1341839338.245667.png +1341839338.277654 rgb/1341839338.277654.png 1341839338.277664 depth/1341839338.277664.png +1341839338.309709 rgb/1341839338.309709.png 1341839338.310236 depth/1341839338.310236.png +1341839338.346052 rgb/1341839338.346052.png 1341839338.346061 depth/1341839338.346061.png +1341839338.377746 rgb/1341839338.377746.png 1341839338.377771 depth/1341839338.377771.png +1341839338.414018 rgb/1341839338.414018.png 1341839338.414172 depth/1341839338.414172.png +1341839338.445575 rgb/1341839338.445575.png 1341839338.445621 depth/1341839338.445621.png +1341839338.477556 rgb/1341839338.477556.png 1341839338.477593 depth/1341839338.477593.png +1341839338.513581 rgb/1341839338.513581.png 1341839338.513631 depth/1341839338.513631.png +1341839338.545689 rgb/1341839338.545689.png 1341839338.545729 depth/1341839338.545729.png +1341839338.578283 rgb/1341839338.578283.png 1341839338.578307 depth/1341839338.578307.png +1341839338.613599 rgb/1341839338.613599.png 1341839338.613629 depth/1341839338.613629.png +1341839338.645675 rgb/1341839338.645675.png 1341839338.645705 depth/1341839338.645705.png +1341839338.681727 rgb/1341839338.681727.png 1341839338.681745 depth/1341839338.681745.png +1341839338.713893 rgb/1341839338.713893.png 1341839338.713936 depth/1341839338.713936.png +1341839338.781709 rgb/1341839338.781709.png 1341839338.781731 depth/1341839338.781731.png +1341839338.813730 rgb/1341839338.813730.png 1341839338.813789 depth/1341839338.813789.png +1341839338.845877 rgb/1341839338.845877.png 1341839338.845925 depth/1341839338.845925.png +1341839338.881802 rgb/1341839338.881802.png 1341839338.881852 depth/1341839338.881852.png +1341839338.913653 rgb/1341839338.913653.png 1341839338.913691 depth/1341839338.913691.png +1341839338.949676 rgb/1341839338.949676.png 1341839338.950055 depth/1341839338.950055.png +1341839338.981956 rgb/1341839338.981956.png 1341839338.982022 depth/1341839338.982022.png +1341839339.013697 rgb/1341839339.013697.png 1341839339.013706 depth/1341839339.013706.png +1341839339.049615 rgb/1341839339.049615.png 1341839339.049635 depth/1341839339.049635.png +1341839339.081735 rgb/1341839339.081735.png 1341839339.081747 depth/1341839339.081747.png +1341839339.113711 rgb/1341839339.113711.png 1341839339.113723 depth/1341839339.113723.png +1341839339.149680 rgb/1341839339.149680.png 1341839339.149743 depth/1341839339.149743.png +1341839339.181651 rgb/1341839339.181651.png 1341839339.181663 depth/1341839339.181663.png +1341839339.217865 rgb/1341839339.217865.png 1341839339.217881 depth/1341839339.217881.png +1341839339.249837 rgb/1341839339.249837.png 1341839339.249852 depth/1341839339.249852.png +1341839339.281657 rgb/1341839339.281657.png 1341839339.281688 depth/1341839339.281688.png +1341839339.317672 rgb/1341839339.317672.png 1341839339.317698 depth/1341839339.317698.png +1341839339.349560 rgb/1341839339.349560.png 1341839339.349572 depth/1341839339.349572.png +1341839339.381716 rgb/1341839339.381716.png 1341839339.381744 depth/1341839339.381744.png +1341839339.417573 rgb/1341839339.417573.png 1341839339.417594 depth/1341839339.417594.png +1341839339.449681 rgb/1341839339.449681.png 1341839339.449770 depth/1341839339.449770.png +1341839339.485695 rgb/1341839339.485695.png 1341839339.485862 depth/1341839339.485862.png +1341839339.517711 rgb/1341839339.517711.png 1341839339.517723 depth/1341839339.517723.png +1341839339.549709 rgb/1341839339.549709.png 1341839339.549722 depth/1341839339.549722.png +1341839339.585694 rgb/1341839339.585694.png 1341839339.585708 depth/1341839339.585708.png +1341839339.617734 rgb/1341839339.617734.png 1341839339.617755 depth/1341839339.617755.png +1341839339.653664 rgb/1341839339.653664.png 1341839339.653686 depth/1341839339.653686.png +1341839339.685594 rgb/1341839339.685594.png 1341839339.685607 depth/1341839339.685607.png +1341839339.725102 rgb/1341839339.725102.png 1341839339.717688 depth/1341839339.717688.png +1341839339.785820 rgb/1341839339.785820.png 1341839339.785841 depth/1341839339.785841.png +1341839339.817649 rgb/1341839339.817649.png 1341839339.817673 depth/1341839339.817673.png +1341839339.853678 rgb/1341839339.853678.png 1341839339.853689 depth/1341839339.853689.png +1341839339.885719 rgb/1341839339.885719.png 1341839339.886194 depth/1341839339.886194.png +1341839339.921797 rgb/1341839339.921797.png 1341839339.921810 depth/1341839339.921810.png +1341839339.953700 rgb/1341839339.953700.png 1341839339.953712 depth/1341839339.953712.png +1341839339.985622 rgb/1341839339.985622.png 1341839339.985940 depth/1341839339.985940.png +1341839340.021864 rgb/1341839340.021864.png 1341839340.021944 depth/1341839340.021944.png +1341839340.053574 rgb/1341839340.053574.png 1341839340.053625 depth/1341839340.053625.png +1341839340.085831 rgb/1341839340.085831.png 1341839340.085849 depth/1341839340.085849.png +1341839340.121782 rgb/1341839340.121782.png 1341839340.121790 depth/1341839340.121790.png +1341839340.153668 rgb/1341839340.153668.png 1341839340.153725 depth/1341839340.153725.png +1341839340.189753 rgb/1341839340.189753.png 1341839340.189767 depth/1341839340.189767.png +1341839340.221730 rgb/1341839340.221730.png 1341839340.221740 depth/1341839340.221740.png +1341839340.253773 rgb/1341839340.253773.png 1341839340.253797 depth/1341839340.253797.png +1341839340.289866 rgb/1341839340.289866.png 1341839340.289889 depth/1341839340.289889.png +1341839340.321580 rgb/1341839340.321580.png 1341839340.321596 depth/1341839340.321596.png +1341839340.353715 rgb/1341839340.353715.png 1341839340.353760 depth/1341839340.353760.png +1341839340.389755 rgb/1341839340.389755.png 1341839340.390182 depth/1341839340.390182.png +1341839340.422038 rgb/1341839340.422038.png 1341839340.422046 depth/1341839340.422046.png +1341839340.457698 rgb/1341839340.457698.png 1341839340.457730 depth/1341839340.457730.png +1341839340.489727 rgb/1341839340.489727.png 1341839340.489763 depth/1341839340.489763.png +1341839340.521632 rgb/1341839340.521632.png 1341839340.521641 depth/1341839340.521641.png +1341839340.557783 rgb/1341839340.557783.png 1341839340.557814 depth/1341839340.557814.png +1341839340.589579 rgb/1341839340.589579.png 1341839340.589605 depth/1341839340.589605.png +1341839340.625761 rgb/1341839340.625761.png 1341839340.625790 depth/1341839340.625790.png +1341839340.657658 rgb/1341839340.657658.png 1341839340.657932 depth/1341839340.657932.png +1341839340.689692 rgb/1341839340.689692.png 1341839340.689715 depth/1341839340.689715.png +1341839340.725740 rgb/1341839340.725740.png 1341839340.725751 depth/1341839340.725751.png +1341839340.757924 rgb/1341839340.757924.png 1341839340.757955 depth/1341839340.757955.png +1341839340.789679 rgb/1341839340.789679.png 1341839340.789691 depth/1341839340.789691.png +1341839340.825682 rgb/1341839340.825682.png 1341839340.825704 depth/1341839340.825704.png +1341839340.857588 rgb/1341839340.857588.png 1341839340.857619 depth/1341839340.857619.png +1341839340.893730 rgb/1341839340.893730.png 1341839340.893741 depth/1341839340.893741.png +1341839340.925735 rgb/1341839340.925735.png 1341839340.925744 depth/1341839340.925744.png +1341839340.957629 rgb/1341839340.957629.png 1341839340.957673 depth/1341839340.957673.png +1341839340.993772 rgb/1341839340.993772.png 1341839340.993781 depth/1341839340.993781.png +1341839341.025671 rgb/1341839341.025671.png 1341839341.025719 depth/1341839341.025719.png +1341839341.057806 rgb/1341839341.057806.png 1341839341.057817 depth/1341839341.057817.png +1341839341.093662 rgb/1341839341.093662.png 1341839341.093674 depth/1341839341.093674.png +1341839341.125745 rgb/1341839341.125745.png 1341839341.125757 depth/1341839341.125757.png +1341839341.161589 rgb/1341839341.161589.png 1341839341.161613 depth/1341839341.161613.png +1341839341.193897 rgb/1341839341.193897.png 1341839341.193914 depth/1341839341.193914.png +1341839341.261788 rgb/1341839341.261788.png 1341839341.261807 depth/1341839341.261807.png +1341839341.293674 rgb/1341839341.293674.png 1341839341.294203 depth/1341839341.294203.png +1341839341.325653 rgb/1341839341.325653.png 1341839341.325664 depth/1341839341.325664.png +1341839341.361673 rgb/1341839341.361673.png 1341839341.361807 depth/1341839341.361807.png +1341839341.393787 rgb/1341839341.393787.png 1341839341.394547 depth/1341839341.394547.png +1341839341.429785 rgb/1341839341.429785.png 1341839341.429797 depth/1341839341.429797.png +1341839341.461594 rgb/1341839341.461594.png 1341839341.461658 depth/1341839341.461658.png +1341839341.493666 rgb/1341839341.493666.png 1341839341.494148 depth/1341839341.494148.png +1341839341.529752 rgb/1341839341.529752.png 1341839341.529786 depth/1341839341.529786.png +1341839341.561764 rgb/1341839341.561764.png 1341839341.561773 depth/1341839341.561773.png +1341839341.593691 rgb/1341839341.593691.png 1341839341.593704 depth/1341839341.593704.png +1341839341.629657 rgb/1341839341.629657.png 1341839341.629668 depth/1341839341.629668.png +1341839341.662189 rgb/1341839341.662189.png 1341839341.662204 depth/1341839341.662204.png +1341839341.697693 rgb/1341839341.697693.png 1341839341.697707 depth/1341839341.697707.png +1341839341.729716 rgb/1341839341.729716.png 1341839341.729730 depth/1341839341.729730.png +1341839341.761680 rgb/1341839341.761680.png 1341839341.761718 depth/1341839341.761718.png +1341839341.797656 rgb/1341839341.797656.png 1341839341.797672 depth/1341839341.797672.png +1341839341.829696 rgb/1341839341.829696.png 1341839341.829711 depth/1341839341.829711.png +1341839341.865686 rgb/1341839341.865686.png 1341839341.865698 depth/1341839341.865698.png +1341839341.897659 rgb/1341839341.897659.png 1341839341.897671 depth/1341839341.897671.png +1341839341.929651 rgb/1341839341.929651.png 1341839341.929668 depth/1341839341.929668.png +1341839341.966152 rgb/1341839341.966152.png 1341839341.966161 depth/1341839341.966161.png +1341839341.997665 rgb/1341839341.997665.png 1341839341.997822 depth/1341839341.997822.png +1341839342.029793 rgb/1341839342.029793.png 1341839342.029821 depth/1341839342.029821.png +1341839342.065765 rgb/1341839342.065765.png 1341839342.065778 depth/1341839342.065778.png +1341839342.097737 rgb/1341839342.097737.png 1341839342.097747 depth/1341839342.097747.png +1341839342.133572 rgb/1341839342.133572.png 1341839342.133584 depth/1341839342.133584.png +1341839342.165740 rgb/1341839342.165740.png 1341839342.165747 depth/1341839342.165747.png +1341839342.197680 rgb/1341839342.197680.png 1341839342.197690 depth/1341839342.197690.png +1341839342.233630 rgb/1341839342.233630.png 1341839342.233646 depth/1341839342.233646.png +1341839342.265857 rgb/1341839342.265857.png 1341839342.265874 depth/1341839342.265874.png +1341839342.297900 rgb/1341839342.297900.png 1341839342.297925 depth/1341839342.297925.png +1341839342.334490 rgb/1341839342.334490.png 1341839342.335634 depth/1341839342.335634.png +1341839342.366742 rgb/1341839342.366742.png 1341839342.367875 depth/1341839342.367875.png +1341839342.401681 rgb/1341839342.401681.png 1341839342.401982 depth/1341839342.401982.png +1341839342.433833 rgb/1341839342.433833.png 1341839342.433927 depth/1341839342.433927.png +1341839342.465726 rgb/1341839342.465726.png 1341839342.465742 depth/1341839342.465742.png +1341839342.501647 rgb/1341839342.501647.png 1341839342.501672 depth/1341839342.501672.png +1341839342.540751 rgb/1341839342.540751.png 1341839342.540774 depth/1341839342.540774.png +1341839342.601758 rgb/1341839342.601758.png 1341839342.601781 depth/1341839342.601781.png +1341839342.669819 rgb/1341839342.669819.png 1341839342.669836 depth/1341839342.669836.png +1341839342.701951 rgb/1341839342.701951.png 1341839342.701958 depth/1341839342.701958.png +1341839342.733628 rgb/1341839342.733628.png 1341839342.734327 depth/1341839342.734327.png +1341839342.769533 rgb/1341839342.769533.png 1341839342.769575 depth/1341839342.769575.png +1341839342.801681 rgb/1341839342.801681.png 1341839342.801697 depth/1341839342.801697.png +1341839342.837574 rgb/1341839342.837574.png 1341839342.837599 depth/1341839342.837599.png +1341839342.869635 rgb/1341839342.869635.png 1341839342.869657 depth/1341839342.869657.png +1341839342.901615 rgb/1341839342.901615.png 1341839342.901629 depth/1341839342.901629.png +1341839342.937722 rgb/1341839342.937722.png 1341839342.937752 depth/1341839342.937752.png +1341839342.969783 rgb/1341839342.969783.png 1341839342.969809 depth/1341839342.969809.png +1341839343.001730 rgb/1341839343.001730.png 1341839343.001757 depth/1341839343.001757.png +1341839343.037568 rgb/1341839343.037568.png 1341839343.037598 depth/1341839343.037598.png +1341839343.069751 rgb/1341839343.069751.png 1341839343.069778 depth/1341839343.069778.png +1341839343.105654 rgb/1341839343.105654.png 1341839343.105680 depth/1341839343.105680.png +1341839343.137584 rgb/1341839343.137584.png 1341839343.137599 depth/1341839343.137599.png +1341839343.169670 rgb/1341839343.169670.png 1341839343.169689 depth/1341839343.169689.png +1341839343.205656 rgb/1341839343.205656.png 1341839343.205678 depth/1341839343.205678.png +1341839343.237612 rgb/1341839343.237612.png 1341839343.237627 depth/1341839343.237627.png +1341839343.305779 rgb/1341839343.305779.png 1341839343.305796 depth/1341839343.305796.png +1341839343.337587 rgb/1341839343.337587.png 1341839343.337603 depth/1341839343.337603.png +1341839343.373793 rgb/1341839343.373793.png 1341839343.373816 depth/1341839343.373816.png +1341839343.405587 rgb/1341839343.405587.png 1341839343.405615 depth/1341839343.405615.png +1341839343.437639 rgb/1341839343.437639.png 1341839343.437656 depth/1341839343.437656.png +1341839343.473895 rgb/1341839343.473895.png 1341839343.473926 depth/1341839343.473926.png +1341839343.505595 rgb/1341839343.505595.png 1341839343.505604 depth/1341839343.505604.png +1341839343.537619 rgb/1341839343.537619.png 1341839343.537630 depth/1341839343.537630.png +1341839343.573926 rgb/1341839343.573926.png 1341839343.573940 depth/1341839343.573940.png +1341839343.605784 rgb/1341839343.605784.png 1341839343.605808 depth/1341839343.605808.png +1341839343.641726 rgb/1341839343.641726.png 1341839343.641734 depth/1341839343.641734.png +1341839343.673994 rgb/1341839343.673994.png 1341839343.674008 depth/1341839343.674008.png +1341839343.705911 rgb/1341839343.705911.png 1341839343.706617 depth/1341839343.706617.png +1341839343.741614 rgb/1341839343.741614.png 1341839343.741621 depth/1341839343.741621.png +1341839343.774055 rgb/1341839343.774055.png 1341839343.774086 depth/1341839343.774086.png +1341839343.805691 rgb/1341839343.805691.png 1341839343.805716 depth/1341839343.805716.png +1341839343.841823 rgb/1341839343.841823.png 1341839343.841908 depth/1341839343.841908.png +1341839343.873716 rgb/1341839343.873716.png 1341839343.873728 depth/1341839343.873728.png +1341839343.909636 rgb/1341839343.909636.png 1341839343.909667 depth/1341839343.909667.png +1341839343.941606 rgb/1341839343.941606.png 1341839343.941616 depth/1341839343.941616.png +1341839343.973942 rgb/1341839343.973942.png 1341839343.973980 depth/1341839343.973980.png +1341839344.009670 rgb/1341839344.009670.png 1341839344.009680 depth/1341839344.009680.png +1341839344.041779 rgb/1341839344.041779.png 1341839344.041837 depth/1341839344.041837.png +1341839344.077608 rgb/1341839344.077608.png 1341839344.077657 depth/1341839344.077657.png +1341839344.109759 rgb/1341839344.109759.png 1341839344.109836 depth/1341839344.109836.png +1341839344.141693 rgb/1341839344.141693.png 1341839344.141705 depth/1341839344.141705.png +1341839344.177686 rgb/1341839344.177686.png 1341839344.177702 depth/1341839344.177702.png +1341839344.209677 rgb/1341839344.209677.png 1341839344.209717 depth/1341839344.209717.png +1341839344.241575 rgb/1341839344.241575.png 1341839344.241645 depth/1341839344.241645.png +1341839344.277638 rgb/1341839344.277638.png 1341839344.277671 depth/1341839344.277671.png +1341839344.309629 rgb/1341839344.309629.png 1341839344.309705 depth/1341839344.309705.png +1341839344.345784 rgb/1341839344.345784.png 1341839344.345801 depth/1341839344.345801.png +1341839344.377695 rgb/1341839344.377695.png 1341839344.377710 depth/1341839344.377710.png +1341839344.409722 rgb/1341839344.409722.png 1341839344.409739 depth/1341839344.409739.png +1341839344.445749 rgb/1341839344.445749.png 1341839344.445778 depth/1341839344.445778.png +1341839344.477598 rgb/1341839344.477598.png 1341839344.477610 depth/1341839344.477610.png +1341839344.510290 rgb/1341839344.510290.png 1341839344.510307 depth/1341839344.510307.png +1341839344.545735 rgb/1341839344.545735.png 1341839344.545748 depth/1341839344.545748.png +1341839344.577829 rgb/1341839344.577829.png 1341839344.577848 depth/1341839344.577848.png +1341839344.613708 rgb/1341839344.613708.png 1341839344.613724 depth/1341839344.613724.png +1341839344.645705 rgb/1341839344.645705.png 1341839344.645720 depth/1341839344.645720.png +1341839344.677613 rgb/1341839344.677613.png 1341839344.677623 depth/1341839344.677623.png +1341839344.713772 rgb/1341839344.713772.png 1341839344.713889 depth/1341839344.713889.png +1341839344.746130 rgb/1341839344.746130.png 1341839344.746136 depth/1341839344.746136.png +1341839344.777798 rgb/1341839344.777798.png 1341839344.777806 depth/1341839344.777806.png +1341839344.813709 rgb/1341839344.813709.png 1341839344.813721 depth/1341839344.813721.png +1341839344.845871 rgb/1341839344.845871.png 1341839344.845917 depth/1341839344.845917.png +1341839344.881699 rgb/1341839344.881699.png 1341839344.881716 depth/1341839344.881716.png +1341839344.914032 rgb/1341839344.914032.png 1341839344.914064 depth/1341839344.914064.png +1341839344.981832 rgb/1341839344.981832.png 1341839344.981867 depth/1341839344.981867.png +1341839345.049749 rgb/1341839345.049749.png 1341839345.049773 depth/1341839345.049773.png +1341839345.081699 rgb/1341839345.081699.png 1341839345.081754 depth/1341839345.081754.png +1341839345.113768 rgb/1341839345.113768.png 1341839345.113787 depth/1341839345.113787.png +1341839345.149757 rgb/1341839345.149757.png 1341839345.149765 depth/1341839345.149765.png +1341839345.181590 rgb/1341839345.181590.png 1341839345.181679 depth/1341839345.181679.png +1341839345.213863 rgb/1341839345.213863.png 1341839345.213887 depth/1341839345.213887.png +1341839345.249611 rgb/1341839345.249611.png 1341839345.249641 depth/1341839345.249641.png +1341839345.281827 rgb/1341839345.281827.png 1341839345.281851 depth/1341839345.281851.png +1341839345.317669 rgb/1341839345.317669.png 1341839345.318190 depth/1341839345.318190.png +1341839345.381810 rgb/1341839345.381810.png 1341839345.381825 depth/1341839345.381825.png +1341839345.417639 rgb/1341839345.417639.png 1341839345.417661 depth/1341839345.417661.png +1341839345.449697 rgb/1341839345.449697.png 1341839345.449712 depth/1341839345.449712.png +1341839345.484384 rgb/1341839345.484384.png 1341839345.484398 depth/1341839345.484398.png +1341839345.517977 rgb/1341839345.517977.png 1341839345.517996 depth/1341839345.517996.png +1341839345.550478 rgb/1341839345.550478.png 1341839345.550489 depth/1341839345.550489.png +1341839345.585698 rgb/1341839345.585698.png 1341839345.585734 depth/1341839345.585734.png +1341839345.620249 rgb/1341839345.620249.png 1341839345.620844 depth/1341839345.620844.png +1341839345.656836 rgb/1341839345.656836.png 1341839345.656909 depth/1341839345.656909.png +1341839345.688614 rgb/1341839345.688614.png 1341839345.688622 depth/1341839345.688622.png +1341839345.720655 rgb/1341839345.720655.png 1341839345.720671 depth/1341839345.720671.png +1341839345.756797 rgb/1341839345.756797.png 1341839345.756838 depth/1341839345.756838.png +1341839345.788610 rgb/1341839345.788610.png 1341839345.788625 depth/1341839345.788625.png +1341839345.824841 rgb/1341839345.824841.png 1341839345.824857 depth/1341839345.824857.png +1341839345.857443 rgb/1341839345.857443.png 1341839345.857455 depth/1341839345.857455.png +1341839345.888695 rgb/1341839345.888695.png 1341839345.888708 depth/1341839345.888708.png +1341839345.924817 rgb/1341839345.924817.png 1341839345.924863 depth/1341839345.924863.png +1341839345.956605 rgb/1341839345.956605.png 1341839345.957143 depth/1341839345.957143.png +1341839345.992629 rgb/1341839345.992629.png 1341839345.993158 depth/1341839345.993158.png +1341839346.024783 rgb/1341839346.024783.png 1341839346.024797 depth/1341839346.024797.png +1341839346.060648 rgb/1341839346.060648.png 1341839346.060663 depth/1341839346.060663.png +1341839346.093032 rgb/1341839346.093032.png 1341839346.093046 depth/1341839346.093046.png +1341839346.124985 rgb/1341839346.124985.png 1341839346.125006 depth/1341839346.125006.png +1341839346.160766 rgb/1341839346.160766.png 1341839346.161318 depth/1341839346.161318.png +1341839346.192680 rgb/1341839346.192680.png 1341839346.192773 depth/1341839346.192773.png +1341839346.228607 rgb/1341839346.228607.png 1341839346.228629 depth/1341839346.228629.png +1341839346.289914 rgb/1341839346.289914.png 1341839346.289939 depth/1341839346.289939.png +1341839346.329287 rgb/1341839346.329287.png 1341839346.329312 depth/1341839346.329312.png +1341839346.360711 rgb/1341839346.360711.png 1341839346.360723 depth/1341839346.360723.png +1341839346.396649 rgb/1341839346.396649.png 1341839346.396661 depth/1341839346.396661.png +1341839346.428652 rgb/1341839346.428652.png 1341839346.428667 depth/1341839346.428667.png +1341839346.460699 rgb/1341839346.460699.png 1341839346.460712 depth/1341839346.460712.png +1341839346.496697 rgb/1341839346.496697.png 1341839346.496730 depth/1341839346.496730.png +1341839346.528703 rgb/1341839346.528703.png 1341839346.529245 depth/1341839346.529245.png +1341839346.564637 rgb/1341839346.564637.png 1341839346.564647 depth/1341839346.564647.png +1341839346.596825 rgb/1341839346.596825.png 1341839346.596836 depth/1341839346.596836.png +1341839346.628694 rgb/1341839346.628694.png 1341839346.629205 depth/1341839346.629205.png +1341839346.664637 rgb/1341839346.664637.png 1341839346.664666 depth/1341839346.664666.png +1341839346.696886 rgb/1341839346.696886.png 1341839346.697459 depth/1341839346.697459.png +1341839346.728718 rgb/1341839346.728718.png 1341839346.728784 depth/1341839346.728784.png +1341839346.764595 rgb/1341839346.764595.png 1341839346.764614 depth/1341839346.764614.png +1341839346.796696 rgb/1341839346.796696.png 1341839346.796721 depth/1341839346.796721.png +1341839346.832738 rgb/1341839346.832738.png 1341839346.832754 depth/1341839346.832754.png +1341839346.864859 rgb/1341839346.864859.png 1341839346.864887 depth/1341839346.864887.png +1341839346.896717 rgb/1341839346.896717.png 1341839346.896738 depth/1341839346.896738.png +1341839346.932707 rgb/1341839346.932707.png 1341839346.932720 depth/1341839346.932720.png +1341839346.964729 rgb/1341839346.964729.png 1341839346.964747 depth/1341839346.964747.png +1341839346.996794 rgb/1341839346.996794.png 1341839346.997094 depth/1341839346.997094.png +1341839347.032667 rgb/1341839347.032667.png 1341839347.032687 depth/1341839347.032687.png +1341839347.064794 rgb/1341839347.064794.png 1341839347.064803 depth/1341839347.064803.png +1341839347.096852 rgb/1341839347.096852.png 1341839347.096949 depth/1341839347.096949.png +1341839347.132647 rgb/1341839347.132647.png 1341839347.132674 depth/1341839347.132674.png +1341839347.164773 rgb/1341839347.164773.png 1341839347.164815 depth/1341839347.164815.png +1341839347.200676 rgb/1341839347.200676.png 1341839347.201086 depth/1341839347.201086.png +1341839347.232838 rgb/1341839347.232838.png 1341839347.232888 depth/1341839347.232888.png +1341839347.264666 rgb/1341839347.264666.png 1341839347.264678 depth/1341839347.264678.png +1341839347.300747 rgb/1341839347.300747.png 1341839347.300769 depth/1341839347.300769.png +1341839347.332783 rgb/1341839347.332783.png 1341839347.332810 depth/1341839347.332810.png +1341839347.364685 rgb/1341839347.364685.png 1341839347.364696 depth/1341839347.364696.png +1341839347.400746 rgb/1341839347.400746.png 1341839347.400758 depth/1341839347.400758.png +1341839347.432739 rgb/1341839347.432739.png 1341839347.432768 depth/1341839347.432768.png +1341839347.464647 rgb/1341839347.464647.png 1341839347.464678 depth/1341839347.464678.png +1341839347.500724 rgb/1341839347.500724.png 1341839347.500741 depth/1341839347.500741.png +1341839347.532880 rgb/1341839347.532880.png 1341839347.532902 depth/1341839347.532902.png +1341839347.564698 rgb/1341839347.564698.png 1341839347.564722 depth/1341839347.564722.png +1341839347.600778 rgb/1341839347.600778.png 1341839347.600810 depth/1341839347.600810.png +1341839347.632793 rgb/1341839347.632793.png 1341839347.632816 depth/1341839347.632816.png +1341839347.668741 rgb/1341839347.668741.png 1341839347.668756 depth/1341839347.668756.png +1341839347.700627 rgb/1341839347.700627.png 1341839347.700646 depth/1341839347.700646.png +1341839347.732741 rgb/1341839347.732741.png 1341839347.732763 depth/1341839347.732763.png +1341839347.768676 rgb/1341839347.768676.png 1341839347.768688 depth/1341839347.768688.png +1341839347.800791 rgb/1341839347.800791.png 1341839347.800813 depth/1341839347.800813.png +1341839347.868672 rgb/1341839347.868672.png 1341839347.868719 depth/1341839347.868719.png +1341839347.929775 rgb/1341839347.929775.png 1341839347.929819 depth/1341839347.929819.png +1341839347.961833 rgb/1341839347.961833.png 1341839347.961854 depth/1341839347.961854.png +1341839347.997737 rgb/1341839347.997737.png 1341839347.997747 depth/1341839347.997747.png +1341839348.030155 rgb/1341839348.030155.png 1341839348.030199 depth/1341839348.030199.png +1341839348.065703 rgb/1341839348.065703.png 1341839348.065716 depth/1341839348.065716.png +1341839348.097826 rgb/1341839348.097826.png 1341839348.097839 depth/1341839348.097839.png +1341839348.129675 rgb/1341839348.129675.png 1341839348.129730 depth/1341839348.129730.png +1341839348.168640 rgb/1341839348.168640.png 1341839348.168751 depth/1341839348.168751.png +1341839348.229823 rgb/1341839348.229823.png 1341839348.229846 depth/1341839348.229846.png +1341839348.265775 rgb/1341839348.265775.png 1341839348.265808 depth/1341839348.265808.png +1341839348.297754 rgb/1341839348.297754.png 1341839348.297768 depth/1341839348.297768.png +1341839348.333717 rgb/1341839348.333717.png 1341839348.333745 depth/1341839348.333745.png +1341839348.365676 rgb/1341839348.365676.png 1341839348.365708 depth/1341839348.365708.png +1341839348.398212 rgb/1341839348.398212.png 1341839348.398979 depth/1341839348.398979.png +1341839348.433965 rgb/1341839348.433965.png 1341839348.433976 depth/1341839348.433976.png +1341839348.465810 rgb/1341839348.465810.png 1341839348.467049 depth/1341839348.467049.png +1341839348.502540 rgb/1341839348.502540.png 1341839348.502595 depth/1341839348.502595.png +1341839348.535817 rgb/1341839348.535817.png 1341839348.535836 depth/1341839348.535836.png +1341839348.571279 rgb/1341839348.571279.png 1341839348.572285 depth/1341839348.572285.png +1341839348.602658 rgb/1341839348.602658.png 1341839348.603842 depth/1341839348.603842.png +1341839348.669100 rgb/1341839348.669100.png 1341839348.670608 depth/1341839348.670608.png +1341839348.733880 rgb/1341839348.733880.png 1341839348.733895 depth/1341839348.733895.png +1341839348.769820 rgb/1341839348.769820.png 1341839348.769839 depth/1341839348.769839.png +1341839348.801702 rgb/1341839348.801702.png 1341839348.801715 depth/1341839348.801715.png +1341839348.833872 rgb/1341839348.833872.png 1341839348.833968 depth/1341839348.833968.png +1341839348.869688 rgb/1341839348.869688.png 1341839348.869700 depth/1341839348.869700.png +1341839348.901723 rgb/1341839348.901723.png 1341839348.901741 depth/1341839348.901741.png +1341839348.933633 rgb/1341839348.933633.png 1341839348.933668 depth/1341839348.933668.png +1341839348.969728 rgb/1341839348.969728.png 1341839348.969744 depth/1341839348.969744.png +1341839349.001667 rgb/1341839349.001667.png 1341839349.001702 depth/1341839349.001702.png +1341839349.037748 rgb/1341839349.037748.png 1341839349.037768 depth/1341839349.037768.png +1341839349.069682 rgb/1341839349.069682.png 1341839349.069693 depth/1341839349.069693.png +1341839349.101803 rgb/1341839349.101803.png 1341839349.101825 depth/1341839349.101825.png +1341839349.137732 rgb/1341839349.137732.png 1341839349.137754 depth/1341839349.137754.png +1341839349.169619 rgb/1341839349.169619.png 1341839349.169628 depth/1341839349.169628.png +1341839349.201697 rgb/1341839349.201697.png 1341839349.201708 depth/1341839349.201708.png +1341839349.237802 rgb/1341839349.237802.png 1341839349.237814 depth/1341839349.237814.png +1341839349.269840 rgb/1341839349.269840.png 1341839349.269853 depth/1341839349.269853.png +1341839349.305885 rgb/1341839349.305885.png 1341839349.305943 depth/1341839349.305943.png +1341839349.338036 rgb/1341839349.338036.png 1341839349.339088 depth/1341839349.339088.png +1341839349.369771 rgb/1341839349.369771.png 1341839349.369787 depth/1341839349.369787.png +1341839349.405706 rgb/1341839349.405706.png 1341839349.405720 depth/1341839349.405720.png +1341839349.437665 rgb/1341839349.437665.png 1341839349.437724 depth/1341839349.437724.png +1341839349.473716 rgb/1341839349.473716.png 1341839349.473729 depth/1341839349.473729.png +1341839349.505708 rgb/1341839349.505708.png 1341839349.505725 depth/1341839349.505725.png +1341839349.537635 rgb/1341839349.537635.png 1341839349.537652 depth/1341839349.537652.png +1341839349.573786 rgb/1341839349.573786.png 1341839349.573799 depth/1341839349.573799.png +1341839349.605579 rgb/1341839349.605579.png 1341839349.605590 depth/1341839349.605590.png +1341839349.637702 rgb/1341839349.637702.png 1341839349.637724 depth/1341839349.637724.png +1341839349.673713 rgb/1341839349.673713.png 1341839349.673741 depth/1341839349.673741.png +1341839349.705908 rgb/1341839349.705908.png 1341839349.705934 depth/1341839349.705934.png +1341839349.741751 rgb/1341839349.741751.png 1341839349.741765 depth/1341839349.741765.png +1341839349.773786 rgb/1341839349.773786.png 1341839349.773825 depth/1341839349.773825.png +1341839349.805812 rgb/1341839349.805812.png 1341839349.805826 depth/1341839349.805826.png +1341839349.841758 rgb/1341839349.841758.png 1341839349.841772 depth/1341839349.841772.png +1341839349.873668 rgb/1341839349.873668.png 1341839349.873696 depth/1341839349.873696.png +1341839349.905746 rgb/1341839349.905746.png 1341839349.905763 depth/1341839349.905763.png +1341839349.941760 rgb/1341839349.941760.png 1341839349.941796 depth/1341839349.941796.png +1341839349.973689 rgb/1341839349.973689.png 1341839349.973701 depth/1341839349.973701.png +1341839350.009717 rgb/1341839350.009717.png 1341839350.009736 depth/1341839350.009736.png +1341839350.041679 rgb/1341839350.041679.png 1341839350.041687 depth/1341839350.041687.png +1341839350.073811 rgb/1341839350.073811.png 1341839350.073824 depth/1341839350.073824.png +1341839350.109658 rgb/1341839350.109658.png 1341839350.109678 depth/1341839350.109678.png +1341839350.141699 rgb/1341839350.141699.png 1341839350.141718 depth/1341839350.141718.png +1341839350.173592 rgb/1341839350.173592.png 1341839350.173605 depth/1341839350.173605.png +1341839350.209540 rgb/1341839350.209540.png 1341839350.209551 depth/1341839350.209551.png +1341839350.241825 rgb/1341839350.241825.png 1341839350.241827 depth/1341839350.241827.png +1341839350.280659 rgb/1341839350.280659.png 1341839350.280678 depth/1341839350.280678.png +1341839350.341753 rgb/1341839350.341753.png 1341839350.341767 depth/1341839350.341767.png +1341839350.377683 rgb/1341839350.377683.png 1341839350.377704 depth/1341839350.377704.png +1341839350.409741 rgb/1341839350.409741.png 1341839350.409792 depth/1341839350.409792.png +1341839350.441672 rgb/1341839350.441672.png 1341839350.441699 depth/1341839350.441699.png +1341839350.477741 rgb/1341839350.477741.png 1341839350.477781 depth/1341839350.477781.png +1341839350.509690 rgb/1341839350.509690.png 1341839350.509715 depth/1341839350.509715.png +1341839350.545700 rgb/1341839350.545700.png 1341839350.545709 depth/1341839350.545709.png +1341839350.577579 rgb/1341839350.577579.png 1341839350.577590 depth/1341839350.577590.png +1341839350.609742 rgb/1341839350.609742.png 1341839350.609760 depth/1341839350.609760.png +1341839350.645797 rgb/1341839350.645797.png 1341839350.645826 depth/1341839350.645826.png +1341839350.677685 rgb/1341839350.677685.png 1341839350.677708 depth/1341839350.677708.png +1341839350.713681 rgb/1341839350.713681.png 1341839350.713888 depth/1341839350.713888.png +1341839350.745657 rgb/1341839350.745657.png 1341839350.746270 depth/1341839350.746270.png +1341839350.777685 rgb/1341839350.777685.png 1341839350.777697 depth/1341839350.777697.png +1341839350.814622 rgb/1341839350.814622.png 1341839350.814726 depth/1341839350.814726.png +1341839350.845591 rgb/1341839350.845591.png 1341839350.845617 depth/1341839350.845617.png +1341839350.877688 rgb/1341839350.877688.png 1341839350.877699 depth/1341839350.877699.png +1341839350.913769 rgb/1341839350.913769.png 1341839350.913778 depth/1341839350.913778.png +1341839350.945777 rgb/1341839350.945777.png 1341839350.945791 depth/1341839350.945791.png +1341839350.981684 rgb/1341839350.981684.png 1341839350.981694 depth/1341839350.981694.png +1341839351.013674 rgb/1341839351.013674.png 1341839351.013686 depth/1341839351.013686.png +1341839351.089039 rgb/1341839351.089039.png 1341839351.089078 depth/1341839351.089078.png +1341839351.145768 rgb/1341839351.145768.png 1341839351.145779 depth/1341839351.145779.png +1341839351.181916 rgb/1341839351.181916.png 1341839351.181935 depth/1341839351.181935.png +1341839351.213695 rgb/1341839351.213695.png 1341839351.214389 depth/1341839351.214389.png +1341839351.249720 rgb/1341839351.249720.png 1341839351.250314 depth/1341839351.250314.png +1341839351.281788 rgb/1341839351.281788.png 1341839351.281815 depth/1341839351.281815.png +1341839351.313675 rgb/1341839351.313675.png 1341839351.313685 depth/1341839351.313685.png +1341839351.349751 rgb/1341839351.349751.png 1341839351.349765 depth/1341839351.349765.png +1341839351.381672 rgb/1341839351.381672.png 1341839351.381679 depth/1341839351.381679.png +1341839351.413685 rgb/1341839351.413685.png 1341839351.413696 depth/1341839351.413696.png +1341839351.449725 rgb/1341839351.449725.png 1341839351.449764 depth/1341839351.449764.png +1341839351.481707 rgb/1341839351.481707.png 1341839351.481719 depth/1341839351.481719.png +1341839351.517772 rgb/1341839351.517772.png 1341839351.517790 depth/1341839351.517790.png +1341839351.549797 rgb/1341839351.549797.png 1341839351.549827 depth/1341839351.549827.png +1341839351.581689 rgb/1341839351.581689.png 1341839351.581725 depth/1341839351.581725.png +1341839351.617604 rgb/1341839351.617604.png 1341839351.617620 depth/1341839351.617620.png +1341839351.649696 rgb/1341839351.649696.png 1341839351.649704 depth/1341839351.649704.png +1341839351.685817 rgb/1341839351.685817.png 1341839351.685834 depth/1341839351.685834.png +1341839351.717596 rgb/1341839351.717596.png 1341839351.717608 depth/1341839351.717608.png +1341839351.749639 rgb/1341839351.749639.png 1341839351.749650 depth/1341839351.749650.png +1341839351.785625 rgb/1341839351.785625.png 1341839351.785635 depth/1341839351.785635.png +1341839351.817627 rgb/1341839351.817627.png 1341839351.817647 depth/1341839351.817647.png +1341839351.849686 rgb/1341839351.849686.png 1341839351.849702 depth/1341839351.849702.png +1341839351.885694 rgb/1341839351.885694.png 1341839351.885705 depth/1341839351.885705.png +1341839351.917729 rgb/1341839351.917729.png 1341839351.917741 depth/1341839351.917741.png +1341839351.953535 rgb/1341839351.953535.png 1341839351.953548 depth/1341839351.953548.png +1341839351.985658 rgb/1341839351.985658.png 1341839351.985669 depth/1341839351.985669.png +1341839352.017647 rgb/1341839352.017647.png 1341839352.017659 depth/1341839352.017659.png +1341839352.053642 rgb/1341839352.053642.png 1341839352.053670 depth/1341839352.053670.png +1341839352.085774 rgb/1341839352.085774.png 1341839352.085784 depth/1341839352.085784.png +1341839352.117716 rgb/1341839352.117716.png 1341839352.117756 depth/1341839352.117756.png +1341839352.153646 rgb/1341839352.153646.png 1341839352.153657 depth/1341839352.153657.png +1341839352.185652 rgb/1341839352.185652.png 1341839352.185690 depth/1341839352.185690.png +1341839352.221735 rgb/1341839352.221735.png 1341839352.221755 depth/1341839352.221755.png +1341839352.253736 rgb/1341839352.253736.png 1341839352.253746 depth/1341839352.253746.png +1341839352.285752 rgb/1341839352.285752.png 1341839352.285780 depth/1341839352.285780.png +1341839352.321760 rgb/1341839352.321760.png 1341839352.321813 depth/1341839352.321813.png +1341839352.353789 rgb/1341839352.353789.png 1341839352.353802 depth/1341839352.353802.png +1341839352.385803 rgb/1341839352.385803.png 1341839352.385821 depth/1341839352.385821.png +1341839352.421731 rgb/1341839352.421731.png 1341839352.421743 depth/1341839352.421743.png +1341839352.453683 rgb/1341839352.453683.png 1341839352.454124 depth/1341839352.454124.png +1341839352.489870 rgb/1341839352.489870.png 1341839352.489884 depth/1341839352.489884.png +1341839352.521781 rgb/1341839352.521781.png 1341839352.521799 depth/1341839352.521799.png +1341839352.553740 rgb/1341839352.553740.png 1341839352.554196 depth/1341839352.554196.png +1341839352.592712 rgb/1341839352.592712.png 1341839352.592733 depth/1341839352.592733.png +1341839352.653962 rgb/1341839352.653962.png 1341839352.653982 depth/1341839352.653982.png +1341839352.692715 rgb/1341839352.692715.png 1341839352.692762 depth/1341839352.692762.png +1341839352.757603 rgb/1341839352.757603.png 1341839352.757652 depth/1341839352.757652.png +1341839352.792571 rgb/1341839352.792571.png 1341839352.792612 depth/1341839352.792612.png +1341839352.857762 rgb/1341839352.857762.png 1341839352.857774 depth/1341839352.857774.png +1341839352.889879 rgb/1341839352.889879.png 1341839352.889975 depth/1341839352.889975.png +1341839352.925639 rgb/1341839352.925639.png 1341839352.925653 depth/1341839352.925653.png +1341839352.960824 rgb/1341839352.960824.png 1341839352.960853 depth/1341839352.960853.png +1341839353.025681 rgb/1341839353.025681.png 1341839353.025694 depth/1341839353.025694.png +1341839353.057719 rgb/1341839353.057719.png 1341839353.057737 depth/1341839353.057737.png +1341839353.089820 rgb/1341839353.089820.png 1341839353.089840 depth/1341839353.089840.png +1341839353.125813 rgb/1341839353.125813.png 1341839353.125824 depth/1341839353.125824.png +1341839353.157710 rgb/1341839353.157710.png 1341839353.157719 depth/1341839353.157719.png +1341839353.193938 rgb/1341839353.193938.png 1341839353.194047 depth/1341839353.194047.png +1341839353.225679 rgb/1341839353.225679.png 1341839353.225693 depth/1341839353.225693.png +1341839353.257913 rgb/1341839353.257913.png 1341839353.257937 depth/1341839353.257937.png +1341839353.296780 rgb/1341839353.296780.png 1341839353.296799 depth/1341839353.296799.png +1341839353.335548 rgb/1341839353.335548.png 1341839353.335584 depth/1341839353.335584.png +1341839353.364651 rgb/1341839353.364651.png 1341839353.364885 depth/1341839353.364885.png +1341839353.400728 rgb/1341839353.400728.png 1341839353.400775 depth/1341839353.400775.png +1341839353.432721 rgb/1341839353.432721.png 1341839353.432737 depth/1341839353.432737.png +1341839353.464780 rgb/1341839353.464780.png 1341839353.464794 depth/1341839353.464794.png +1341839353.500713 rgb/1341839353.500713.png 1341839353.500731 depth/1341839353.500731.png +1341839353.532682 rgb/1341839353.532682.png 1341839353.532694 depth/1341839353.532694.png +1341839353.568645 rgb/1341839353.568645.png 1341839353.568655 depth/1341839353.568655.png +1341839353.600681 rgb/1341839353.600681.png 1341839353.600699 depth/1341839353.600699.png +1341839353.663071 rgb/1341839353.663071.png 1341839353.663133 depth/1341839353.663133.png +1341839353.693949 rgb/1341839353.693949.png 1341839353.694757 depth/1341839353.694757.png +1341839353.729827 rgb/1341839353.729827.png 1341839353.729840 depth/1341839353.729840.png +1341839353.761755 rgb/1341839353.761755.png 1341839353.762769 depth/1341839353.762769.png +1341839353.794339 rgb/1341839353.794339.png 1341839353.794377 depth/1341839353.794377.png +1341839353.838084 rgb/1341839353.838084.png 1341839353.838101 depth/1341839353.838101.png +1341839353.900785 rgb/1341839353.900785.png 1341839353.900821 depth/1341839353.900821.png +1341839353.961728 rgb/1341839353.961728.png 1341839353.961940 depth/1341839353.961940.png +1341839354.000918 rgb/1341839354.000918.png 1341839354.002030 depth/1341839354.002030.png +1341839354.037947 rgb/1341839354.037947.png 1341839354.039276 depth/1341839354.039276.png +1341839354.069412 rgb/1341839354.069412.png 1341839354.069798 depth/1341839354.069798.png +1341839354.136797 rgb/1341839354.136797.png 1341839354.136831 depth/1341839354.136831.png +1341839354.197963 rgb/1341839354.197963.png 1341839354.198709 depth/1341839354.198709.png +1341839354.229618 rgb/1341839354.229618.png 1341839354.229653 depth/1341839354.229653.png +1341839354.265633 rgb/1341839354.265633.png 1341839354.265645 depth/1341839354.265645.png +1341839354.298363 rgb/1341839354.298363.png 1341839354.297874 depth/1341839354.297874.png +1341839354.329689 rgb/1341839354.329689.png 1341839354.329700 depth/1341839354.329700.png +1341839354.366365 rgb/1341839354.366365.png 1341839354.366440 depth/1341839354.366440.png +1341839354.397620 rgb/1341839354.397620.png 1341839354.397631 depth/1341839354.397631.png +1341839354.433710 rgb/1341839354.433710.png 1341839354.433728 depth/1341839354.433728.png +1341839354.465713 rgb/1341839354.465713.png 1341839354.465726 depth/1341839354.465726.png +1341839354.497576 rgb/1341839354.497576.png 1341839354.497590 depth/1341839354.497590.png +1341839354.533748 rgb/1341839354.533748.png 1341839354.533790 depth/1341839354.533790.png +1341839354.565577 rgb/1341839354.565577.png 1341839354.565585 depth/1341839354.565585.png +1341839354.597692 rgb/1341839354.597692.png 1341839354.597739 depth/1341839354.597739.png +1341839354.633605 rgb/1341839354.633605.png 1341839354.633631 depth/1341839354.633631.png +1341839354.665643 rgb/1341839354.665643.png 1341839354.665662 depth/1341839354.665662.png +1341839354.701714 rgb/1341839354.701714.png 1341839354.701725 depth/1341839354.701725.png +1341839354.733804 rgb/1341839354.733804.png 1341839354.733850 depth/1341839354.733850.png +1341839354.765616 rgb/1341839354.765616.png 1341839354.765676 depth/1341839354.765676.png +1341839354.801679 rgb/1341839354.801679.png 1341839354.801718 depth/1341839354.801718.png +1341839354.833771 rgb/1341839354.833771.png 1341839354.833783 depth/1341839354.833783.png +1341839354.865631 rgb/1341839354.865631.png 1341839354.865709 depth/1341839354.865709.png +1341839354.901651 rgb/1341839354.901651.png 1341839354.901667 depth/1341839354.901667.png +1341839354.933716 rgb/1341839354.933716.png 1341839354.934160 depth/1341839354.934160.png +1341839354.969646 rgb/1341839354.969646.png 1341839354.969722 depth/1341839354.969722.png +1341839355.001713 rgb/1341839355.001713.png 1341839355.001769 depth/1341839355.001769.png +1341839355.033725 rgb/1341839355.033725.png 1341839355.033737 depth/1341839355.033737.png +1341839355.069603 rgb/1341839355.069603.png 1341839355.069614 depth/1341839355.069614.png +1341839355.101627 rgb/1341839355.101627.png 1341839355.101644 depth/1341839355.101644.png +1341839355.137531 rgb/1341839355.137531.png 1341839355.137540 depth/1341839355.137540.png +1341839355.169562 rgb/1341839355.169562.png 1341839355.169571 depth/1341839355.169571.png +1341839355.201760 rgb/1341839355.201760.png 1341839355.201782 depth/1341839355.201782.png +1341839355.237695 rgb/1341839355.237695.png 1341839355.237716 depth/1341839355.237716.png +1341839355.269652 rgb/1341839355.269652.png 1341839355.269692 depth/1341839355.269692.png +1341839355.301616 rgb/1341839355.301616.png 1341839355.301664 depth/1341839355.301664.png +1341839355.337610 rgb/1341839355.337610.png 1341839355.337641 depth/1341839355.337641.png +1341839355.369612 rgb/1341839355.369612.png 1341839355.369662 depth/1341839355.369662.png +1341839355.405623 rgb/1341839355.405623.png 1341839355.405658 depth/1341839355.405658.png +1341839355.437629 rgb/1341839355.437629.png 1341839355.437662 depth/1341839355.437662.png +1341839355.469756 rgb/1341839355.469756.png 1341839355.469766 depth/1341839355.469766.png +1341839355.505688 rgb/1341839355.505688.png 1341839355.505709 depth/1341839355.505709.png +1341839355.537644 rgb/1341839355.537644.png 1341839355.537653 depth/1341839355.537653.png +1341839355.569700 rgb/1341839355.569700.png 1341839355.569708 depth/1341839355.569708.png +1341839355.605650 rgb/1341839355.605650.png 1341839355.605674 depth/1341839355.605674.png +1341839355.637626 rgb/1341839355.637626.png 1341839355.637635 depth/1341839355.637635.png +1341839355.673784 rgb/1341839355.673784.png 1341839355.673801 depth/1341839355.673801.png +1341839355.706249 rgb/1341839355.706249.png 1341839355.706928 depth/1341839355.706928.png +1341839355.739256 rgb/1341839355.739256.png 1341839355.739271 depth/1341839355.739271.png +1341839355.774017 rgb/1341839355.774017.png 1341839355.774038 depth/1341839355.774038.png +1341839355.806602 rgb/1341839355.806602.png 1341839355.807663 depth/1341839355.807663.png +1341839355.838477 rgb/1341839355.838477.png 1341839355.840813 depth/1341839355.840813.png +1341839355.876285 rgb/1341839355.876285.png 1341839355.877042 depth/1341839355.877042.png +1341839355.909298 rgb/1341839355.909298.png 1341839355.909353 depth/1341839355.909353.png +1341839355.942206 rgb/1341839355.942206.png 1341839355.942231 depth/1341839355.942231.png +1341839355.974188 rgb/1341839355.974188.png 1341839355.975397 depth/1341839355.975397.png +1341839356.041846 rgb/1341839356.041846.png 1341839356.041875 depth/1341839356.041875.png +1341839356.073656 rgb/1341839356.073656.png 1341839356.073705 depth/1341839356.073705.png +1341839356.109615 rgb/1341839356.109615.png 1341839356.109646 depth/1341839356.109646.png +1341839356.141597 rgb/1341839356.141597.png 1341839356.141613 depth/1341839356.141613.png +1341839356.173684 rgb/1341839356.173684.png 1341839356.173695 depth/1341839356.173695.png +1341839356.209613 rgb/1341839356.209613.png 1341839356.209623 depth/1341839356.209623.png +1341839356.241782 rgb/1341839356.241782.png 1341839356.241797 depth/1341839356.241797.png +1341839356.273675 rgb/1341839356.273675.png 1341839356.273709 depth/1341839356.273709.png +1341839356.309726 rgb/1341839356.309726.png 1341839356.309737 depth/1341839356.309737.png +1341839356.342087 rgb/1341839356.342087.png 1341839356.342107 depth/1341839356.342107.png +1341839356.377564 rgb/1341839356.377564.png 1341839356.377576 depth/1341839356.377576.png +1341839356.409691 rgb/1341839356.409691.png 1341839356.409746 depth/1341839356.409746.png +1341839356.441698 rgb/1341839356.441698.png 1341839356.441728 depth/1341839356.441728.png +1341839356.477584 rgb/1341839356.477584.png 1341839356.477618 depth/1341839356.477618.png +1341839356.509645 rgb/1341839356.509645.png 1341839356.509661 depth/1341839356.509661.png +1341839356.541706 rgb/1341839356.541706.png 1341839356.541721 depth/1341839356.541721.png +1341839356.577608 rgb/1341839356.577608.png 1341839356.577645 depth/1341839356.577645.png +1341839356.609837 rgb/1341839356.609837.png 1341839356.609851 depth/1341839356.609851.png +1341839356.645735 rgb/1341839356.645735.png 1341839356.645767 depth/1341839356.645767.png +1341839356.677975 rgb/1341839356.677975.png 1341839356.678001 depth/1341839356.678001.png +1341839356.709843 rgb/1341839356.709843.png 1341839356.710350 depth/1341839356.710350.png +1341839356.745847 rgb/1341839356.745847.png 1341839356.745869 depth/1341839356.745869.png +1341839356.777774 rgb/1341839356.777774.png 1341839356.777797 depth/1341839356.777797.png +1341839356.809802 rgb/1341839356.809802.png 1341839356.809816 depth/1341839356.809816.png +1341839356.845719 rgb/1341839356.845719.png 1341839356.845743 depth/1341839356.845743.png +1341839356.877710 rgb/1341839356.877710.png 1341839356.877920 depth/1341839356.877920.png +1341839356.913747 rgb/1341839356.913747.png 1341839356.913773 depth/1341839356.913773.png +1341839356.945651 rgb/1341839356.945651.png 1341839356.945674 depth/1341839356.945674.png +1341839356.978052 rgb/1341839356.978052.png 1341839356.978071 depth/1341839356.978071.png +1341839357.013861 rgb/1341839357.013861.png 1341839357.013875 depth/1341839357.013875.png +1341839357.046107 rgb/1341839357.046107.png 1341839357.046119 depth/1341839357.046119.png +1341839357.077622 rgb/1341839357.077622.png 1341839357.077637 depth/1341839357.077637.png +1341839357.113806 rgb/1341839357.113806.png 1341839357.113828 depth/1341839357.113828.png +1341839357.146224 rgb/1341839357.146224.png 1341839357.146265 depth/1341839357.146265.png +1341839357.181674 rgb/1341839357.181674.png 1341839357.181688 depth/1341839357.181688.png +1341839357.213755 rgb/1341839357.213755.png 1341839357.213772 depth/1341839357.213772.png +1341839357.245802 rgb/1341839357.245802.png 1341839357.245874 depth/1341839357.245874.png +1341839357.281655 rgb/1341839357.281655.png 1341839357.281713 depth/1341839357.281713.png +1341839357.313687 rgb/1341839357.313687.png 1341839357.313694 depth/1341839357.313694.png +1341839357.349654 rgb/1341839357.349654.png 1341839357.349699 depth/1341839357.349699.png +1341839357.381649 rgb/1341839357.381649.png 1341839357.381667 depth/1341839357.381667.png +1341839357.413668 rgb/1341839357.413668.png 1341839357.413685 depth/1341839357.413685.png +1341839357.449913 rgb/1341839357.449913.png 1341839357.449934 depth/1341839357.449934.png +1341839357.481703 rgb/1341839357.481703.png 1341839357.481712 depth/1341839357.481712.png +1341839357.514956 rgb/1341839357.514956.png 1341839357.514990 depth/1341839357.514990.png +1341839357.549716 rgb/1341839357.549716.png 1341839357.549742 depth/1341839357.549742.png +1341839357.581581 rgb/1341839357.581581.png 1341839357.581606 depth/1341839357.581606.png +1341839357.617637 rgb/1341839357.617637.png 1341839357.617709 depth/1341839357.617709.png +1341839357.649685 rgb/1341839357.649685.png 1341839357.649699 depth/1341839357.649699.png +1341839357.681786 rgb/1341839357.681786.png 1341839357.681817 depth/1341839357.681817.png +1341839357.717826 rgb/1341839357.717826.png 1341839357.717860 depth/1341839357.717860.png +1341839357.749655 rgb/1341839357.749655.png 1341839357.749666 depth/1341839357.749666.png +1341839357.781624 rgb/1341839357.781624.png 1341839357.781642 depth/1341839357.781642.png +1341839357.817786 rgb/1341839357.817786.png 1341839357.817823 depth/1341839357.817823.png +1341839357.849783 rgb/1341839357.849783.png 1341839357.849808 depth/1341839357.849808.png +1341839357.885712 rgb/1341839357.885712.png 1341839357.885736 depth/1341839357.885736.png +1341839357.917712 rgb/1341839357.917712.png 1341839357.917751 depth/1341839357.917751.png +1341839357.949667 rgb/1341839357.949667.png 1341839357.949690 depth/1341839357.949690.png +1341839357.985579 rgb/1341839357.985579.png 1341839357.985623 depth/1341839357.985623.png +1341839358.017628 rgb/1341839358.017628.png 1341839358.017650 depth/1341839358.017650.png +1341839358.049615 rgb/1341839358.049615.png 1341839358.049655 depth/1341839358.049655.png +1341839358.085696 rgb/1341839358.085696.png 1341839358.085737 depth/1341839358.085737.png +1341839358.117598 rgb/1341839358.117598.png 1341839358.117637 depth/1341839358.117637.png +1341839358.153682 rgb/1341839358.153682.png 1341839358.153715 depth/1341839358.153715.png +1341839358.185801 rgb/1341839358.185801.png 1341839358.185844 depth/1341839358.185844.png +1341839358.217780 rgb/1341839358.217780.png 1341839358.217797 depth/1341839358.217797.png +1341839358.253603 rgb/1341839358.253603.png 1341839358.253652 depth/1341839358.253652.png +1341839358.285662 rgb/1341839358.285662.png 1341839358.285679 depth/1341839358.285679.png +1341839358.321840 rgb/1341839358.321840.png 1341839358.321849 depth/1341839358.321849.png +1341839358.353833 rgb/1341839358.353833.png 1341839358.353846 depth/1341839358.353846.png +1341839358.385678 rgb/1341839358.385678.png 1341839358.385731 depth/1341839358.385731.png +1341839358.428788 rgb/1341839358.428788.png 1341839358.428825 depth/1341839358.428825.png +1341839358.485712 rgb/1341839358.485712.png 1341839358.485748 depth/1341839358.485748.png +1341839358.521878 rgb/1341839358.521878.png 1341839358.521915 depth/1341839358.521915.png +1341839358.554882 rgb/1341839358.554882.png 1341839358.554900 depth/1341839358.554900.png +1341839358.589750 rgb/1341839358.589750.png 1341839358.589775 depth/1341839358.589775.png +1341839358.621635 rgb/1341839358.621635.png 1341839358.621650 depth/1341839358.621650.png +1341839358.653698 rgb/1341839358.653698.png 1341839358.653706 depth/1341839358.653706.png +1341839358.689793 rgb/1341839358.689793.png 1341839358.689824 depth/1341839358.689824.png +1341839358.721862 rgb/1341839358.721862.png 1341839358.721953 depth/1341839358.721953.png +1341839358.753842 rgb/1341839358.753842.png 1341839358.753862 depth/1341839358.753862.png +1341839358.789992 rgb/1341839358.789992.png 1341839358.790019 depth/1341839358.790019.png +1341839358.821835 rgb/1341839358.821835.png 1341839358.822338 depth/1341839358.822338.png +1341839358.857631 rgb/1341839358.857631.png 1341839358.857645 depth/1341839358.857645.png +1341839358.889695 rgb/1341839358.889695.png 1341839358.890250 depth/1341839358.890250.png +1341839358.921673 rgb/1341839358.921673.png 1341839358.921681 depth/1341839358.921681.png +1341839358.957766 rgb/1341839358.957766.png 1341839358.957797 depth/1341839358.957797.png +1341839358.989751 rgb/1341839358.989751.png 1341839358.989760 depth/1341839358.989760.png +1341839359.021755 rgb/1341839359.021755.png 1341839359.021775 depth/1341839359.021775.png +1341839359.058178 rgb/1341839359.058178.png 1341839359.058198 depth/1341839359.058198.png +1341839359.089826 rgb/1341839359.089826.png 1341839359.090576 depth/1341839359.090576.png +1341839359.125660 rgb/1341839359.125660.png 1341839359.125670 depth/1341839359.125670.png +1341839359.157759 rgb/1341839359.157759.png 1341839359.157815 depth/1341839359.157815.png +1341839359.189872 rgb/1341839359.189872.png 1341839359.189878 depth/1341839359.189878.png +1341839359.225681 rgb/1341839359.225681.png 1341839359.225701 depth/1341839359.225701.png +1341839359.257807 rgb/1341839359.257807.png 1341839359.257833 depth/1341839359.257833.png +1341839359.289681 rgb/1341839359.289681.png 1341839359.289696 depth/1341839359.289696.png +1341839359.325714 rgb/1341839359.325714.png 1341839359.325740 depth/1341839359.325740.png +1341839359.357757 rgb/1341839359.357757.png 1341839359.357773 depth/1341839359.357773.png +1341839359.393776 rgb/1341839359.393776.png 1341839359.393816 depth/1341839359.393816.png +1341839359.425642 rgb/1341839359.425642.png 1341839359.425656 depth/1341839359.425656.png +1341839359.457813 rgb/1341839359.457813.png 1341839359.457834 depth/1341839359.457834.png +1341839359.493829 rgb/1341839359.493829.png 1341839359.493854 depth/1341839359.493854.png +1341839359.525779 rgb/1341839359.525779.png 1341839359.525792 depth/1341839359.525792.png +1341839359.561710 rgb/1341839359.561710.png 1341839359.561753 depth/1341839359.561753.png +1341839359.593664 rgb/1341839359.593664.png 1341839359.593701 depth/1341839359.593701.png +1341839359.625670 rgb/1341839359.625670.png 1341839359.625855 depth/1341839359.625855.png +1341839359.661897 rgb/1341839359.661897.png 1341839359.661931 depth/1341839359.661931.png +1341839359.694301 rgb/1341839359.694301.png 1341839359.694317 depth/1341839359.694317.png +1341839359.725642 rgb/1341839359.725642.png 1341839359.725654 depth/1341839359.725654.png +1341839359.761750 rgb/1341839359.761750.png 1341839359.761764 depth/1341839359.761764.png +1341839359.793758 rgb/1341839359.793758.png 1341839359.793778 depth/1341839359.793778.png +1341839359.829704 rgb/1341839359.829704.png 1341839359.829763 depth/1341839359.829763.png +1341839359.861791 rgb/1341839359.861791.png 1341839359.861821 depth/1341839359.861821.png +1341839359.893777 rgb/1341839359.893777.png 1341839359.893806 depth/1341839359.893806.png +1341839359.929739 rgb/1341839359.929739.png 1341839359.929773 depth/1341839359.929773.png +1341839359.961705 rgb/1341839359.961705.png 1341839359.961730 depth/1341839359.961730.png +1341839359.993730 rgb/1341839359.993730.png 1341839359.993743 depth/1341839359.993743.png +1341839360.029709 rgb/1341839360.029709.png 1341839360.029722 depth/1341839360.029722.png +1341839360.061822 rgb/1341839360.061822.png 1341839360.062441 depth/1341839360.062441.png +1341839360.100893 rgb/1341839360.100893.png 1341839360.100910 depth/1341839360.100910.png +1341839360.137502 rgb/1341839360.137502.png 1341839360.138191 depth/1341839360.138191.png +1341839360.201017 rgb/1341839360.201017.png 1341839360.202419 depth/1341839360.202419.png +1341839360.236907 rgb/1341839360.236907.png 1341839360.237476 depth/1341839360.237476.png +1341839360.269741 rgb/1341839360.269741.png 1341839360.270870 depth/1341839360.270870.png +1341839360.305127 rgb/1341839360.305127.png 1341839360.305510 depth/1341839360.305510.png +1341839360.337161 rgb/1341839360.337161.png 1341839360.337571 depth/1341839360.337571.png +1341839360.371370 rgb/1341839360.371370.png 1341839360.373429 depth/1341839360.373429.png +1341839360.404790 rgb/1341839360.404790.png 1341839360.404820 depth/1341839360.404820.png +1341839360.473022 rgb/1341839360.473022.png 1341839360.473319 depth/1341839360.473319.png +1341839360.533749 rgb/1341839360.533749.png 1341839360.533800 depth/1341839360.533800.png +1341839360.565788 rgb/1341839360.565788.png 1341839360.565814 depth/1341839360.565814.png +1341839360.597615 rgb/1341839360.597615.png 1341839360.597672 depth/1341839360.597672.png +1341839360.633615 rgb/1341839360.633615.png 1341839360.633651 depth/1341839360.633651.png +1341839360.665699 rgb/1341839360.665699.png 1341839360.665719 depth/1341839360.665719.png +1341839360.697767 rgb/1341839360.697767.png 1341839360.697813 depth/1341839360.697813.png +1341839360.733659 rgb/1341839360.733659.png 1341839360.733668 depth/1341839360.733668.png +1341839360.765779 rgb/1341839360.765779.png 1341839360.765793 depth/1341839360.765793.png +1341839360.801691 rgb/1341839360.801691.png 1341839360.801703 depth/1341839360.801703.png +1341839360.833754 rgb/1341839360.833754.png 1341839360.833770 depth/1341839360.833770.png +1341839360.865719 rgb/1341839360.865719.png 1341839360.865733 depth/1341839360.865733.png +1341839360.901694 rgb/1341839360.901694.png 1341839360.901705 depth/1341839360.901705.png +1341839360.965710 rgb/1341839360.965710.png 1341839360.965737 depth/1341839360.965737.png +1341839361.002295 rgb/1341839361.002295.png 1341839361.002321 depth/1341839361.002321.png +1341839361.033764 rgb/1341839361.033764.png 1341839361.034750 depth/1341839361.034750.png +1341839361.102289 rgb/1341839361.102289.png 1341839361.103706 depth/1341839361.103706.png +1341839361.169771 rgb/1341839361.169771.png 1341839361.169933 depth/1341839361.169933.png +1341839361.201803 rgb/1341839361.201803.png 1341839361.201826 depth/1341839361.201826.png +1341839361.233892 rgb/1341839361.233892.png 1341839361.233920 depth/1341839361.233920.png +1341839361.269677 rgb/1341839361.269677.png 1341839361.269703 depth/1341839361.269703.png +1341839361.301795 rgb/1341839361.301795.png 1341839361.301843 depth/1341839361.301843.png +1341839361.337636 rgb/1341839361.337636.png 1341839361.337686 depth/1341839361.337686.png +1341839361.369704 rgb/1341839361.369704.png 1341839361.369755 depth/1341839361.369755.png +1341839361.401585 rgb/1341839361.401585.png 1341839361.401618 depth/1341839361.401618.png +1341839361.437714 rgb/1341839361.437714.png 1341839361.437742 depth/1341839361.437742.png +1341839361.469733 rgb/1341839361.469733.png 1341839361.469756 depth/1341839361.469756.png +1341839361.501602 rgb/1341839361.501602.png 1341839361.501612 depth/1341839361.501612.png +1341839361.537692 rgb/1341839361.537692.png 1341839361.537722 depth/1341839361.537722.png +1341839361.569984 rgb/1341839361.569984.png 1341839361.570767 depth/1341839361.570767.png +1341839361.606542 rgb/1341839361.606542.png 1341839361.607329 depth/1341839361.607329.png +1341839361.637785 rgb/1341839361.637785.png 1341839361.637921 depth/1341839361.637921.png +1341839361.708797 rgb/1341839361.708797.png 1341839361.708855 depth/1341839361.708855.png +1341839361.773788 rgb/1341839361.773788.png 1341839361.773844 depth/1341839361.773844.png +1341839361.805940 rgb/1341839361.805940.png 1341839361.805953 depth/1341839361.805953.png +1341839361.837711 rgb/1341839361.837711.png 1341839361.838183 depth/1341839361.838183.png +1341839361.873794 rgb/1341839361.873794.png 1341839361.874230 depth/1341839361.874230.png +1341839361.905952 rgb/1341839361.905952.png 1341839361.905976 depth/1341839361.905976.png +1341839361.937751 rgb/1341839361.937751.png 1341839361.937796 depth/1341839361.937796.png +1341839361.973665 rgb/1341839361.973665.png 1341839361.973701 depth/1341839361.973701.png +1341839362.041782 rgb/1341839362.041782.png 1341839362.041796 depth/1341839362.041796.png +1341839362.073669 rgb/1341839362.073669.png 1341839362.073699 depth/1341839362.073699.png +1341839362.105771 rgb/1341839362.105771.png 1341839362.105993 depth/1341839362.105993.png +1341839362.141801 rgb/1341839362.141801.png 1341839362.141822 depth/1341839362.141822.png +1341839362.173951 rgb/1341839362.173951.png 1341839362.173985 depth/1341839362.173985.png +1341839362.205868 rgb/1341839362.205868.png 1341839362.205875 depth/1341839362.205875.png +1341839362.244834 rgb/1341839362.244834.png 1341839362.244887 depth/1341839362.244887.png +1341839362.309766 rgb/1341839362.309766.png 1341839362.309785 depth/1341839362.309785.png +1341839362.342256 rgb/1341839362.342256.png 1341839362.342269 depth/1341839362.342269.png +1341839362.375616 rgb/1341839362.375616.png 1341839362.376908 depth/1341839362.376908.png +1341839362.409857 rgb/1341839362.409857.png 1341839362.411098 depth/1341839362.411098.png +1341839362.441822 rgb/1341839362.441822.png 1341839362.441894 depth/1341839362.441894.png +1341839362.473901 rgb/1341839362.473901.png 1341839362.473911 depth/1341839362.473911.png +1341839362.509593 rgb/1341839362.509593.png 1341839362.509604 depth/1341839362.509604.png +1341839362.542222 rgb/1341839362.542222.png 1341839362.542263 depth/1341839362.542263.png +1341839362.577899 rgb/1341839362.577899.png 1341839362.577920 depth/1341839362.577920.png +1341839362.617020 rgb/1341839362.617020.png 1341839362.617027 depth/1341839362.617027.png +1341839362.649367 rgb/1341839362.649367.png 1341839362.649381 depth/1341839362.649381.png +1341839362.680746 rgb/1341839362.680746.png 1341839362.680757 depth/1341839362.680757.png +1341839362.716791 rgb/1341839362.716791.png 1341839362.716808 depth/1341839362.716808.png +1341839362.748669 rgb/1341839362.748669.png 1341839362.748683 depth/1341839362.748683.png +1341839362.784599 rgb/1341839362.784599.png 1341839362.784611 depth/1341839362.784611.png +1341839362.816854 rgb/1341839362.816854.png 1341839362.817010 depth/1341839362.817010.png +1341839362.848682 rgb/1341839362.848682.png 1341839362.848690 depth/1341839362.848690.png +1341839362.884649 rgb/1341839362.884649.png 1341839362.884665 depth/1341839362.884665.png +1341839362.916705 rgb/1341839362.916705.png 1341839362.916719 depth/1341839362.916719.png +1341839362.952721 rgb/1341839362.952721.png 1341839362.952744 depth/1341839362.952744.png +1341839362.984800 rgb/1341839362.984800.png 1341839362.984817 depth/1341839362.984817.png +1341839363.016641 rgb/1341839363.016641.png 1341839363.016656 depth/1341839363.016656.png +1341839363.052753 rgb/1341839363.052753.png 1341839363.052768 depth/1341839363.052768.png +1341839363.084836 rgb/1341839363.084836.png 1341839363.084854 depth/1341839363.084854.png +1341839363.120807 rgb/1341839363.120807.png 1341839363.120843 depth/1341839363.120843.png +1341839363.152777 rgb/1341839363.152777.png 1341839363.152798 depth/1341839363.152798.png +1341839363.184689 rgb/1341839363.184689.png 1341839363.184717 depth/1341839363.184717.png +1341839363.220783 rgb/1341839363.220783.png 1341839363.220795 depth/1341839363.220795.png +1341839363.252646 rgb/1341839363.252646.png 1341839363.252661 depth/1341839363.252661.png +1341839363.288713 rgb/1341839363.288713.png 1341839363.289488 depth/1341839363.289488.png +1341839363.320693 rgb/1341839363.320693.png 1341839363.320701 depth/1341839363.320701.png +1341839363.352718 rgb/1341839363.352718.png 1341839363.352737 depth/1341839363.352737.png +1341839363.388705 rgb/1341839363.388705.png 1341839363.388748 depth/1341839363.388748.png +1341839363.420746 rgb/1341839363.420746.png 1341839363.420760 depth/1341839363.420760.png +1341839363.452892 rgb/1341839363.452892.png 1341839363.452907 depth/1341839363.452907.png +1341839363.488698 rgb/1341839363.488698.png 1341839363.488720 depth/1341839363.488720.png +1341839363.520896 rgb/1341839363.520896.png 1341839363.520904 depth/1341839363.520904.png +1341839363.556670 rgb/1341839363.556670.png 1341839363.556678 depth/1341839363.556678.png +1341839363.588697 rgb/1341839363.588697.png 1341839363.588713 depth/1341839363.588713.png +1341839363.620692 rgb/1341839363.620692.png 1341839363.621300 depth/1341839363.621300.png +1341839363.656709 rgb/1341839363.656709.png 1341839363.656723 depth/1341839363.656723.png +1341839363.713762 rgb/1341839363.713762.png 1341839363.713784 depth/1341839363.713784.png +1341839363.749603 rgb/1341839363.749603.png 1341839363.749630 depth/1341839363.749630.png +1341839363.781800 rgb/1341839363.781800.png 1341839363.781815 depth/1341839363.781815.png +1341839363.817716 rgb/1341839363.817716.png 1341839363.818286 depth/1341839363.818286.png +1341839363.849637 rgb/1341839363.849637.png 1341839363.849647 depth/1341839363.849647.png +1341839363.881770 rgb/1341839363.881770.png 1341839363.881834 depth/1341839363.881834.png +1341839363.917738 rgb/1341839363.917738.png 1341839363.917748 depth/1341839363.917748.png +1341839363.949778 rgb/1341839363.949778.png 1341839363.949819 depth/1341839363.949819.png +1341839363.985613 rgb/1341839363.985613.png 1341839363.985653 depth/1341839363.985653.png +1341839364.017747 rgb/1341839364.017747.png 1341839364.017757 depth/1341839364.017757.png +1341839364.049835 rgb/1341839364.049835.png 1341839364.049845 depth/1341839364.049845.png +1341839364.085694 rgb/1341839364.085694.png 1341839364.085748 depth/1341839364.085748.png +1341839364.117765 rgb/1341839364.117765.png 1341839364.117780 depth/1341839364.117780.png +1341839364.149652 rgb/1341839364.149652.png 1341839364.149747 depth/1341839364.149747.png +1341839364.185672 rgb/1341839364.185672.png 1341839364.185688 depth/1341839364.185688.png +1341839364.217809 rgb/1341839364.217809.png 1341839364.217822 depth/1341839364.217822.png +1341839364.253809 rgb/1341839364.253809.png 1341839364.253826 depth/1341839364.253826.png +1341839364.285702 rgb/1341839364.285702.png 1341839364.286246 depth/1341839364.286246.png +1341839364.317689 rgb/1341839364.317689.png 1341839364.317704 depth/1341839364.317704.png +1341839364.353709 rgb/1341839364.353709.png 1341839364.353723 depth/1341839364.353723.png +1341839364.385786 rgb/1341839364.385786.png 1341839364.385804 depth/1341839364.385804.png diff --git a/Examples/RGB-D/rgbd_tum.cc b/Examples/RGB-D/rgbd_tum.cc new file mode 100644 index 0000000000..6af5bf3317 --- /dev/null +++ b/Examples/RGB-D/rgbd_tum.cc @@ -0,0 +1,166 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strAssociationFilename, vector &vstrImageFilenamesRGB, + vector &vstrImageFilenamesD, vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 5) + { + cerr << endl << "Usage: ./rgbd_tum path_to_vocabulary path_to_settings path_to_sequence path_to_association" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageFilenamesRGB; + vector vstrImageFilenamesD; + vector vTimestamps; + string strAssociationFilename = string(argv[4]); + LoadImages(strAssociationFilename, vstrImageFilenamesRGB, vstrImageFilenamesD, vTimestamps); + + // Check consistency in the number of images and depthmaps + int nImages = vstrImageFilenamesRGB.size(); + if(vstrImageFilenamesRGB.empty()) + { + cerr << endl << "No images found in provided path." << endl; + return 1; + } + else if(vstrImageFilenamesD.size()!=vstrImageFilenamesRGB.size()) + { + cerr << endl << "Different number of images for rgb and depth." << endl; + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::RGBD,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + cout << endl << "-------" << endl; + cout << "Start processing sequence ..." << endl; + cout << "Images in the sequence: " << nImages << endl << endl; + + // Main loop + cv::Mat imRGB, imD; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageFilenamesRGB, + vector &vstrImageFilenamesD, vector &vTimestamps) +{ + ifstream fAssociation; + fAssociation.open(strAssociationFilename.c_str()); + while(!fAssociation.eof()) + { + string s; + getline(fAssociation,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + double t; + string sRGB, sD; + ss >> t; + vTimestamps.push_back(t); + ss >> sRGB; + vstrImageFilenamesRGB.push_back(sRGB); + ss >> t; + ss >> sD; + vstrImageFilenamesD.push_back(sD); + + } + } +} diff --git a/Examples/ROS/ORB_SLAM2/CMakeLists.txt b/Examples/ROS/ORB_SLAM2/CMakeLists.txt new file mode 100644 index 0000000000..df2ae91ff3 --- /dev/null +++ b/Examples/ROS/ORB_SLAM2/CMakeLists.txt @@ -0,0 +1,70 @@ +cmake_minimum_required(VERSION 2.4.6) +include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) + +rosbuild_init() + +IF(NOT ROS_BUILD_TYPE) + SET(ROS_BUILD_TYPE Release) +ENDIF() + +MESSAGE("Build type: " ${ROS_BUILD_TYPE}) + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") + +# Check C++11 or C++0x support +include(CheckCXXCompilerFlag) +CHECK_CXX_COMPILER_FLAG("-std=c++11" COMPILER_SUPPORTS_CXX11) +CHECK_CXX_COMPILER_FLAG("-std=c++0x" COMPILER_SUPPORTS_CXX0X) +if(COMPILER_SUPPORTS_CXX11) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") + add_definitions(-DCOMPILEDWITHC11) + message(STATUS "Using flag -std=c++11.") +elseif(COMPILER_SUPPORTS_CXX0X) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") + add_definitions(-DCOMPILEDWITHC0X) + message(STATUS "Using flag -std=c++0x.") +else() + message(FATAL_ERROR "The compiler ${CMAKE_CXX_COMPILER} has no C++11 support. Please use a different C++ compiler.") +endif() + +LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/../../../cmake_modules) + +find_package(OpenCV 2.4.3 REQUIRED) +find_package(Eigen3 3.1.0 REQUIRED) +find_package(Pangolin REQUIRED) + +include_directories( +${PROJECT_SOURCE_DIR} +${PROJECT_SOURCE_DIR}/../../../ +${PROJECT_SOURCE_DIR}/../../../include +${Pangolin_INCLUDE_DIRS} +) + +set(LIBS +${OpenCV_LIBS} +${EIGEN3_LIBS} +${Pangolin_LIBRARIES} +${PROJECT_SOURCE_DIR}/../../../Thirdparty/DBoW2/lib/libDBoW2.so +${PROJECT_SOURCE_DIR}/../../../Thirdparty/g2o/lib/libg2o.so +${PROJECT_SOURCE_DIR}/../../../lib/libORB_SLAM2.so +) + +# Node for monocular camera +rosbuild_add_executable(Mono +src/ros_mono.cc +) + +target_link_libraries(Mono +${LIBS} +) + +# Node for RGB-D camera +rosbuild_add_executable(RGBD +src/ros_rgbd.cc +) + +target_link_libraries(RGBD +${LIBS} +) + diff --git a/Examples/ROS/ORB_SLAM2/manifest.xml b/Examples/ROS/ORB_SLAM2/manifest.xml new file mode 100644 index 0000000000..b40564f796 --- /dev/null +++ b/Examples/ROS/ORB_SLAM2/manifest.xml @@ -0,0 +1,19 @@ + + + + ORB_SLAM2 + + + Raul Mur-Artal + GPLv3 + + + + + + + + + + + diff --git a/Examples/ROS/ORB_SLAM2/src/ros_mono.cc b/Examples/ROS/ORB_SLAM2/src/ros_mono.cc new file mode 100644 index 0000000000..2913525bfc --- /dev/null +++ b/Examples/ROS/ORB_SLAM2/src/ros_mono.cc @@ -0,0 +1,96 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include +#include +#include +#include + +#include +#include + +#include + +#include"../../../include/System.h" + +using namespace std; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){} + + void GrabImage(const sensor_msgs::ImageConstPtr& msg); + + ORB_SLAM2::System* mpSLAM; +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "Mono"); + ros::start(); + + if(argc != 3) + { + cerr << endl << "Usage: rosrun ORB_SLAM2 Mono path_to_vocabulary path_to_settings" << endl; + ros::shutdown(); + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::MONOCULAR,true); + + ImageGrabber igb(&SLAM); + + ros::NodeHandle nodeHandler; + ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb); + + ros::spin(); + + // Stop all threads + SLAM.Shutdown(); + + // Save camera trajectory + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); + + ros::shutdown(); + + return 0; +} + +void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptr; + try + { + cv_ptr = cv_bridge::toCvShare(msg); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); +} + + diff --git a/Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc b/Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc new file mode 100644 index 0000000000..85cdb3e18f --- /dev/null +++ b/Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc @@ -0,0 +1,122 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include"../../../include/System.h" + +using namespace std; + +class ImageGrabber +{ +public: + ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){} + + void GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD); + + ORB_SLAM2::System* mpSLAM; +}; + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "RGBD"); + ros::start(); + + if(argc != 3) + { + cerr << endl << "Usage: rosrun ORB_SLAM2 RGBD path_to_vocabulary path_to_settings" << endl; + ros::shutdown(); + return 1; + } + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::RGBD,true); + + ImageGrabber igb(&SLAM); + + ros::NodeHandle nh; + + message_filters::Subscriber rgb_sub(nh, "/camera/rgb/image_raw", 1); + message_filters::Subscriber depth_sub(nh, "camera/depth_registered/image_raw", 1); + typedef message_filters::sync_policies::ApproximateTime sync_pol; + message_filters::Synchronizer sync(sync_pol(10), rgb_sub,depth_sub); + sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD,&igb,_1,_2)); + + ros::spin(); + + // Stop all threads + SLAM.Shutdown(); + + // Save camera trajectory + SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); + + ros::shutdown(); + + return 0; +} + +void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD) +{ + // Copy the ros image message to cv::Mat. + cv_bridge::CvImageConstPtr cv_ptrRGB; + try + { + cv_ptrRGB = cv_bridge::toCvShare(msgRGB); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + cv_bridge::CvImageConstPtr cv_ptrD; + try + { + cv_ptrD = cv_bridge::toCvShare(msgD); + } + catch (cv_bridge::Exception& e) + { + ROS_ERROR("cv_bridge exception: %s", e.what()); + return; + } + + cout << cv_ptrD->image.rows << " x " << cv_ptrD->image.cols << ", type: " << cv_ptrD->image.type() << endl; + /*cv::imshow("rgb",cv_ptrRGB->image); + cv::imshow("depth",cv_ptrD->image); + + cv::waitKey(20);*/ + + + mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec()); +} + + diff --git a/Examples/Stereo/KITTI00-02.yaml b/Examples/Stereo/KITTI00-02.yaml new file mode 100644 index 0000000000..f67dc0c3af --- /dev/null +++ b/Examples/Stereo/KITTI00-02.yaml @@ -0,0 +1,66 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 718.856 +Camera.fy: 718.856 +Camera.cx: 607.1928 +Camera.cy: 185.2157 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +Camera.width: 1241 +Camera.height: 376 + +# Camera frames per second +Camera.fps: 10.0 + +# stereo baseline times fx +Camera.bf: 386.1448 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 35 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 2000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.6 +Viewer.KeyFrameLineWidth: 2 +Viewer.GraphLineWidth: 1 +Viewer.PointSize:2 +Viewer.CameraSize: 0.7 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -100 +Viewer.ViewpointZ: -0.1 +Viewer.ViewpointF: 2000 + diff --git a/Examples/Stereo/KITTI03.yaml b/Examples/Stereo/KITTI03.yaml new file mode 100644 index 0000000000..0e805b382e --- /dev/null +++ b/Examples/Stereo/KITTI03.yaml @@ -0,0 +1,66 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 721.5377 +Camera.fy: 721.5377 +Camera.cx: 609.5593 +Camera.cy: 172.854 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +Camera.width: 1241 +Camera.height: 376 + +# Camera frames per second +Camera.fps: 10.0 + +# stereo baseline times fx +Camera.bf: 387.5744 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 40 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 2000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 20 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.6 +Viewer.KeyFrameLineWidth: 2 +Viewer.GraphLineWidth: 1 +Viewer.PointSize:2 +Viewer.CameraSize: 0.7 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -100 +Viewer.ViewpointZ: -0.1 +Viewer.ViewpointF: 2000 + diff --git a/Examples/Stereo/KITTI04-12.yaml b/Examples/Stereo/KITTI04-12.yaml new file mode 100644 index 0000000000..80f5b3b3d2 --- /dev/null +++ b/Examples/Stereo/KITTI04-12.yaml @@ -0,0 +1,66 @@ +%YAML:1.0 + +#-------------------------------------------------------------------------------------------- +# Camera Parameters. Adjust them! +#-------------------------------------------------------------------------------------------- + +# Camera calibration and distortion parameters (OpenCV) +Camera.fx: 707.0912 +Camera.fy: 707.0912 +Camera.cx: 601.8873 +Camera.cy: 183.1104 + +Camera.k1: 0.0 +Camera.k2: 0.0 +Camera.p1: 0.0 +Camera.p2: 0.0 + +Camera.width: 1241 +Camera.height: 376 + +# Camera frames per second +Camera.fps: 10.0 + +# stereo baseline times fx +Camera.bf: 379.8145 + +# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale) +Camera.RGB: 1 + +# Close/Far threshold. Baseline times. +ThDepth: 40 + +#-------------------------------------------------------------------------------------------- +# ORB Parameters +#-------------------------------------------------------------------------------------------- + +# ORB Extractor: Number of features per image +ORBextractor.nFeatures: 2000 + +# ORB Extractor: Scale factor between levels in the scale pyramid +ORBextractor.scaleFactor: 1.2 + +# ORB Extractor: Number of levels in the scale pyramid +ORBextractor.nLevels: 8 + +# ORB Extractor: Fast threshold +# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response. +# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST +# You can lower these values if your images have low contrast +ORBextractor.iniThFAST: 12 +ORBextractor.minThFAST: 7 + +#-------------------------------------------------------------------------------------------- +# Viewer Parameters +#-------------------------------------------------------------------------------------------- +Viewer.KeyFrameSize: 0.6 +Viewer.KeyFrameLineWidth: 2 +Viewer.GraphLineWidth: 1 +Viewer.PointSize:2 +Viewer.CameraSize: 0.7 +Viewer.CameraLineWidth: 3 +Viewer.ViewpointX: 0 +Viewer.ViewpointY: -100 +Viewer.ViewpointZ: -0.1 +Viewer.ViewpointF: 2000 + diff --git a/Examples/Stereo/stereo_kitti.cc b/Examples/Stereo/stereo_kitti.cc new file mode 100644 index 0000000000..da0ccb7bca --- /dev/null +++ b/Examples/Stereo/stereo_kitti.cc @@ -0,0 +1,163 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include +#include +#include +#include + +#include + +#include + +using namespace std; + +void LoadImages(const string &strPathToSequence, vector &vstrImageLeft, + vector &vstrImageRight, vector &vTimestamps); + +int main(int argc, char **argv) +{ + if(argc != 4) + { + cerr << endl << "Usage: ./stereo_kitti path_to_vocabulary path_to_settings path_to_sequence" << endl; + return 1; + } + + // Retrieve paths to images + vector vstrImageLeft; + vector vstrImageRight; + vector vTimestamps; + LoadImages(string(argv[3]), vstrImageLeft, vstrImageRight, vTimestamps); + + const int nImages = vstrImageLeft.size(); + + // Create SLAM system. It initializes all system threads and gets ready to process frames. + ORB_SLAM2::System SLAM(argv[1],argv[2],ORB_SLAM2::System::STEREO,true); + + // Vector for tracking time statistics + vector vTimesTrack; + vTimesTrack.resize(nImages); + + cout << endl << "-------" << endl; + cout << "Start processing sequence ..." << endl; + cout << "Images in the sequence: " << nImages << endl << endl; + + // Main loop + cv::Mat imLeft, imRight; + for(int ni=0; ni >(t2 - t1).count(); + + vTimesTrack[ni]=ttrack; + + // Wait to load the next frame + double T=0; + if(ni0) + T = tframe-vTimestamps[ni-1]; + + if(ttrack &vstrImageLeft, + vector &vstrImageRight, vector &vTimestamps) +{ + ifstream fTimes; + string strPathTimeFile = strPathToSequence + "/times.txt"; + fTimes.open(strPathTimeFile.c_str()); + while(!fTimes.eof()) + { + string s; + getline(fTimes,s); + if(!s.empty()) + { + stringstream ss; + ss << s; + double t; + ss >> t; + vTimestamps.push_back(t); + } + } + + string strPrefixLeft = strPathToSequence + "/image_0/"; + string strPrefixRight = strPathToSequence + "/image_1/"; + + const int nTimes = vTimestamps.size(); + vstrImageLeft.resize(nTimes); + vstrImageRight.resize(nTimes); + + for(int i=0; i + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/Thirdparty/DBoW2/CMakeLists.txt b/Thirdparty/DBoW2/CMakeLists.txt new file mode 100644 index 0000000000..4da56b2bcd --- /dev/null +++ b/Thirdparty/DBoW2/CMakeLists.txt @@ -0,0 +1,34 @@ +cmake_minimum_required(VERSION 2.8) +project(DBoW2) + +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wall -O3 -march=native ") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -O3 -march=native") + +set(HDRS_DBOW2 + DBoW2/BowVector.h + DBoW2/FORB.h + DBoW2/FClass.h + DBoW2/FeatureVector.h + DBoW2/ScoringObject.h + DBoW2/TemplatedVocabulary.h) +set(SRCS_DBOW2 + DBoW2/BowVector.cpp + DBoW2/FORB.cpp + DBoW2/FeatureVector.cpp + DBoW2/ScoringObject.cpp) + +set(HDRS_DUTILS + DUtils/Random.h + DUtils/Timestamp.h) +set(SRCS_DUTILS + DUtils/Random.cpp + DUtils/Timestamp.cpp) + +find_package(OpenCV REQUIRED) + +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + +include_directories(${OpenCV_INCLUDE_DIRS}) +add_library(DBoW2 SHARED ${SRCS_DBOW2} ${SRCS_DUTILS}) +target_link_libraries(DBoW2 ${OpenCV_LIBS}) + diff --git a/Thirdparty/DBoW2/DBoW2/BowVector.cpp b/Thirdparty/DBoW2/DBoW2/BowVector.cpp new file mode 100644 index 0000000000..1337fa3e5b --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/BowVector.cpp @@ -0,0 +1,130 @@ +/** + * File: BowVector.cpp + * Date: March 2011 + * Author: Dorian Galvez-Lopez + * Description: bag of words vector + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include +#include +#include + +#include "BowVector.h" + +namespace DBoW2 { + +// -------------------------------------------------------------------------- + +BowVector::BowVector(void) +{ +} + +// -------------------------------------------------------------------------- + +BowVector::~BowVector(void) +{ +} + +// -------------------------------------------------------------------------- + +void BowVector::addWeight(WordId id, WordValue v) +{ + BowVector::iterator vit = this->lower_bound(id); + + if(vit != this->end() && !(this->key_comp()(id, vit->first))) + { + vit->second += v; + } + else + { + this->insert(vit, BowVector::value_type(id, v)); + } +} + +// -------------------------------------------------------------------------- + +void BowVector::addIfNotExist(WordId id, WordValue v) +{ + BowVector::iterator vit = this->lower_bound(id); + + if(vit == this->end() || (this->key_comp()(id, vit->first))) + { + this->insert(vit, BowVector::value_type(id, v)); + } +} + +// -------------------------------------------------------------------------- + +void BowVector::normalize(LNorm norm_type) +{ + double norm = 0.0; + BowVector::iterator it; + + if(norm_type == DBoW2::L1) + { + for(it = begin(); it != end(); ++it) + norm += fabs(it->second); + } + else + { + for(it = begin(); it != end(); ++it) + norm += it->second * it->second; + norm = sqrt(norm); + } + + if(norm > 0.0) + { + for(it = begin(); it != end(); ++it) + it->second /= norm; + } +} + +// -------------------------------------------------------------------------- + +std::ostream& operator<< (std::ostream &out, const BowVector &v) +{ + BowVector::const_iterator vit; + std::vector::const_iterator iit; + unsigned int i = 0; + const unsigned int N = v.size(); + for(vit = v.begin(); vit != v.end(); ++vit, ++i) + { + out << "<" << vit->first << ", " << vit->second << ">"; + + if(i < N-1) out << ", "; + } + return out; +} + +// -------------------------------------------------------------------------- + +void BowVector::saveM(const std::string &filename, size_t W) const +{ + std::fstream f(filename.c_str(), std::ios::out); + + WordId last = 0; + BowVector::const_iterator bit; + for(bit = this->begin(); bit != this->end(); ++bit) + { + for(; last < bit->first; ++last) + { + f << "0 "; + } + f << bit->second << " "; + + last = bit->first + 1; + } + for(; last < (WordId)W; ++last) + f << "0 "; + + f.close(); +} + +// -------------------------------------------------------------------------- + +} // namespace DBoW2 + diff --git a/Thirdparty/DBoW2/DBoW2/BowVector.h b/Thirdparty/DBoW2/DBoW2/BowVector.h new file mode 100644 index 0000000000..f559811deb --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/BowVector.h @@ -0,0 +1,109 @@ +/** + * File: BowVector.h + * Date: March 2011 + * Author: Dorian Galvez-Lopez + * Description: bag of words vector + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_BOW_VECTOR__ +#define __D_T_BOW_VECTOR__ + +#include +#include +#include + +namespace DBoW2 { + +/// Id of words +typedef unsigned int WordId; + +/// Value of a word +typedef double WordValue; + +/// Id of nodes in the vocabulary treee +typedef unsigned int NodeId; + +/// L-norms for normalization +enum LNorm +{ + L1, + L2 +}; + +/// Weighting type +enum WeightingType +{ + TF_IDF, + TF, + IDF, + BINARY +}; + +/// Scoring type +enum ScoringType +{ + L1_NORM, + L2_NORM, + CHI_SQUARE, + KL, + BHATTACHARYYA, + DOT_PRODUCT, +}; + +/// Vector of words to represent images +class BowVector: + public std::map +{ +public: + + /** + * Constructor + */ + BowVector(void); + + /** + * Destructor + */ + ~BowVector(void); + + /** + * Adds a value to a word value existing in the vector, or creates a new + * word with the given value + * @param id word id to look for + * @param v value to create the word with, or to add to existing word + */ + void addWeight(WordId id, WordValue v); + + /** + * Adds a word with a value to the vector only if this does not exist yet + * @param id word id to look for + * @param v value to give to the word if this does not exist + */ + void addIfNotExist(WordId id, WordValue v); + + /** + * L1-Normalizes the values in the vector + * @param norm_type norm used + */ + void normalize(LNorm norm_type); + + /** + * Prints the content of the bow vector + * @param out stream + * @param v + */ + friend std::ostream& operator<<(std::ostream &out, const BowVector &v); + + /** + * Saves the bow vector as a vector in a matlab file + * @param filename + * @param W number of words in the vocabulary + */ + void saveM(const std::string &filename, size_t W) const; +}; + +} // namespace DBoW2 + +#endif diff --git a/Thirdparty/DBoW2/DBoW2/FClass.h b/Thirdparty/DBoW2/DBoW2/FClass.h new file mode 100644 index 0000000000..13be53d753 --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/FClass.h @@ -0,0 +1,71 @@ +/** + * File: FClass.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: generic FClass to instantiate templated classes + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_FCLASS__ +#define __D_T_FCLASS__ + +#include +#include +#include + +namespace DBoW2 { + +/// Generic class to encapsulate functions to manage descriptors. +/** + * This class must be inherited. Derived classes can be used as the + * parameter F when creating Templated structures + * (TemplatedVocabulary, TemplatedDatabase, ...) + */ +class FClass +{ + class TDescriptor; + typedef const TDescriptor *pDescriptor; + + /** + * Calculates the mean value of a set of descriptors + * @param descriptors + * @param mean mean descriptor + */ + virtual void meanValue(const std::vector &descriptors, + TDescriptor &mean) = 0; + + /** + * Calculates the distance between two descriptors + * @param a + * @param b + * @return distance + */ + static double distance(const TDescriptor &a, const TDescriptor &b); + + /** + * Returns a string version of the descriptor + * @param a descriptor + * @return string version + */ + static std::string toString(const TDescriptor &a); + + /** + * Returns a descriptor from a string + * @param a descriptor + * @param s string version + */ + static void fromString(TDescriptor &a, const std::string &s); + + /** + * Returns a mat with the descriptors in float format + * @param descriptors + * @param mat (out) NxL 32F matrix + */ + static void toMat32F(const std::vector &descriptors, + cv::Mat &mat); +}; + +} // namespace DBoW2 + +#endif diff --git a/Thirdparty/DBoW2/DBoW2/FORB.cpp b/Thirdparty/DBoW2/DBoW2/FORB.cpp new file mode 100644 index 0000000000..1f1990c2f7 --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/FORB.cpp @@ -0,0 +1,193 @@ +/** + * File: FORB.cpp + * Date: June 2012 + * Author: Dorian Galvez-Lopez + * Description: functions for ORB descriptors + * License: see the LICENSE.txt file + * + * Distance function has been modified + * + */ + + +#include +#include +#include +#include + +#include "FORB.h" + +using namespace std; + +namespace DBoW2 { + +// -------------------------------------------------------------------------- + +const int FORB::L=32; + +void FORB::meanValue(const std::vector &descriptors, + FORB::TDescriptor &mean) +{ + if(descriptors.empty()) + { + mean.release(); + return; + } + else if(descriptors.size() == 1) + { + mean = descriptors[0]->clone(); + } + else + { + vector sum(FORB::L * 8, 0); + + for(size_t i = 0; i < descriptors.size(); ++i) + { + const cv::Mat &d = *descriptors[i]; + const unsigned char *p = d.ptr(); + + for(int j = 0; j < d.cols; ++j, ++p) + { + if(*p & (1 << 7)) ++sum[ j*8 ]; + if(*p & (1 << 6)) ++sum[ j*8 + 1 ]; + if(*p & (1 << 5)) ++sum[ j*8 + 2 ]; + if(*p & (1 << 4)) ++sum[ j*8 + 3 ]; + if(*p & (1 << 3)) ++sum[ j*8 + 4 ]; + if(*p & (1 << 2)) ++sum[ j*8 + 5 ]; + if(*p & (1 << 1)) ++sum[ j*8 + 6 ]; + if(*p & (1)) ++sum[ j*8 + 7 ]; + } + } + + mean = cv::Mat::zeros(1, FORB::L, CV_8U); + unsigned char *p = mean.ptr(); + + const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; + for(size_t i = 0; i < sum.size(); ++i) + { + if(sum[i] >= N2) + { + // set bit + *p |= 1 << (7 - (i % 8)); + } + + if(i % 8 == 7) ++p; + } + } +} + +// -------------------------------------------------------------------------- + +int FORB::distance(const FORB::TDescriptor &a, + const FORB::TDescriptor &b) +{ + // Bit set count operation from + // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel + + const int *pa = a.ptr(); + const int *pb = b.ptr(); + + int dist=0; + + for(int i=0; i<8; i++, pa++, pb++) + { + unsigned int v = *pa ^ *pb; + v = v - ((v >> 1) & 0x55555555); + v = (v & 0x33333333) + ((v >> 2) & 0x33333333); + dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24; + } + + return dist; +} + +// -------------------------------------------------------------------------- + +std::string FORB::toString(const FORB::TDescriptor &a) +{ + stringstream ss; + const unsigned char *p = a.ptr(); + + for(int i = 0; i < a.cols; ++i, ++p) + { + ss << (int)*p << " "; + } + + return ss.str(); +} + +// -------------------------------------------------------------------------- + +void FORB::fromString(FORB::TDescriptor &a, const std::string &s) +{ + a.create(1, FORB::L, CV_8U); + unsigned char *p = a.ptr(); + + stringstream ss(s); + for(int i = 0; i < FORB::L; ++i, ++p) + { + int n; + ss >> n; + + if(!ss.fail()) + *p = (unsigned char)n; + } + +} + +// -------------------------------------------------------------------------- + +void FORB::toMat32F(const std::vector &descriptors, + cv::Mat &mat) +{ + if(descriptors.empty()) + { + mat.release(); + return; + } + + const size_t N = descriptors.size(); + + mat.create(N, FORB::L*8, CV_32F); + float *p = mat.ptr(); + + for(size_t i = 0; i < N; ++i) + { + const int C = descriptors[i].cols; + const unsigned char *desc = descriptors[i].ptr(); + + for(int j = 0; j < C; ++j, p += 8) + { + p[0] = (desc[j] & (1 << 7) ? 1 : 0); + p[1] = (desc[j] & (1 << 6) ? 1 : 0); + p[2] = (desc[j] & (1 << 5) ? 1 : 0); + p[3] = (desc[j] & (1 << 4) ? 1 : 0); + p[4] = (desc[j] & (1 << 3) ? 1 : 0); + p[5] = (desc[j] & (1 << 2) ? 1 : 0); + p[6] = (desc[j] & (1 << 1) ? 1 : 0); + p[7] = desc[j] & (1); + } + } +} + +// -------------------------------------------------------------------------- + +void FORB::toMat8U(const std::vector &descriptors, + cv::Mat &mat) +{ + mat.create(descriptors.size(), 32, CV_8U); + + unsigned char *p = mat.ptr(); + + for(size_t i = 0; i < descriptors.size(); ++i, p += 32) + { + const unsigned char *d = descriptors[i].ptr(); + std::copy(d, d+32, p); + } + +} + +// -------------------------------------------------------------------------- + +} // namespace DBoW2 + + diff --git a/Thirdparty/DBoW2/DBoW2/FORB.h b/Thirdparty/DBoW2/DBoW2/FORB.h new file mode 100644 index 0000000000..a39599f20e --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/FORB.h @@ -0,0 +1,79 @@ +/** + * File: FORB.h + * Date: June 2012 + * Author: Dorian Galvez-Lopez + * Description: functions for ORB descriptors + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_F_ORB__ +#define __D_T_F_ORB__ + +#include +#include +#include + +#include "FClass.h" + +namespace DBoW2 { + +/// Functions to manipulate ORB descriptors +class FORB: protected FClass +{ +public: + + /// Descriptor type + typedef cv::Mat TDescriptor; // CV_8U + /// Pointer to a single descriptor + typedef const TDescriptor *pDescriptor; + /// Descriptor length (in bytes) + static const int L; + + /** + * Calculates the mean value of a set of descriptors + * @param descriptors + * @param mean mean descriptor + */ + static void meanValue(const std::vector &descriptors, + TDescriptor &mean); + + /** + * Calculates the distance between two descriptors + * @param a + * @param b + * @return distance + */ + static int distance(const TDescriptor &a, const TDescriptor &b); + + /** + * Returns a string version of the descriptor + * @param a descriptor + * @return string version + */ + static std::string toString(const TDescriptor &a); + + /** + * Returns a descriptor from a string + * @param a descriptor + * @param s string version + */ + static void fromString(TDescriptor &a, const std::string &s); + + /** + * Returns a mat with the descriptors in float format + * @param descriptors + * @param mat (out) NxL 32F matrix + */ + static void toMat32F(const std::vector &descriptors, + cv::Mat &mat); + + static void toMat8U(const std::vector &descriptors, + cv::Mat &mat); + +}; + +} // namespace DBoW2 + +#endif + diff --git a/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp b/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp new file mode 100644 index 0000000000..c055a15767 --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/FeatureVector.cpp @@ -0,0 +1,85 @@ +/** + * File: FeatureVector.cpp + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: feature vector + * License: see the LICENSE.txt file + * + */ + +#include "FeatureVector.h" +#include +#include +#include + +namespace DBoW2 { + +// --------------------------------------------------------------------------- + +FeatureVector::FeatureVector(void) +{ +} + +// --------------------------------------------------------------------------- + +FeatureVector::~FeatureVector(void) +{ +} + +// --------------------------------------------------------------------------- + +void FeatureVector::addFeature(NodeId id, unsigned int i_feature) +{ + FeatureVector::iterator vit = this->lower_bound(id); + + if(vit != this->end() && vit->first == id) + { + vit->second.push_back(i_feature); + } + else + { + vit = this->insert(vit, FeatureVector::value_type(id, + std::vector() )); + vit->second.push_back(i_feature); + } +} + +// --------------------------------------------------------------------------- + +std::ostream& operator<<(std::ostream &out, + const FeatureVector &v) +{ + if(!v.empty()) + { + FeatureVector::const_iterator vit = v.begin(); + + const std::vector* f = &vit->second; + + out << "<" << vit->first << ": ["; + if(!f->empty()) out << (*f)[0]; + for(unsigned int i = 1; i < f->size(); ++i) + { + out << ", " << (*f)[i]; + } + out << "]>"; + + for(++vit; vit != v.end(); ++vit) + { + f = &vit->second; + + out << ", <" << vit->first << ": ["; + if(!f->empty()) out << (*f)[0]; + for(unsigned int i = 1; i < f->size(); ++i) + { + out << ", " << (*f)[i]; + } + out << "]>"; + } + } + + return out; +} + +// --------------------------------------------------------------------------- + +} // namespace DBoW2 diff --git a/Thirdparty/DBoW2/DBoW2/FeatureVector.h b/Thirdparty/DBoW2/DBoW2/FeatureVector.h new file mode 100644 index 0000000000..08a91def7c --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/FeatureVector.h @@ -0,0 +1,56 @@ +/** + * File: FeatureVector.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: feature vector + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_FEATURE_VECTOR__ +#define __D_T_FEATURE_VECTOR__ + +#include "BowVector.h" +#include +#include +#include + +namespace DBoW2 { + +/// Vector of nodes with indexes of local features +class FeatureVector: + public std::map > +{ +public: + + /** + * Constructor + */ + FeatureVector(void); + + /** + * Destructor + */ + ~FeatureVector(void); + + /** + * Adds a feature to an existing node, or adds a new node with an initial + * feature + * @param id node id to add or to modify + * @param i_feature index of feature to add to the given node + */ + void addFeature(NodeId id, unsigned int i_feature); + + /** + * Sends a string versions of the feature vector through the stream + * @param out stream + * @param v feature vector + */ + friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v); + +}; + +} // namespace DBoW2 + +#endif + diff --git a/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp b/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp new file mode 100644 index 0000000000..063a96e87d --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/ScoringObject.cpp @@ -0,0 +1,315 @@ +/** + * File: ScoringObject.cpp + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: functions to compute bow scores + * License: see the LICENSE.txt file + * + */ + +#include +#include "TemplatedVocabulary.h" +#include "BowVector.h" + +using namespace DBoW2; + +// If you change the type of WordValue, make sure you change also the +// epsilon value (this is needed by the KL method) +const double GeneralScoring::LOG_EPS = log(DBL_EPSILON); // FLT_EPSILON + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double L1Scoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += fabs(vi - wi) - fabs(vi) - fabs(wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) + // for all i | v_i != 0 and w_i != 0 + // (Nister, 2006) + // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} + score = -score/2.0; + + return score; // [0..1] +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double L2Scoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += vi * wi; + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) ) + // for all i | v_i != 0 and w_i != 0 ) + // (Nister, 2006) + if(score >= 1) // rounding errors + score = 1.0; + else + score = 1.0 - sqrt(1.0 - score); // [0..1] + + return score; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double ChiSquareScoring::score(const BowVector &v1, const BowVector &v2) + const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + // all the items are taken into account + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) + // we move the -4 out + if(vi + wi != 0.0) score += vi * wi / (vi + wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + } + } + + // this takes the -4 into account + score = 2. * score; // [0..1] + + return score; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double KLScoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + // all the items or v are taken into account + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + if(vi != 0 && wi != 0) score += vi * log(vi/wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + score += vi * (log(vi) - LOG_EPS); + ++v1_it; + } + else + { + // move v2_it forward, do not add any score + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // sum rest of items of v + for(; v1_it != v1_end; ++v1_it) + if(v1_it->second != 0) + score += v1_it->second * (log(v1_it->second) - LOG_EPS); + + return score; // cannot be scaled +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double BhattacharyyaScoring::score(const BowVector &v1, + const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += sqrt(vi * wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + return score; // already scaled +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double DotProductScoring::score(const BowVector &v1, + const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += vi * wi; + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + return score; // cannot scale +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + diff --git a/Thirdparty/DBoW2/DBoW2/ScoringObject.h b/Thirdparty/DBoW2/DBoW2/ScoringObject.h new file mode 100644 index 0000000000..8d5b82192a --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/ScoringObject.h @@ -0,0 +1,96 @@ +/** + * File: ScoringObject.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: functions to compute bow scores + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_SCORING_OBJECT__ +#define __D_T_SCORING_OBJECT__ + +#include "BowVector.h" + +namespace DBoW2 { + +/// Base class of scoring functions +class GeneralScoring +{ +public: + /** + * Computes the score between two vectors. Vectors must be sorted and + * normalized if necessary + * @param v (in/out) + * @param w (in/out) + * @return score + */ + virtual double score(const BowVector &v, const BowVector &w) const = 0; + + /** + * Returns whether a vector must be normalized before scoring according + * to the scoring scheme + * @param norm norm to use + * @return true iff must normalize + */ + virtual bool mustNormalize(LNorm &norm) const = 0; + + /// Log of epsilon + static const double LOG_EPS; + // If you change the type of WordValue, make sure you change also the + // epsilon value (this is needed by the KL method) + + virtual ~GeneralScoring() {} //!< Required for virtual base classes + +}; + +/** + * Macro for defining Scoring classes + * @param NAME name of class + * @param MUSTNORMALIZE if vectors must be normalized to compute the score + * @param NORM type of norm to use when MUSTNORMALIZE + */ +#define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ + NAME: public GeneralScoring \ + { public: \ + /** \ + * Computes score between two vectors \ + * @param v \ + * @param w \ + * @return score between v and w \ + */ \ + virtual double score(const BowVector &v, const BowVector &w) const; \ + \ + /** \ + * Says if a vector must be normalized according to the scoring function \ + * @param norm (out) if true, norm to use + * @return true iff vectors must be normalized \ + */ \ + virtual inline bool mustNormalize(LNorm &norm) const \ + { norm = NORM; return MUSTNORMALIZE; } \ + } + +/// L1 Scoring object +class __SCORING_CLASS(L1Scoring, true, L1); + +/// L2 Scoring object +class __SCORING_CLASS(L2Scoring, true, L2); + +/// Chi square Scoring object +class __SCORING_CLASS(ChiSquareScoring, true, L1); + +/// KL divergence Scoring object +class __SCORING_CLASS(KLScoring, true, L1); + +/// Bhattacharyya Scoring object +class __SCORING_CLASS(BhattacharyyaScoring, true, L1); + +/// Dot product Scoring object +class __SCORING_CLASS(DotProductScoring, false, L1); + +#undef __SCORING_CLASS + +} // namespace DBoW2 + +#endif + diff --git a/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h b/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h new file mode 100644 index 0000000000..01959344ed --- /dev/null +++ b/Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h @@ -0,0 +1,1665 @@ +/** + * This is a modified version of TemplatedVocabulary.h from DBoW2 (see below). + * Added functions: Save and Load from text files without using cv::FileStorage. + * Date: August 2015 + * Raúl Mur-Artal + */ + +/** + * File: TemplatedVocabulary.h + * Date: February 2011 + * Author: Dorian Galvez-Lopez + * Description: templated vocabulary + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_TEMPLATED_VOCABULARY__ +#define __D_T_TEMPLATED_VOCABULARY__ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "FeatureVector.h" +#include "BowVector.h" +#include "ScoringObject.h" + +#include "../DUtils/Random.h" + +using namespace std; + +namespace DBoW2 { + +/// @param TDescriptor class of descriptor +/// @param F class of descriptor functions +template +/// Generic Vocabulary +class TemplatedVocabulary +{ +public: + + /** + * Initiates an empty vocabulary + * @param k branching factor + * @param L depth levels + * @param weighting weighting type + * @param scoring scoring type + */ + TemplatedVocabulary(int k = 10, int L = 5, + WeightingType weighting = TF_IDF, ScoringType scoring = L1_NORM); + + /** + * Creates the vocabulary by loading a file + * @param filename + */ + TemplatedVocabulary(const std::string &filename); + + /** + * Creates the vocabulary by loading a file + * @param filename + */ + TemplatedVocabulary(const char *filename); + + /** + * Copy constructor + * @param voc + */ + TemplatedVocabulary(const TemplatedVocabulary &voc); + + /** + * Destructor + */ + virtual ~TemplatedVocabulary(); + + /** + * Assigns the given vocabulary to this by copying its data and removing + * all the data contained by this vocabulary before + * @param voc + * @return reference to this vocabulary + */ + TemplatedVocabulary& operator=( + const TemplatedVocabulary &voc); + + /** + * Creates a vocabulary from the training features with the already + * defined parameters + * @param training_features + */ + virtual void create + (const std::vector > &training_features); + + /** + * Creates a vocabulary from the training features, setting the branching + * factor and the depth levels of the tree + * @param training_features + * @param k branching factor + * @param L depth levels + */ + virtual void create + (const std::vector > &training_features, + int k, int L); + + /** + * Creates a vocabulary from the training features, setting the branching + * factor nad the depth levels of the tree, and the weighting and scoring + * schemes + */ + virtual void create + (const std::vector > &training_features, + int k, int L, WeightingType weighting, ScoringType scoring); + + /** + * Returns the number of words in the vocabulary + * @return number of words + */ + virtual inline unsigned int size() const; + + /** + * Returns whether the vocabulary is empty (i.e. it has not been trained) + * @return true iff the vocabulary is empty + */ + virtual inline bool empty() const; + + /** + * Transforms a set of descriptores into a bow vector + * @param features + * @param v (out) bow vector of weighted words + */ + virtual void transform(const std::vector& features, BowVector &v) + const; + + /** + * Transform a set of descriptors into a bow vector and a feature vector + * @param features + * @param v (out) bow vector + * @param fv (out) feature vector of nodes and feature indexes + * @param levelsup levels to go up the vocabulary tree to get the node index + */ + virtual void transform(const std::vector& features, + BowVector &v, FeatureVector &fv, int levelsup) const; + + /** + * Transforms a single feature into a word (without weight) + * @param feature + * @return word id + */ + virtual WordId transform(const TDescriptor& feature) const; + + /** + * Returns the score of two vectors + * @param a vector + * @param b vector + * @return score between vectors + * @note the vectors must be already sorted and normalized if necessary + */ + inline double score(const BowVector &a, const BowVector &b) const; + + /** + * Returns the id of the node that is "levelsup" levels from the word given + * @param wid word id + * @param levelsup 0..L + * @return node id. if levelsup is 0, returns the node id associated to the + * word id + */ + virtual NodeId getParentNode(WordId wid, int levelsup) const; + + /** + * Returns the ids of all the words that are under the given node id, + * by traversing any of the branches that goes down from the node + * @param nid starting node id + * @param words ids of words + */ + void getWordsFromNode(NodeId nid, std::vector &words) const; + + /** + * Returns the branching factor of the tree (k) + * @return k + */ + inline int getBranchingFactor() const { return m_k; } + + /** + * Returns the depth levels of the tree (L) + * @return L + */ + inline int getDepthLevels() const { return m_L; } + + /** + * Returns the real depth levels of the tree on average + * @return average of depth levels of leaves + */ + float getEffectiveLevels() const; + + /** + * Returns the descriptor of a word + * @param wid word id + * @return descriptor + */ + virtual inline TDescriptor getWord(WordId wid) const; + + /** + * Returns the weight of a word + * @param wid word id + * @return weight + */ + virtual inline WordValue getWordWeight(WordId wid) const; + + /** + * Returns the weighting method + * @return weighting method + */ + inline WeightingType getWeightingType() const { return m_weighting; } + + /** + * Returns the scoring method + * @return scoring method + */ + inline ScoringType getScoringType() const { return m_scoring; } + + /** + * Changes the weighting method + * @param type new weighting type + */ + inline void setWeightingType(WeightingType type); + + /** + * Changes the scoring method + * @param type new scoring type + */ + void setScoringType(ScoringType type); + + /** + * Loads the vocabulary from a text file + * @param filename + */ + bool loadFromTextFile(const std::string &filename); + + /** + * Saves the vocabulary into a text file + * @param filename + */ + void saveToTextFile(const std::string &filename) const; + + /** + * Saves the vocabulary into a file + * @param filename + */ + void save(const std::string &filename) const; + + /** + * Loads the vocabulary from a file + * @param filename + */ + void load(const std::string &filename); + + /** + * Saves the vocabulary to a file storage structure + * @param fn node in file storage + */ + virtual void save(cv::FileStorage &fs, + const std::string &name = "vocabulary") const; + + /** + * Loads the vocabulary from a file storage node + * @param fn first node + * @param subname name of the child node of fn where the tree is stored. + * If not given, the fn node is used instead + */ + virtual void load(const cv::FileStorage &fs, + const std::string &name = "vocabulary"); + + /** + * Stops those words whose weight is below minWeight. + * Words are stopped by setting their weight to 0. There are not returned + * later when transforming image features into vectors. + * Note that when using IDF or TF_IDF, the weight is the idf part, which + * is equivalent to -log(f), where f is the frequency of the word + * (f = Ni/N, Ni: number of training images where the word is present, + * N: number of training images). + * Note that the old weight is forgotten, and subsequent calls to this + * function with a lower minWeight have no effect. + * @return number of words stopped now + */ + virtual int stopWords(double minWeight); + +protected: + + /// Pointer to descriptor + typedef const TDescriptor *pDescriptor; + + /// Tree node + struct Node + { + /// Node id + NodeId id; + /// Weight if the node is a word + WordValue weight; + /// Children + vector children; + /// Parent node (undefined in case of root) + NodeId parent; + /// Node descriptor + TDescriptor descriptor; + + /// Word id if the node is a word + WordId word_id; + + /** + * Empty constructor + */ + Node(): id(0), weight(0), parent(0), word_id(0){} + + /** + * Constructor + * @param _id node id + */ + Node(NodeId _id): id(_id), weight(0), parent(0), word_id(0){} + + /** + * Returns whether the node is a leaf node + * @return true iff the node is a leaf + */ + inline bool isLeaf() const { return children.empty(); } + }; + +protected: + + /** + * Creates an instance of the scoring object accoring to m_scoring + */ + void createScoringObject(); + + /** + * Returns a set of pointers to descriptores + * @param training_features all the features + * @param features (out) pointers to the training features + */ + void getFeatures( + const vector > &training_features, + vector &features) const; + + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + * @param weight (out) word weight + * @param nid (out) if given, id of the node "levelsup" levels up + * @param levelsup + */ + virtual void transform(const TDescriptor &feature, + WordId &id, WordValue &weight, NodeId* nid = NULL, int levelsup = 0) const; + + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + */ + virtual void transform(const TDescriptor &feature, WordId &id) const; + + /** + * Creates a level in the tree, under the parent, by running kmeans with + * a descriptor set, and recursively creates the subsequent levels too + * @param parent_id id of parent node + * @param descriptors descriptors to run the kmeans on + * @param current_level current level in the tree + */ + void HKmeansStep(NodeId parent_id, const vector &descriptors, + int current_level); + + /** + * Creates k clusters from the given descriptors with some seeding algorithm. + * @note In this class, kmeans++ is used, but this function should be + * overriden by inherited classes. + */ + virtual void initiateClusters(const vector &descriptors, + vector &clusters) const; + + /** + * Creates k clusters from the given descriptor sets by running the + * initial step of kmeans++ + * @param descriptors + * @param clusters resulting clusters + */ + void initiateClustersKMpp(const vector &descriptors, + vector &clusters) const; + + /** + * Create the words of the vocabulary once the tree has been built + */ + void createWords(); + + /** + * Sets the weights of the nodes of tree according to the given features. + * Before calling this function, the nodes and the words must be already + * created (by calling HKmeansStep and createWords) + * @param features + */ + void setNodeWeights(const vector > &features); + +protected: + + /// Branching factor + int m_k; + + /// Depth levels + int m_L; + + /// Weighting method + WeightingType m_weighting; + + /// Scoring method + ScoringType m_scoring; + + /// Object for computing scores + GeneralScoring* m_scoring_object; + + /// Tree nodes + std::vector m_nodes; + + /// Words of the vocabulary (tree leaves) + /// this condition holds: m_words[wid]->word_id == wid + std::vector m_words; + +}; + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary + (int k, int L, WeightingType weighting, ScoringType scoring) + : m_k(k), m_L(L), m_weighting(weighting), m_scoring(scoring), + m_scoring_object(NULL) +{ + createScoringObject(); +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary + (const std::string &filename): m_scoring_object(NULL) +{ + load(filename); +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary + (const char *filename): m_scoring_object(NULL) +{ + load(filename); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::createScoringObject() +{ + delete m_scoring_object; + m_scoring_object = NULL; + + switch(m_scoring) + { + case L1_NORM: + m_scoring_object = new L1Scoring; + break; + + case L2_NORM: + m_scoring_object = new L2Scoring; + break; + + case CHI_SQUARE: + m_scoring_object = new ChiSquareScoring; + break; + + case KL: + m_scoring_object = new KLScoring; + break; + + case BHATTACHARYYA: + m_scoring_object = new BhattacharyyaScoring; + break; + + case DOT_PRODUCT: + m_scoring_object = new DotProductScoring; + break; + + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::setScoringType(ScoringType type) +{ + m_scoring = type; + createScoringObject(); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::setWeightingType(WeightingType type) +{ + this->m_weighting = type; +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::TemplatedVocabulary( + const TemplatedVocabulary &voc) + : m_scoring_object(NULL) +{ + *this = voc; +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary::~TemplatedVocabulary() +{ + delete m_scoring_object; +} + +// -------------------------------------------------------------------------- + +template +TemplatedVocabulary& +TemplatedVocabulary::operator= + (const TemplatedVocabulary &voc) +{ + this->m_k = voc.m_k; + this->m_L = voc.m_L; + this->m_scoring = voc.m_scoring; + this->m_weighting = voc.m_weighting; + + this->createScoringObject(); + + this->m_nodes.clear(); + this->m_words.clear(); + + this->m_nodes = voc.m_nodes; + this->createWords(); + + return *this; +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::create( + const std::vector > &training_features) +{ + m_nodes.clear(); + m_words.clear(); + + // expected_nodes = Sum_{i=0..L} ( k^i ) + int expected_nodes = + (int)((pow((double)m_k, (double)m_L + 1) - 1)/(m_k - 1)); + + m_nodes.reserve(expected_nodes); // avoid allocations when creating the tree + + + vector features; + getFeatures(training_features, features); + + + // create root + m_nodes.push_back(Node(0)); // root + + // create the tree + HKmeansStep(0, features, 1); + + // create the words + createWords(); + + // and set the weight of each node of the tree + setNodeWeights(training_features); + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::create( + const std::vector > &training_features, + int k, int L) +{ + m_k = k; + m_L = L; + + create(training_features); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::create( + const std::vector > &training_features, + int k, int L, WeightingType weighting, ScoringType scoring) +{ + m_k = k; + m_L = L; + m_weighting = weighting; + m_scoring = scoring; + createScoringObject(); + + create(training_features); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::getFeatures( + const vector > &training_features, + vector &features) const +{ + features.resize(0); + + typename vector >::const_iterator vvit; + typename vector::const_iterator vit; + for(vvit = training_features.begin(); vvit != training_features.end(); ++vvit) + { + features.reserve(features.size() + vvit->size()); + for(vit = vvit->begin(); vit != vvit->end(); ++vit) + { + features.push_back(&(*vit)); + } + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::HKmeansStep(NodeId parent_id, + const vector &descriptors, int current_level) +{ + if(descriptors.empty()) return; + + // features associated to each cluster + vector clusters; + vector > groups; // groups[i] = [j1, j2, ...] + // j1, j2, ... indices of descriptors associated to cluster i + + clusters.reserve(m_k); + groups.reserve(m_k); + + //const int msizes[] = { m_k, descriptors.size() }; + //cv::SparseMat assoc(2, msizes, CV_8U); + //cv::SparseMat last_assoc(2, msizes, CV_8U); + //// assoc.row(cluster_idx).col(descriptor_idx) = 1 iif associated + + if((int)descriptors.size() <= m_k) + { + // trivial case: one cluster per feature + groups.resize(descriptors.size()); + + for(unsigned int i = 0; i < descriptors.size(); i++) + { + groups[i].push_back(i); + clusters.push_back(*descriptors[i]); + } + } + else + { + // select clusters and groups with kmeans + + bool first_time = true; + bool goon = true; + + // to check if clusters move after iterations + vector last_association, current_association; + + while(goon) + { + // 1. Calculate clusters + + if(first_time) + { + // random sample + initiateClusters(descriptors, clusters); + } + else + { + // calculate cluster centres + + for(unsigned int c = 0; c < clusters.size(); ++c) + { + vector cluster_descriptors; + cluster_descriptors.reserve(groups[c].size()); + + /* + for(unsigned int d = 0; d < descriptors.size(); ++d) + { + if( assoc.find(c, d) ) + { + cluster_descriptors.push_back(descriptors[d]); + } + } + */ + + vector::const_iterator vit; + for(vit = groups[c].begin(); vit != groups[c].end(); ++vit) + { + cluster_descriptors.push_back(descriptors[*vit]); + } + + + F::meanValue(cluster_descriptors, clusters[c]); + } + + } // if(!first_time) + + // 2. Associate features with clusters + + // calculate distances to cluster centers + groups.clear(); + groups.resize(clusters.size(), vector()); + current_association.resize(descriptors.size()); + + //assoc.clear(); + + typename vector::const_iterator fit; + //unsigned int d = 0; + for(fit = descriptors.begin(); fit != descriptors.end(); ++fit)//, ++d) + { + double best_dist = F::distance(*(*fit), clusters[0]); + unsigned int icluster = 0; + + for(unsigned int c = 1; c < clusters.size(); ++c) + { + double dist = F::distance(*(*fit), clusters[c]); + if(dist < best_dist) + { + best_dist = dist; + icluster = c; + } + } + + //assoc.ref(icluster, d) = 1; + + groups[icluster].push_back(fit - descriptors.begin()); + current_association[ fit - descriptors.begin() ] = icluster; + } + + // kmeans++ ensures all the clusters has any feature associated with them + + // 3. check convergence + if(first_time) + { + first_time = false; + } + else + { + //goon = !eqUChar(last_assoc, assoc); + + goon = false; + for(unsigned int i = 0; i < current_association.size(); i++) + { + if(current_association[i] != last_association[i]){ + goon = true; + break; + } + } + } + + if(goon) + { + // copy last feature-cluster association + last_association = current_association; + //last_assoc = assoc.clone(); + } + + } // while(goon) + + } // if must run kmeans + + // create nodes + for(unsigned int i = 0; i < clusters.size(); ++i) + { + NodeId id = m_nodes.size(); + m_nodes.push_back(Node(id)); + m_nodes.back().descriptor = clusters[i]; + m_nodes.back().parent = parent_id; + m_nodes[parent_id].children.push_back(id); + } + + // go on with the next level + if(current_level < m_L) + { + // iterate again with the resulting clusters + const vector &children_ids = m_nodes[parent_id].children; + for(unsigned int i = 0; i < clusters.size(); ++i) + { + NodeId id = children_ids[i]; + + vector child_features; + child_features.reserve(groups[i].size()); + + vector::const_iterator vit; + for(vit = groups[i].begin(); vit != groups[i].end(); ++vit) + { + child_features.push_back(descriptors[*vit]); + } + + if(child_features.size() > 1) + { + HKmeansStep(id, child_features, current_level + 1); + } + } + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::initiateClusters + (const vector &descriptors, vector &clusters) const +{ + initiateClustersKMpp(descriptors, clusters); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::initiateClustersKMpp( + const vector &pfeatures, vector &clusters) const +{ + // Implements kmeans++ seeding algorithm + // Algorithm: + // 1. Choose one center uniformly at random from among the data points. + // 2. For each data point x, compute D(x), the distance between x and the nearest + // center that has already been chosen. + // 3. Add one new data point as a center. Each point x is chosen with probability + // proportional to D(x)^2. + // 4. Repeat Steps 2 and 3 until k centers have been chosen. + // 5. Now that the initial centers have been chosen, proceed using standard k-means + // clustering. + + DUtils::Random::SeedRandOnce(); + + clusters.resize(0); + clusters.reserve(m_k); + vector min_dists(pfeatures.size(), std::numeric_limits::max()); + + // 1. + + int ifeature = DUtils::Random::RandomInt(0, pfeatures.size()-1); + + // create first cluster + clusters.push_back(*pfeatures[ifeature]); + + // compute the initial distances + typename vector::const_iterator fit; + vector::iterator dit; + dit = min_dists.begin(); + for(fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) + { + *dit = F::distance(*(*fit), clusters.back()); + } + + while((int)clusters.size() < m_k) + { + // 2. + dit = min_dists.begin(); + for(fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) + { + if(*dit > 0) + { + double dist = F::distance(*(*fit), clusters.back()); + if(dist < *dit) *dit = dist; + } + } + + // 3. + double dist_sum = std::accumulate(min_dists.begin(), min_dists.end(), 0.0); + + if(dist_sum > 0) + { + double cut_d; + do + { + cut_d = DUtils::Random::RandomValue(0, dist_sum); + } while(cut_d == 0.0); + + double d_up_now = 0; + for(dit = min_dists.begin(); dit != min_dists.end(); ++dit) + { + d_up_now += *dit; + if(d_up_now >= cut_d) break; + } + + if(dit == min_dists.end()) + ifeature = pfeatures.size()-1; + else + ifeature = dit - min_dists.begin(); + + clusters.push_back(*pfeatures[ifeature]); + + } // if dist_sum > 0 + else + break; + + } // while(used_clusters < m_k) + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::createWords() +{ + m_words.resize(0); + + if(!m_nodes.empty()) + { + m_words.reserve( (int)pow((double)m_k, (double)m_L) ); + + typename vector::iterator nit; + + nit = m_nodes.begin(); // ignore root + for(++nit; nit != m_nodes.end(); ++nit) + { + if(nit->isLeaf()) + { + nit->word_id = m_words.size(); + m_words.push_back( &(*nit) ); + } + } + } +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::setNodeWeights + (const vector > &training_features) +{ + const unsigned int NWords = m_words.size(); + const unsigned int NDocs = training_features.size(); + + if(m_weighting == TF || m_weighting == BINARY) + { + // idf part must be 1 always + for(unsigned int i = 0; i < NWords; i++) + m_words[i]->weight = 1; + } + else if(m_weighting == IDF || m_weighting == TF_IDF) + { + // IDF and TF-IDF: we calculte the idf path now + + // Note: this actually calculates the idf part of the tf-idf score. + // The complete tf-idf score is calculated in ::transform + + vector Ni(NWords, 0); + vector counted(NWords, false); + + typename vector >::const_iterator mit; + typename vector::const_iterator fit; + + for(mit = training_features.begin(); mit != training_features.end(); ++mit) + { + fill(counted.begin(), counted.end(), false); + + for(fit = mit->begin(); fit < mit->end(); ++fit) + { + WordId word_id; + transform(*fit, word_id); + + if(!counted[word_id]) + { + Ni[word_id]++; + counted[word_id] = true; + } + } + } + + // set ln(N/Ni) + for(unsigned int i = 0; i < NWords; i++) + { + if(Ni[i] > 0) + { + m_words[i]->weight = log((double)NDocs / (double)Ni[i]); + }// else // This cannot occur if using kmeans++ + } + + } + +} + +// -------------------------------------------------------------------------- + +template +inline unsigned int TemplatedVocabulary::size() const +{ + return m_words.size(); +} + +// -------------------------------------------------------------------------- + +template +inline bool TemplatedVocabulary::empty() const +{ + return m_words.empty(); +} + +// -------------------------------------------------------------------------- + +template +float TemplatedVocabulary::getEffectiveLevels() const +{ + long sum = 0; + typename std::vector::const_iterator wit; + for(wit = m_words.begin(); wit != m_words.end(); ++wit) + { + const Node *p = *wit; + + for(; p->id != 0; sum++) p = &m_nodes[p->parent]; + } + + return (float)((double)sum / (double)m_words.size()); +} + +// -------------------------------------------------------------------------- + +template +TDescriptor TemplatedVocabulary::getWord(WordId wid) const +{ + return m_words[wid]->descriptor; +} + +// -------------------------------------------------------------------------- + +template +WordValue TemplatedVocabulary::getWordWeight(WordId wid) const +{ + return m_words[wid]->weight; +} + +// -------------------------------------------------------------------------- + +template +WordId TemplatedVocabulary::transform + (const TDescriptor& feature) const +{ + if(empty()) + { + return 0; + } + + WordId wid; + transform(feature, wid); + return wid; +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform( + const std::vector& features, BowVector &v) const +{ + v.clear(); + + if(empty()) + { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + typename vector::const_iterator fit; + + if(m_weighting == TF || m_weighting == TF_IDF) + { + for(fit = features.begin(); fit < features.end(); ++fit) + { + WordId id; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w); + + // not stopped + if(w > 0) v.addWeight(id, w); + } + + if(!v.empty() && !must) + { + // unnecessary when normalizing + const double nd = v.size(); + for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } + else // IDF || BINARY + { + for(fit = features.begin(); fit < features.end(); ++fit) + { + WordId id; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w); + + // not stopped + if(w > 0) v.addIfNotExist(id, w); + + } // if add_features + } // if m_weighting == ... + + if(must) v.normalize(norm); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform( + const std::vector& features, + BowVector &v, FeatureVector &fv, int levelsup) const +{ + v.clear(); + fv.clear(); + + if(empty()) // safe for subclasses + { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + typename vector::const_iterator fit; + + if(m_weighting == TF || m_weighting == TF_IDF) + { + unsigned int i_feature = 0; + for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature) + { + WordId id; + NodeId nid; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w, &nid, levelsup); + + if(w > 0) // not stopped + { + v.addWeight(id, w); + fv.addFeature(nid, i_feature); + } + } + + if(!v.empty() && !must) + { + // unnecessary when normalizing + const double nd = v.size(); + for(BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } + else // IDF || BINARY + { + unsigned int i_feature = 0; + for(fit = features.begin(); fit < features.end(); ++fit, ++i_feature) + { + WordId id; + NodeId nid; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w, &nid, levelsup); + + if(w > 0) // not stopped + { + v.addIfNotExist(id, w); + fv.addFeature(nid, i_feature); + } + } + } // if m_weighting == ... + + if(must) v.normalize(norm); +} + +// -------------------------------------------------------------------------- + +template +inline double TemplatedVocabulary::score + (const BowVector &v1, const BowVector &v2) const +{ + return m_scoring_object->score(v1, v2); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform + (const TDescriptor &feature, WordId &id) const +{ + WordValue weight; + transform(feature, id, weight); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::transform(const TDescriptor &feature, + WordId &word_id, WordValue &weight, NodeId *nid, int levelsup) const +{ + // propagate the feature down the tree + vector nodes; + typename vector::const_iterator nit; + + // level at which the node must be stored in nid, if given + const int nid_level = m_L - levelsup; + if(nid_level <= 0 && nid != NULL) *nid = 0; // root + + NodeId final_id = 0; // root + int current_level = 0; + + do + { + ++current_level; + nodes = m_nodes[final_id].children; + final_id = nodes[0]; + + double best_d = F::distance(feature, m_nodes[final_id].descriptor); + + for(nit = nodes.begin() + 1; nit != nodes.end(); ++nit) + { + NodeId id = *nit; + double d = F::distance(feature, m_nodes[id].descriptor); + if(d < best_d) + { + best_d = d; + final_id = id; + } + } + + if(nid != NULL && current_level == nid_level) + *nid = final_id; + + } while( !m_nodes[final_id].isLeaf() ); + + // turn node id into word id + word_id = m_nodes[final_id].word_id; + weight = m_nodes[final_id].weight; +} + +// -------------------------------------------------------------------------- + +template +NodeId TemplatedVocabulary::getParentNode + (WordId wid, int levelsup) const +{ + NodeId ret = m_words[wid]->id; // node id + while(levelsup > 0 && ret != 0) // ret == 0 --> root + { + --levelsup; + ret = m_nodes[ret].parent; + } + return ret; +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::getWordsFromNode + (NodeId nid, std::vector &words) const +{ + words.clear(); + + if(m_nodes[nid].isLeaf()) + { + words.push_back(m_nodes[nid].word_id); + } + else + { + words.reserve(m_k); // ^1, ^2, ... + + vector parents; + parents.push_back(nid); + + while(!parents.empty()) + { + NodeId parentid = parents.back(); + parents.pop_back(); + + const vector &child_ids = m_nodes[parentid].children; + vector::const_iterator cit; + + for(cit = child_ids.begin(); cit != child_ids.end(); ++cit) + { + const Node &child_node = m_nodes[*cit]; + + if(child_node.isLeaf()) + words.push_back(child_node.word_id); + else + parents.push_back(*cit); + + } // for each child + } // while !parents.empty + } +} + +// -------------------------------------------------------------------------- + +template +int TemplatedVocabulary::stopWords(double minWeight) +{ + int c = 0; + typename vector::iterator wit; + for(wit = m_words.begin(); wit != m_words.end(); ++wit) + { + if((*wit)->weight < minWeight) + { + ++c; + (*wit)->weight = 0; + } + } + return c; +} + +// -------------------------------------------------------------------------- + +template +bool TemplatedVocabulary::loadFromTextFile(const std::string &filename) +{ + ifstream f; + f.open(filename.c_str()); + + if(f.eof()) + return false; + + m_words.clear(); + m_nodes.clear(); + + string s; + getline(f,s); + stringstream ss; + ss << s; + ss >> m_k; + ss >> m_L; + int n1, n2; + ss >> n1; + ss >> n2; + + if(m_k<0 || m_k>20 || m_L<1 || m_L>10 || n1<0 || n1>5 || n2<0 || n2>3) + { + std::cerr << "Vocabulary loading failure: This is not a correct text file!" << endl; + return false; + } + + m_scoring = (ScoringType)n1; + m_weighting = (WeightingType)n2; + createScoringObject(); + + // nodes + int expected_nodes = + (int)((pow((double)m_k, (double)m_L + 1) - 1)/(m_k - 1)); + m_nodes.reserve(expected_nodes); + + m_words.reserve(pow((double)m_k, (double)m_L + 1)); + + m_nodes.resize(1); + m_nodes[0].id = 0; + while(!f.eof()) + { + string snode; + getline(f,snode); + stringstream ssnode; + ssnode << snode; + + int nid = m_nodes.size(); + m_nodes.resize(m_nodes.size()+1); + m_nodes[nid].id = nid; + + int pid ; + ssnode >> pid; + m_nodes[nid].parent = pid; + m_nodes[pid].children.push_back(nid); + + int nIsLeaf; + ssnode >> nIsLeaf; + + stringstream ssd; + for(int iD=0;iD> sElement; + ssd << sElement << " "; + } + F::fromString(m_nodes[nid].descriptor, ssd.str()); + + ssnode >> m_nodes[nid].weight; + + if(nIsLeaf>0) + { + int wid = m_words.size(); + m_words.resize(wid+1); + + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } + else + { + m_nodes[nid].children.reserve(m_k); + } + } + + return true; + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::saveToTextFile(const std::string &filename) const +{ + fstream f; + f.open(filename.c_str(),ios_base::out); + f << m_k << " " << m_L << " " << " " << m_scoring << " " << m_weighting << endl; + + for(size_t i=1; i +void TemplatedVocabulary::save(const std::string &filename) const +{ + cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); + if(!fs.isOpened()) throw string("Could not open file ") + filename; + + save(fs); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::load(const std::string &filename) +{ + cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); + if(!fs.isOpened()) throw string("Could not open file ") + filename; + + this->load(fs); +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::save(cv::FileStorage &f, + const std::string &name) const +{ + // Format YAML: + // vocabulary + // { + // k: + // L: + // scoringType: + // weightingType: + // nodes + // [ + // { + // nodeId: + // parentId: + // weight: + // descriptor: + // } + // ] + // words + // [ + // { + // wordId: + // nodeId: + // } + // ] + // } + // + // The root node (index 0) is not included in the node vector + // + + f << name << "{"; + + f << "k" << m_k; + f << "L" << m_L; + f << "scoringType" << m_scoring; + f << "weightingType" << m_weighting; + + // tree + f << "nodes" << "["; + vector parents, children; + vector::const_iterator pit; + + parents.push_back(0); // root + + while(!parents.empty()) + { + NodeId pid = parents.back(); + parents.pop_back(); + + const Node& parent = m_nodes[pid]; + children = parent.children; + + for(pit = children.begin(); pit != children.end(); pit++) + { + const Node& child = m_nodes[*pit]; + + // save node data + f << "{:"; + f << "nodeId" << (int)child.id; + f << "parentId" << (int)pid; + f << "weight" << (double)child.weight; + f << "descriptor" << F::toString(child.descriptor); + f << "}"; + + // add to parent list + if(!child.isLeaf()) + { + parents.push_back(*pit); + } + } + } + + f << "]"; // nodes + + // words + f << "words" << "["; + + typename vector::const_iterator wit; + for(wit = m_words.begin(); wit != m_words.end(); wit++) + { + WordId id = wit - m_words.begin(); + f << "{:"; + f << "wordId" << (int)id; + f << "nodeId" << (int)(*wit)->id; + f << "}"; + } + + f << "]"; // words + + f << "}"; + +} + +// -------------------------------------------------------------------------- + +template +void TemplatedVocabulary::load(const cv::FileStorage &fs, + const std::string &name) +{ + m_words.clear(); + m_nodes.clear(); + + cv::FileNode fvoc = fs[name]; + + m_k = (int)fvoc["k"]; + m_L = (int)fvoc["L"]; + m_scoring = (ScoringType)((int)fvoc["scoringType"]); + m_weighting = (WeightingType)((int)fvoc["weightingType"]); + + createScoringObject(); + + // nodes + cv::FileNode fn = fvoc["nodes"]; + + m_nodes.resize(fn.size() + 1); // +1 to include root + m_nodes[0].id = 0; + + for(unsigned int i = 0; i < fn.size(); ++i) + { + NodeId nid = (int)fn[i]["nodeId"]; + NodeId pid = (int)fn[i]["parentId"]; + WordValue weight = (WordValue)fn[i]["weight"]; + string d = (string)fn[i]["descriptor"]; + + m_nodes[nid].id = nid; + m_nodes[nid].parent = pid; + m_nodes[nid].weight = weight; + m_nodes[pid].children.push_back(nid); + + F::fromString(m_nodes[nid].descriptor, d); + } + + // words + fn = fvoc["words"]; + + m_words.resize(fn.size()); + + for(unsigned int i = 0; i < fn.size(); ++i) + { + NodeId wid = (int)fn[i]["wordId"]; + NodeId nid = (int)fn[i]["nodeId"]; + + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } +} + +// -------------------------------------------------------------------------- + +/** + * Writes printable information of the vocabulary + * @param os stream to write to + * @param voc + */ +template +std::ostream& operator<<(std::ostream &os, + const TemplatedVocabulary &voc) +{ + os << "Vocabulary: k = " << voc.getBranchingFactor() + << ", L = " << voc.getDepthLevels() + << ", Weighting = "; + + switch(voc.getWeightingType()) + { + case TF_IDF: os << "tf-idf"; break; + case TF: os << "tf"; break; + case IDF: os << "idf"; break; + case BINARY: os << "binary"; break; + } + + os << ", Scoring = "; + switch(voc.getScoringType()) + { + case L1_NORM: os << "L1-norm"; break; + case L2_NORM: os << "L2-norm"; break; + case CHI_SQUARE: os << "Chi square distance"; break; + case KL: os << "KL-divergence"; break; + case BHATTACHARYYA: os << "Bhattacharyya coefficient"; break; + case DOT_PRODUCT: os << "Dot product"; break; + } + + os << ", Number of words = " << voc.size(); + + return os; +} + +} // namespace DBoW2 + +#endif diff --git a/Thirdparty/DBoW2/DUtils/Random.cpp b/Thirdparty/DBoW2/DUtils/Random.cpp new file mode 100644 index 0000000000..79df2a6978 --- /dev/null +++ b/Thirdparty/DBoW2/DUtils/Random.cpp @@ -0,0 +1,129 @@ +/* + * File: Random.cpp + * Project: DUtils library + * Author: Dorian Galvez-Lopez + * Date: April 2010 + * Description: manages pseudo-random numbers + * License: see the LICENSE.txt file + * + */ + +#include "Random.h" +#include "Timestamp.h" +#include +using namespace std; + +bool DUtils::Random::m_already_seeded = false; + +void DUtils::Random::SeedRand(){ + Timestamp time; + time.setToCurrentTime(); + srand((unsigned)time.getFloatTime()); +} + +void DUtils::Random::SeedRandOnce() +{ + if(!m_already_seeded) + { + DUtils::Random::SeedRand(); + m_already_seeded = true; + } +} + +void DUtils::Random::SeedRand(int seed) +{ + srand(seed); +} + +void DUtils::Random::SeedRandOnce(int seed) +{ + if(!m_already_seeded) + { + DUtils::Random::SeedRand(seed); + m_already_seeded = true; + } +} + +int DUtils::Random::RandomInt(int min, int max){ + int d = max - min + 1; + return int(((double)rand()/((double)RAND_MAX + 1.0)) * d) + min; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer(int min, int max) +{ + if(min <= max) + { + m_min = min; + m_max = max; + } + else + { + m_min = max; + m_max = min; + } + + createValues(); +} + +// --------------------------------------------------------------------------- + +DUtils::Random::UnrepeatedRandomizer::UnrepeatedRandomizer + (const DUtils::Random::UnrepeatedRandomizer& rnd) +{ + *this = rnd; +} + +// --------------------------------------------------------------------------- + +int DUtils::Random::UnrepeatedRandomizer::get() +{ + if(empty()) createValues(); + + DUtils::Random::SeedRandOnce(); + + int k = DUtils::Random::RandomInt(0, m_values.size()-1); + int ret = m_values[k]; + m_values[k] = m_values.back(); + m_values.pop_back(); + + return ret; +} + +// --------------------------------------------------------------------------- + +void DUtils::Random::UnrepeatedRandomizer::createValues() +{ + int n = m_max - m_min + 1; + + m_values.resize(n); + for(int i = 0; i < n; ++i) m_values[i] = m_min + i; +} + +// --------------------------------------------------------------------------- + +void DUtils::Random::UnrepeatedRandomizer::reset() +{ + if((int)m_values.size() != m_max - m_min + 1) createValues(); +} + +// --------------------------------------------------------------------------- + +DUtils::Random::UnrepeatedRandomizer& +DUtils::Random::UnrepeatedRandomizer::operator= + (const DUtils::Random::UnrepeatedRandomizer& rnd) +{ + if(this != &rnd) + { + this->m_min = rnd.m_min; + this->m_max = rnd.m_max; + this->m_values = rnd.m_values; + } + return *this; +} + +// --------------------------------------------------------------------------- + + diff --git a/Thirdparty/DBoW2/DUtils/Random.h b/Thirdparty/DBoW2/DUtils/Random.h new file mode 100644 index 0000000000..5115dc47c2 --- /dev/null +++ b/Thirdparty/DBoW2/DUtils/Random.h @@ -0,0 +1,184 @@ +/* + * File: Random.h + * Project: DUtils library + * Author: Dorian Galvez-Lopez + * Date: April 2010, November 2011 + * Description: manages pseudo-random numbers + * License: see the LICENSE.txt file + * + */ + +#pragma once +#ifndef __D_RANDOM__ +#define __D_RANDOM__ + +#include +#include + +namespace DUtils { + +/// Functions to generate pseudo-random numbers +class Random +{ +public: + class UnrepeatedRandomizer; + +public: + /** + * Sets the random number seed to the current time + */ + static void SeedRand(); + + /** + * Sets the random number seed to the current time only the first + * time this function is called + */ + static void SeedRandOnce(); + + /** + * Sets the given random number seed + * @param seed + */ + static void SeedRand(int seed); + + /** + * Sets the given random number seed only the first time this function + * is called + * @param seed + */ + static void SeedRandOnce(int seed); + + /** + * Returns a random number in the range [0..1] + * @return random T number in [0..1] + */ + template + static T RandomValue(){ + return (T)rand()/(T)RAND_MAX; + } + + /** + * Returns a random number in the range [min..max] + * @param min + * @param max + * @return random T number in [min..max] + */ + template + static T RandomValue(T min, T max){ + return Random::RandomValue() * (max - min) + min; + } + + /** + * Returns a random int in the range [min..max] + * @param min + * @param max + * @return random int in [min..max] + */ + static int RandomInt(int min, int max); + + /** + * Returns a random number from a gaussian distribution + * @param mean + * @param sigma standard deviation + */ + template + static T RandomGaussianValue(T mean, T sigma) + { + // Box-Muller transformation + T x1, x2, w, y1; + + do { + x1 = (T)2. * RandomValue() - (T)1.; + x2 = (T)2. * RandomValue() - (T)1.; + w = x1 * x1 + x2 * x2; + } while ( w >= (T)1. || w == (T)0. ); + + w = sqrt( ((T)-2.0 * log( w ) ) / w ); + y1 = x1 * w; + + return( mean + y1 * sigma ); + } + +private: + + /// If SeedRandOnce() or SeedRandOnce(int) have already been called + static bool m_already_seeded; + +}; + +// --------------------------------------------------------------------------- + +/// Provides pseudo-random numbers with no repetitions +class Random::UnrepeatedRandomizer +{ +public: + + /** + * Creates a randomizer that returns numbers in the range [min, max] + * @param min + * @param max + */ + UnrepeatedRandomizer(int min, int max); + ~UnrepeatedRandomizer(){} + + /** + * Copies a randomizer + * @param rnd + */ + UnrepeatedRandomizer(const UnrepeatedRandomizer& rnd); + + /** + * Copies a randomizer + * @param rnd + */ + UnrepeatedRandomizer& operator=(const UnrepeatedRandomizer& rnd); + + /** + * Returns a random number not given before. If all the possible values + * were already given, the process starts again + * @return unrepeated random number + */ + int get(); + + /** + * Returns whether all the possible values between min and max were + * already given. If get() is called when empty() is true, the behaviour + * is the same than after creating the randomizer + * @return true iff all the values were returned + */ + inline bool empty() const { return m_values.empty(); } + + /** + * Returns the number of values still to be returned + * @return amount of values to return + */ + inline unsigned int left() const { return m_values.size(); } + + /** + * Resets the randomizer as it were just created + */ + void reset(); + +protected: + + /** + * Creates the vector with available values + */ + void createValues(); + +protected: + + /// Min of range of values + int m_min; + /// Max of range of values + int m_max; + + /// Available values + std::vector m_values; + +}; + +} + +#endif + diff --git a/Thirdparty/DBoW2/DUtils/Timestamp.cpp b/Thirdparty/DBoW2/DUtils/Timestamp.cpp new file mode 100644 index 0000000000..4551839f17 --- /dev/null +++ b/Thirdparty/DBoW2/DUtils/Timestamp.cpp @@ -0,0 +1,246 @@ +/* + * File: Timestamp.cpp + * Author: Dorian Galvez-Lopez + * Date: March 2009 + * Description: timestamping functions + * + * Note: in windows, this class has a 1ms resolution + * + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include +#include +#include +#include + +#ifdef _WIN32 +#ifndef WIN32 +#define WIN32 +#endif +#endif + +#ifdef WIN32 +#include +#define sprintf sprintf_s +#else +#include +#endif + +#include "Timestamp.h" + +using namespace std; + +using namespace DUtils; + +Timestamp::Timestamp(Timestamp::tOptions option) +{ + if(option & CURRENT_TIME) + setToCurrentTime(); + else if(option & ZERO) + setTime(0.); +} + +Timestamp::~Timestamp(void) +{ +} + +bool Timestamp::empty() const +{ + return m_secs == 0 && m_usecs == 0; +} + +void Timestamp::setToCurrentTime(){ + +#ifdef WIN32 + struct __timeb32 timebuffer; + _ftime32_s( &timebuffer ); // C4996 + // Note: _ftime is deprecated; consider using _ftime_s instead + m_secs = timebuffer.time; + m_usecs = timebuffer.millitm * 1000; +#else + struct timeval now; + gettimeofday(&now, NULL); + m_secs = now.tv_sec; + m_usecs = now.tv_usec; +#endif + +} + +void Timestamp::setTime(const string &stime){ + string::size_type p = stime.find('.'); + if(p == string::npos){ + m_secs = atol(stime.c_str()); + m_usecs = 0; + }else{ + m_secs = atol(stime.substr(0, p).c_str()); + + string s_usecs = stime.substr(p+1, 6); + m_usecs = atol(stime.substr(p+1).c_str()); + m_usecs *= (unsigned long)pow(10.0, double(6 - s_usecs.length())); + } +} + +void Timestamp::setTime(double s) +{ + m_secs = (unsigned long)s; + m_usecs = (s - (double)m_secs) * 1e6; +} + +double Timestamp::getFloatTime() const { + return double(m_secs) + double(m_usecs)/1000000.0; +} + +string Timestamp::getStringTime() const { + char buf[32]; + sprintf(buf, "%.6lf", this->getFloatTime()); + return string(buf); +} + +double Timestamp::operator- (const Timestamp &t) const { + return this->getFloatTime() - t.getFloatTime(); +} + +Timestamp& Timestamp::operator+= (double s) +{ + *this = *this + s; + return *this; +} + +Timestamp& Timestamp::operator-= (double s) +{ + *this = *this - s; + return *this; +} + +Timestamp Timestamp::operator+ (double s) const +{ + unsigned long secs = (long)floor(s); + unsigned long usecs = (long)((s - (double)secs) * 1e6); + + return this->plus(secs, usecs); +} + +Timestamp Timestamp::plus(unsigned long secs, unsigned long usecs) const +{ + Timestamp t; + + const unsigned long max = 1000000ul; + + if(m_usecs + usecs >= max) + t.setTime(m_secs + secs + 1, m_usecs + usecs - max); + else + t.setTime(m_secs + secs, m_usecs + usecs); + + return t; +} + +Timestamp Timestamp::operator- (double s) const +{ + unsigned long secs = (long)floor(s); + unsigned long usecs = (long)((s - (double)secs) * 1e6); + + return this->minus(secs, usecs); +} + +Timestamp Timestamp::minus(unsigned long secs, unsigned long usecs) const +{ + Timestamp t; + + const unsigned long max = 1000000ul; + + if(m_usecs < usecs) + t.setTime(m_secs - secs - 1, max - (usecs - m_usecs)); + else + t.setTime(m_secs - secs, m_usecs - usecs); + + return t; +} + +bool Timestamp::operator> (const Timestamp &t) const +{ + if(m_secs > t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs > t.m_usecs; + else return false; +} + +bool Timestamp::operator>= (const Timestamp &t) const +{ + if(m_secs > t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs >= t.m_usecs; + else return false; +} + +bool Timestamp::operator< (const Timestamp &t) const +{ + if(m_secs < t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs < t.m_usecs; + else return false; +} + +bool Timestamp::operator<= (const Timestamp &t) const +{ + if(m_secs < t.m_secs) return true; + else if(m_secs == t.m_secs) return m_usecs <= t.m_usecs; + else return false; +} + +bool Timestamp::operator== (const Timestamp &t) const +{ + return(m_secs == t.m_secs && m_usecs == t.m_usecs); +} + + +string Timestamp::Format(bool machine_friendly) const +{ + struct tm tm_time; + + time_t t = (time_t)getFloatTime(); + +#ifdef WIN32 + localtime_s(&tm_time, &t); +#else + localtime_r(&t, &tm_time); +#endif + + char buffer[128]; + + if(machine_friendly) + { + strftime(buffer, 128, "%Y%m%d_%H%M%S", &tm_time); + } + else + { + strftime(buffer, 128, "%c", &tm_time); // Thu Aug 23 14:55:02 2001 + } + + return string(buffer); +} + +string Timestamp::Format(double s) { + int days = int(s / (24. * 3600.0)); + s -= days * (24. * 3600.0); + int hours = int(s / 3600.0); + s -= hours * 3600; + int minutes = int(s / 60.0); + s -= minutes * 60; + int seconds = int(s); + int ms = int((s - seconds)*1e6); + + stringstream ss; + ss.fill('0'); + bool b; + if((b = (days > 0))) ss << days << "d "; + if((b = (b || hours > 0))) ss << setw(2) << hours << ":"; + if((b = (b || minutes > 0))) ss << setw(2) << minutes << ":"; + if(b) ss << setw(2); + ss << seconds; + if(!b) ss << "." << setw(6) << ms; + + return ss.str(); +} + + diff --git a/Thirdparty/DBoW2/DUtils/Timestamp.h b/Thirdparty/DBoW2/DUtils/Timestamp.h new file mode 100644 index 0000000000..b92f89f872 --- /dev/null +++ b/Thirdparty/DBoW2/DUtils/Timestamp.h @@ -0,0 +1,204 @@ +/* + * File: Timestamp.h + * Author: Dorian Galvez-Lopez + * Date: March 2009 + * Description: timestamping functions + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_TIMESTAMP__ +#define __D_TIMESTAMP__ + +#include +using namespace std; + +namespace DUtils { + +/// Timestamp +class Timestamp +{ +public: + + /// Options to initiate a timestamp + enum tOptions + { + NONE = 0, + CURRENT_TIME = 0x1, + ZERO = 0x2 + }; + +public: + + /** + * Creates a timestamp + * @param option option to set the initial time stamp + */ + Timestamp(Timestamp::tOptions option = NONE); + + /** + * Destructor + */ + virtual ~Timestamp(void); + + /** + * Says if the timestamp is "empty": seconds and usecs are both 0, as + * when initiated with the ZERO flag + * @return true iif secs == usecs == 0 + */ + bool empty() const; + + /** + * Sets this instance to the current time + */ + void setToCurrentTime(); + + /** + * Sets the timestamp from seconds and microseconds + * @param secs: seconds + * @param usecs: microseconds + */ + inline void setTime(unsigned long secs, unsigned long usecs){ + m_secs = secs; + m_usecs = usecs; + } + + /** + * Returns the timestamp in seconds and microseconds + * @param secs seconds + * @param usecs microseconds + */ + inline void getTime(unsigned long &secs, unsigned long &usecs) const + { + secs = m_secs; + usecs = m_usecs; + } + + /** + * Sets the timestamp from a string with the time in seconds + * @param stime: string such as "1235603336.036609" + */ + void setTime(const string &stime); + + /** + * Sets the timestamp from a number of seconds from the epoch + * @param s seconds from the epoch + */ + void setTime(double s); + + /** + * Returns this timestamp as the number of seconds in (long) float format + */ + double getFloatTime() const; + + /** + * Returns this timestamp as the number of seconds in fixed length string format + */ + string getStringTime() const; + + /** + * Returns the difference in seconds between this timestamp (greater) and t (smaller) + * If the order is swapped, a negative number is returned + * @param t: timestamp to subtract from this timestamp + * @return difference in seconds + */ + double operator- (const Timestamp &t) const; + + /** + * Returns a copy of this timestamp + s seconds + us microseconds + * @param s seconds + * @param us microseconds + */ + Timestamp plus(unsigned long s, unsigned long us) const; + + /** + * Returns a copy of this timestamp - s seconds - us microseconds + * @param s seconds + * @param us microseconds + */ + Timestamp minus(unsigned long s, unsigned long us) const; + + /** + * Adds s seconds to this timestamp and returns a reference to itself + * @param s seconds + * @return reference to this timestamp + */ + Timestamp& operator+= (double s); + + /** + * Substracts s seconds to this timestamp and returns a reference to itself + * @param s seconds + * @return reference to this timestamp + */ + Timestamp& operator-= (double s); + + /** + * Returns a copy of this timestamp + s seconds + * @param s: seconds + */ + Timestamp operator+ (double s) const; + + /** + * Returns a copy of this timestamp - s seconds + * @param s: seconds + */ + Timestamp operator- (double s) const; + + /** + * Returns whether this timestamp is at the future of t + * @param t + */ + bool operator> (const Timestamp &t) const; + + /** + * Returns whether this timestamp is at the future of (or is the same as) t + * @param t + */ + bool operator>= (const Timestamp &t) const; + + /** + * Returns whether this timestamp and t represent the same instant + * @param t + */ + bool operator== (const Timestamp &t) const; + + /** + * Returns whether this timestamp is at the past of t + * @param t + */ + bool operator< (const Timestamp &t) const; + + /** + * Returns whether this timestamp is at the past of (or is the same as) t + * @param t + */ + bool operator<= (const Timestamp &t) const; + + /** + * Returns the timestamp in a human-readable string + * @param machine_friendly if true, the returned string is formatted + * to yyyymmdd_hhmmss, without weekday or spaces + * @note This has not been tested under Windows + * @note The timestamp is truncated to seconds + */ + string Format(bool machine_friendly = false) const; + + /** + * Returns a string version of the elapsed time in seconds, with the format + * xd hh:mm:ss, hh:mm:ss, mm:ss or s.us + * @param s: elapsed seconds (given by getFloatTime) to format + */ + static string Format(double s); + + +protected: + /// Seconds + unsigned long m_secs; // seconds + /// Microseconds + unsigned long m_usecs; // microseconds +}; + +} + +#endif + diff --git a/Thirdparty/DBoW2/LICENSE.txt b/Thirdparty/DBoW2/LICENSE.txt new file mode 100644 index 0000000000..376332c159 --- /dev/null +++ b/Thirdparty/DBoW2/LICENSE.txt @@ -0,0 +1,46 @@ +DBoW2: bag-of-words library for C++ with generic descriptors + +Copyright (c) 2015 Dorian Galvez-Lopez. http://doriangalvez.com +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions +are met: +1. Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. +2. Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. +3. The original author of the work must be notified of any + redistribution of source code or in binary form. +4. Neither the name of copyright holders nor the names of its + contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +''AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS OR CONTRIBUTORS +BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. + +If you use it in an academic work, please cite: + + @ARTICLE{GalvezTRO12, + author={G\'alvez-L\'opez, Dorian and Tard\'os, J. D.}, + journal={IEEE Transactions on Robotics}, + title={Bags of Binary Words for Fast Place Recognition in Image Sequences}, + year={2012}, + month={October}, + volume={28}, + number={5}, + pages={1188--1197}, + doi={10.1109/TRO.2012.2197158}, + ISSN={1552-3098} + } + diff --git a/Thirdparty/DBoW2/README.txt b/Thirdparty/DBoW2/README.txt new file mode 100644 index 0000000000..71827f06cf --- /dev/null +++ b/Thirdparty/DBoW2/README.txt @@ -0,0 +1,7 @@ +You should have received this DBoW2 version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2). +See the original DBoW2 library at: https://github.com/dorian3d/DBoW2 +All files included in this version are BSD, see LICENSE.txt + +We also use Random.h, Random.cpp, Timestamp.pp and Timestamp.h from DLib/DUtils. +See the original DLib library at: https://github.com/dorian3d/DLib +All files included in this version are BSD, see LICENSE.txt diff --git a/Thirdparty/g2o/CMakeLists.txt b/Thirdparty/g2o/CMakeLists.txt new file mode 100644 index 0000000000..5882a53ff2 --- /dev/null +++ b/Thirdparty/g2o/CMakeLists.txt @@ -0,0 +1,178 @@ +CMAKE_MINIMUM_REQUIRED(VERSION 2.6) +SET(CMAKE_LEGACY_CYGWIN_WIN32 0) + +PROJECT(g2o) + +SET(g2o_C_FLAGS) +SET(g2o_CXX_FLAGS) + +# default built type +IF(NOT CMAKE_BUILD_TYPE) + SET(CMAKE_BUILD_TYPE Release) +ENDIF() + +MESSAGE(STATUS "BUILD TYPE:" ${CMAKE_BUILD_TYPE}) + +SET (G2O_LIB_TYPE SHARED) + +# There seems to be an issue with MSVC8 +# see http://eigen.tuxfamily.org/bz/show_bug.cgi?id=83 +if(MSVC90) + add_definitions(-DEIGEN_DONT_ALIGN_STATICALLY=1) + message(STATUS "Disabling memory alignment for MSVC8") +endif(MSVC90) + +# Set the output directory for the build executables and libraries +IF(WIN32) + SET(g2o_LIBRARY_OUTPUT_DIRECTORY ${g2o_SOURCE_DIR}/bin CACHE PATH "Target for the libraries") +ELSE(WIN32) + SET(g2o_LIBRARY_OUTPUT_DIRECTORY ${g2o_SOURCE_DIR}/lib CACHE PATH "Target for the libraries") +ENDIF(WIN32) +SET(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${g2o_LIBRARY_OUTPUT_DIRECTORY}) +SET(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${g2o_LIBRARY_OUTPUT_DIRECTORY}) +SET(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${g2o_RUNTIME_OUTPUT_DIRECTORY}) + +# Set search directory for looking for our custom CMake scripts to +# look for SuiteSparse, QGLViewer, and Eigen3. +LIST(APPEND CMAKE_MODULE_PATH ${g2o_SOURCE_DIR}/cmake_modules) + +# Detect OS and define macros appropriately +IF(UNIX) + ADD_DEFINITIONS(-DUNIX) + MESSAGE(STATUS "Compiling on Unix") +ENDIF(UNIX) + +# For building the CHOLMOD / CSPARSE solvers +FIND_PACKAGE(BLAS REQUIRED) +FIND_PACKAGE(LAPACK REQUIRED) + +# Eigen library parallelise itself, though, presumably due to performance issues +# OPENMP is experimental. We experienced some slowdown with it +FIND_PACKAGE(OpenMP) +SET(G2O_USE_OPENMP OFF CACHE BOOL "Build g2o with OpenMP support (EXPERIMENTAL)") +IF(OPENMP_FOUND AND G2O_USE_OPENMP) + SET (G2O_OPENMP 1) + SET(g2o_C_FLAGS "${g2o_C_FLAGS} ${OpenMP_C_FLAGS}") + SET(g2o_CXX_FLAGS "${g2o_CXX_FLAGS} -DEIGEN_DONT_PARALLELIZE ${OpenMP_CXX_FLAGS}") + MESSAGE(STATUS "Compiling with OpenMP support") +ENDIF(OPENMP_FOUND AND G2O_USE_OPENMP) + +# Compiler specific options for gcc +SET(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} -O3 -march=native") +SET(CMAKE_C_FLAGS_RELEASE "${CMAKE_C_FLAGS_RELEASE} -O3 -march=native") + +# activate warnings !!! +SET(g2o_C_FLAGS "${g2o_C_FLAGS} -Wall -W") +SET(g2o_CXX_FLAGS "${g2o_CXX_FLAGS} -Wall -W") + +# specifying compiler flags +SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${g2o_CXX_FLAGS}") +SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${g2o_C_FLAGS}") + +# Find Eigen3 +SET(EIGEN3_INCLUDE_DIR ${G2O_EIGEN3_INCLUDE}) +FIND_PACKAGE(Eigen3 3.1.0 REQUIRED) +IF(EIGEN3_FOUND) + SET(G2O_EIGEN3_INCLUDE ${EIGEN3_INCLUDE_DIR} CACHE PATH "Directory of Eigen3") +ELSE(EIGEN3_FOUND) + SET(G2O_EIGEN3_INCLUDE "" CACHE PATH "Directory of Eigen3") +ENDIF(EIGEN3_FOUND) + +# Generate config.h +SET(G2O_CXX_COMPILER "${CMAKE_CXX_COMPILER_ID} ${CMAKE_CXX_COMPILER}") +configure_file(config.h.in ${g2o_SOURCE_DIR}/config.h) + +# Set up the top-level include directories +INCLUDE_DIRECTORIES( +${g2o_SOURCE_DIR}/core +${g2o_SOURCE_DIR}/types +${g2o_SOURCE_DIR}/stuff +${G2O_EIGEN3_INCLUDE}) + +# Include the subdirectories +ADD_LIBRARY(g2o ${G2O_LIB_TYPE} +#types +g2o/types/types_sba.h +g2o/types/types_six_dof_expmap.h +g2o/types/types_sba.cpp +g2o/types/types_six_dof_expmap.cpp +g2o/types/types_seven_dof_expmap.cpp +g2o/types/types_seven_dof_expmap.h +g2o/types/se3quat.h +g2o/types/se3_ops.h +g2o/types/se3_ops.hpp +#core +g2o/core/base_edge.h +g2o/core/base_binary_edge.h +g2o/core/hyper_graph_action.cpp +g2o/core/base_binary_edge.hpp +g2o/core/hyper_graph_action.h +g2o/core/base_multi_edge.h +g2o/core/hyper_graph.cpp +g2o/core/base_multi_edge.hpp +g2o/core/hyper_graph.h +g2o/core/base_unary_edge.h +g2o/core/linear_solver.h +g2o/core/base_unary_edge.hpp +g2o/core/marginal_covariance_cholesky.cpp +g2o/core/base_vertex.h +g2o/core/marginal_covariance_cholesky.h +g2o/core/base_vertex.hpp +g2o/core/matrix_structure.cpp +g2o/core/batch_stats.cpp +g2o/core/matrix_structure.h +g2o/core/batch_stats.h +g2o/core/openmp_mutex.h +g2o/core/block_solver.h +g2o/core/block_solver.hpp +g2o/core/parameter.cpp +g2o/core/parameter.h +g2o/core/cache.cpp +g2o/core/cache.h +g2o/core/optimizable_graph.cpp +g2o/core/optimizable_graph.h +g2o/core/solver.cpp +g2o/core/solver.h +g2o/core/creators.h +g2o/core/optimization_algorithm_factory.cpp +g2o/core/estimate_propagator.cpp +g2o/core/optimization_algorithm_factory.h +g2o/core/estimate_propagator.h +g2o/core/factory.cpp +g2o/core/optimization_algorithm_property.h +g2o/core/factory.h +g2o/core/sparse_block_matrix.h +g2o/core/sparse_optimizer.cpp +g2o/core/sparse_block_matrix.hpp +g2o/core/sparse_optimizer.h +g2o/core/hyper_dijkstra.cpp +g2o/core/hyper_dijkstra.h +g2o/core/parameter_container.cpp +g2o/core/parameter_container.h +g2o/core/optimization_algorithm.cpp +g2o/core/optimization_algorithm.h +g2o/core/optimization_algorithm_with_hessian.cpp +g2o/core/optimization_algorithm_with_hessian.h +g2o/core/optimization_algorithm_levenberg.cpp +g2o/core/optimization_algorithm_levenberg.h +g2o/core/jacobian_workspace.cpp +g2o/core/jacobian_workspace.h +g2o/core/robust_kernel.cpp +g2o/core/robust_kernel.h +g2o/core/robust_kernel_factory.cpp +g2o/core/robust_kernel_factory.h +g2o/core/robust_kernel_impl.cpp +g2o/core/robust_kernel_impl.h +#stuff +g2o/stuff/string_tools.h +g2o/stuff/color_macros.h +g2o/stuff/macros.h +g2o/stuff/timeutil.cpp +g2o/stuff/misc.h +g2o/stuff/timeutil.h +g2o/stuff/os_specific.c +g2o/stuff/os_specific.h +g2o/stuff/string_tools.cpp +g2o/stuff/property.cpp +g2o/stuff/property.h +) diff --git a/Thirdparty/g2o/README.txt b/Thirdparty/g2o/README.txt new file mode 100644 index 0000000000..82641a8a1b --- /dev/null +++ b/Thirdparty/g2o/README.txt @@ -0,0 +1,3 @@ +You should have received this g2o version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2). +See the original g2o library at: https://github.com/RainerKuemmerle/g2o +All files included in this g2o version are BSD, see license-bsd.txt diff --git a/Thirdparty/g2o/cmake_modules/FindBLAS.cmake b/Thirdparty/g2o/cmake_modules/FindBLAS.cmake new file mode 100644 index 0000000000..68c4e07241 --- /dev/null +++ b/Thirdparty/g2o/cmake_modules/FindBLAS.cmake @@ -0,0 +1,419 @@ +# 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. +# +# This module was modified by CGAL team: +# - find libraries for a C++ compiler, instead of Fortran +# - added BLAS_INCLUDE_DIR, BLAS_DEFINITIONS and BLAS_LIBRARIES_DIR +# - removed BLAS95_LIBRARIES + +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 ENV LIB + ) + elseif ( APPLE ) + find_library(${_prefix}_${_library}_LIBRARY + NAMES ${_library} + PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH + ) + else () + find_library(${_prefix}_${_library}_LIBRARY + NAMES ${_library} + PATHS /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}}) + #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}}) + #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_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 "" ) + + # + # If Unix, search for BLAS function in possible libraries + # + + # BLAS in ATLAS library? (http://math-atlas.sourceforge.net/) + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "cblas;f77blas;atlas" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV 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" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + # BLAS in Alpha CXML library? + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "cxml" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV 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" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV 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" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV 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" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + # BLAS in SGIMATH library? + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "complib.sgimath" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV 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" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + #BLAS in intel mkl 10 library? (em64t 64bit) + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "mkl_intel_lp64;mkl_intel_thread;mkl_core;guide;pthread" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + ### windows version of intel mkl 10? + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + SGEMM + "" + "mkl_c_dll;mkl_intel_thread_dll;mkl_core_dll;libguide40" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + #older versions of intel mkl libs + + # BLAS in intel mkl library? (shared) + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "mkl;guide;pthread" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + #BLAS in intel mkl library? (static, 32bit) + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "mkl_ia32;guide;pthread" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + #BLAS in intel mkl library? (static, em64t 64bit) + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "mkl_em64t;guide;pthread" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + #BLAS in acml library? + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "acml" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + # Apple BLAS library? + if(NOT BLAS_LIBRARIES) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "Accelerate" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + if ( NOT BLAS_LIBRARIES ) + check_fortran_libraries( + BLAS_DEFINITIONS + BLAS_LIBRARIES + BLAS + sgemm + "" + "vecLib" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV 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" + "${CGAL_TAUCS_LIBRARIES_DIR} ENV BLAS_LIB_DIR" + ) + endif() + + if(BLAS_LIBRARIES_DIR OR BLAS_LIBRARIES) + set(BLAS_FOUND TRUE) + else() + set(BLAS_FOUND FALSE) + 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) diff --git a/Thirdparty/g2o/cmake_modules/FindEigen3.cmake b/Thirdparty/g2o/cmake_modules/FindEigen3.cmake new file mode 100644 index 0000000000..8c2a734c3d --- /dev/null +++ b/Thirdparty/g2o/cmake_modules/FindEigen3.cmake @@ -0,0 +1,87 @@ +# - Try to find Eigen3 lib +# +# This module supports requiring a minimum version, e.g. you can do +# find_package(Eigen3 3.1.2) +# to require version 3.1.2 or newer of Eigen3. +# +# Once done this will define +# +# EIGEN3_FOUND - system has eigen lib with correct version +# EIGEN3_INCLUDE_DIR - the eigen include directory +# EIGEN3_VERSION - eigen version + +# Copyright (c) 2006, 2007 Montel Laurent, +# Copyright (c) 2008, 2009 Gael Guennebaud, +# Copyright (c) 2009 Benoit Jacob +# Redistribution and use is allowed according to the terms of the 2-clause BSD license. + +if(NOT Eigen3_FIND_VERSION) + if(NOT Eigen3_FIND_VERSION_MAJOR) + set(Eigen3_FIND_VERSION_MAJOR 2) + endif(NOT Eigen3_FIND_VERSION_MAJOR) + if(NOT Eigen3_FIND_VERSION_MINOR) + set(Eigen3_FIND_VERSION_MINOR 91) + endif(NOT Eigen3_FIND_VERSION_MINOR) + if(NOT Eigen3_FIND_VERSION_PATCH) + set(Eigen3_FIND_VERSION_PATCH 0) + endif(NOT Eigen3_FIND_VERSION_PATCH) + + set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") +endif(NOT Eigen3_FIND_VERSION) + +macro(_eigen3_check_version) + file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) + + string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") + set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") + set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") + set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") + + set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) + if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK FALSE) + else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK TRUE) + endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + + if(NOT EIGEN3_VERSION_OK) + + message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " + "but at least version ${Eigen3_FIND_VERSION} is required") + endif(NOT EIGEN3_VERSION_OK) +endmacro(_eigen3_check_version) + +if (EIGEN3_INCLUDE_DIR) + + # in cache already + _eigen3_check_version() + set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) + +else (EIGEN3_INCLUDE_DIR) + + # specific additional paths for some OS + if (WIN32) + set(EIGEN_ADDITIONAL_SEARCH_PATHS ${EIGEN_ADDITIONAL_SEARCH_PATHS} "C:/Program Files/Eigen/include" "C:/Program Files (x86)/Eigen/include") + endif(WIN32) + + find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library + PATHS + ${CMAKE_INSTALL_PREFIX}/include + ${EIGEN_ADDITIONAL_SEARCH_PATHS} + ${KDE4_INCLUDE_DIR} + PATH_SUFFIXES eigen3 eigen + ) + + if(EIGEN3_INCLUDE_DIR) + _eigen3_check_version() + endif(EIGEN3_INCLUDE_DIR) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) + + mark_as_advanced(EIGEN3_INCLUDE_DIR) + +endif(EIGEN3_INCLUDE_DIR) + diff --git a/Thirdparty/g2o/cmake_modules/FindLAPACK.cmake b/Thirdparty/g2o/cmake_modules/FindLAPACK.cmake new file mode 100644 index 0000000000..2fcae2199f --- /dev/null +++ b/Thirdparty/g2o/cmake_modules/FindLAPACK.cmake @@ -0,0 +1,273 @@ +# 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 libraries for a C++ compiler, instead of Fortran +# - added LAPACK_INCLUDE_DIR, LAPACK_DEFINITIONS and LAPACK_LIBRARIES_DIR +# - removed LAPACK95_LIBRARIES + + +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_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 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 ENV LIB + ) + elseif ( APPLE ) + find_library(${_prefix}_${_library}_LIBRARY + NAMES ${_library} + PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH + ) + else () + find_library(${_prefix}_${_library}_LIBRARY + NAMES ${_library} + PATHS /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 "" ) + + # + # 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() + + if(LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES) + set(LAPACK_FOUND TRUE) + else() + set(LAPACK_FOUND FALSE) + 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) diff --git a/Thirdparty/g2o/config.h.in b/Thirdparty/g2o/config.h.in new file mode 100644 index 0000000000..49c686b1c0 --- /dev/null +++ b/Thirdparty/g2o/config.h.in @@ -0,0 +1,13 @@ +#ifndef G2O_CONFIG_H +#define G2O_CONFIG_H + +#cmakedefine G2O_OPENMP 1 +#cmakedefine G2O_SHARED_LIBS 1 + +// give a warning if Eigen defaults to row-major matrices. +// We internally assume column-major matrices throughout the code. +#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR +# error "g2o requires column major Eigen matrices (see http://eigen.tuxfamily.org/bz/show_bug.cgi?id=422)" +#endif + +#endif diff --git a/Thirdparty/g2o/g2o/core/base_binary_edge.h b/Thirdparty/g2o/g2o/core/base_binary_edge.h new file mode 100644 index 0000000000..660e83afd6 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_binary_edge.h @@ -0,0 +1,119 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BASE_BINARY_EDGE_H +#define G2O_BASE_BINARY_EDGE_H + +#include +#include + +#include "base_edge.h" +#include "robust_kernel.h" +#include "../../config.h" + +namespace g2o { + + using namespace Eigen; + + template + class BaseBinaryEdge : public BaseEdge + { + public: + + typedef VertexXi VertexXiType; + typedef VertexXj VertexXjType; + + static const int Di = VertexXiType::Dimension; + static const int Dj = VertexXjType::Dimension; + + static const int Dimension = BaseEdge::Dimension; + typedef typename BaseEdge::Measurement Measurement; + typedef typename Matrix::AlignedMapType JacobianXiOplusType; + typedef typename Matrix::AlignedMapType JacobianXjOplusType; + typedef typename BaseEdge::ErrorVector ErrorVector; + typedef typename BaseEdge::InformationType InformationType; + + typedef Eigen::Map, Matrix::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType; + typedef Eigen::Map, Matrix::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockTransposedType; + + BaseBinaryEdge() : BaseEdge(), + _hessianRowMajor(false), + _hessian(0, VertexXiType::Dimension, VertexXjType::Dimension), // HACK we map to the null pointer for initializing the Maps + _hessianTransposed(0, VertexXjType::Dimension, VertexXiType::Dimension), + _jacobianOplusXi(0, D, Di), _jacobianOplusXj(0, D, Dj) + { + _vertices.resize(2); + } + + virtual OptimizableGraph::Vertex* createFrom(); + virtual OptimizableGraph::Vertex* createTo(); + + virtual void resize(size_t size); + + virtual bool allVerticesFixed() const; + + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace); + + /** + * Linearizes the oplus operator in the vertex, and stores + * the result in temporary variables _jacobianOplusXi and _jacobianOplusXj + */ + virtual void linearizeOplus(); + + //! returns the result of the linearization in the manifold space for the node xi + const JacobianXiOplusType& jacobianOplusXi() const { return _jacobianOplusXi;} + //! returns the result of the linearization in the manifold space for the node xj + const JacobianXjOplusType& jacobianOplusXj() const { return _jacobianOplusXj;} + + virtual void constructQuadraticForm() ; + + virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor); + + using BaseEdge::resize; + using BaseEdge::computeError; + + protected: + using BaseEdge::_measurement; + using BaseEdge::_information; + using BaseEdge::_error; + using BaseEdge::_vertices; + using BaseEdge::_dimension; + + bool _hessianRowMajor; + HessianBlockType _hessian; + HessianBlockTransposedType _hessianTransposed; + JacobianXiOplusType _jacobianOplusXi; + JacobianXjOplusType _jacobianOplusXj; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#include "base_binary_edge.hpp" + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/base_binary_edge.hpp b/Thirdparty/g2o/g2o/core/base_binary_edge.hpp new file mode 100644 index 0000000000..7542a9fd61 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_binary_edge.hpp @@ -0,0 +1,218 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +template +OptimizableGraph::Vertex* BaseBinaryEdge::createFrom(){ + return new VertexXiType(); +} + +template +OptimizableGraph::Vertex* BaseBinaryEdge::createTo(){ + return new VertexXjType(); +} + + +template +void BaseBinaryEdge::resize(size_t size) +{ + if (size != 2) { + std::cerr << "WARNING, attempting to resize binary edge " << BaseEdge::id() << " to " << size << std::endl; + } + BaseEdge::resize(size); +} + +template +bool BaseBinaryEdge::allVerticesFixed() const +{ + return (static_cast (_vertices[0])->fixed() && + static_cast (_vertices[1])->fixed()); +} + +template +void BaseBinaryEdge::constructQuadraticForm() +{ + VertexXiType* from = static_cast(_vertices[0]); + VertexXjType* to = static_cast(_vertices[1]); + + // get the Jacobian of the nodes in the manifold domain + const JacobianXiOplusType& A = jacobianOplusXi(); + const JacobianXjOplusType& B = jacobianOplusXj(); + + + bool fromNotFixed = !(from->fixed()); + bool toNotFixed = !(to->fixed()); + + if (fromNotFixed || toNotFixed) { +#ifdef G2O_OPENMP + from->lockQuadraticForm(); + to->lockQuadraticForm(); +#endif + const InformationType& omega = _information; + Matrix omega_r = - omega * _error; + if (this->robustKernel() == 0) { + if (fromNotFixed) { + Matrix AtO = A.transpose() * omega; + from->b().noalias() += A.transpose() * omega_r; + from->A().noalias() += AtO*A; + if (toNotFixed ) { + if (_hessianRowMajor) // we have to write to the block as transposed + _hessianTransposed.noalias() += B.transpose() * AtO.transpose(); + else + _hessian.noalias() += AtO * B; + } + } + if (toNotFixed) { + to->b().noalias() += B.transpose() * omega_r; + to->A().noalias() += B.transpose() * omega * B; + } + } else { // robust (weighted) error according to some kernel + double error = this->chi2(); + Eigen::Vector3d rho; + this->robustKernel()->robustify(error, rho); + InformationType weightedOmega = this->robustInformation(rho); + //std::cout << PVAR(rho.transpose()) << std::endl; + //std::cout << PVAR(weightedOmega) << std::endl; + + omega_r *= rho[1]; + if (fromNotFixed) { + from->b().noalias() += A.transpose() * omega_r; + from->A().noalias() += A.transpose() * weightedOmega * A; + if (toNotFixed ) { + if (_hessianRowMajor) // we have to write to the block as transposed + _hessianTransposed.noalias() += B.transpose() * weightedOmega * A; + else + _hessian.noalias() += A.transpose() * weightedOmega * B; + } + } + if (toNotFixed) { + to->b().noalias() += B.transpose() * omega_r; + to->A().noalias() += B.transpose() * weightedOmega * B; + } + } +#ifdef G2O_OPENMP + to->unlockQuadraticForm(); + from->unlockQuadraticForm(); +#endif + } +} + +template +void BaseBinaryEdge::linearizeOplus(JacobianWorkspace& jacobianWorkspace) +{ + new (&_jacobianOplusXi) JacobianXiOplusType(jacobianWorkspace.workspaceForVertex(0), D, Di); + new (&_jacobianOplusXj) JacobianXjOplusType(jacobianWorkspace.workspaceForVertex(1), D, Dj); + linearizeOplus(); +} + +template +void BaseBinaryEdge::linearizeOplus() +{ + VertexXiType* vi = static_cast(_vertices[0]); + VertexXjType* vj = static_cast(_vertices[1]); + + bool iNotFixed = !(vi->fixed()); + bool jNotFixed = !(vj->fixed()); + + if (!iNotFixed && !jNotFixed) + return; + +#ifdef G2O_OPENMP + vi->lockQuadraticForm(); + vj->lockQuadraticForm(); +#endif + + const double delta = 1e-9; + const double scalar = 1.0 / (2*delta); + ErrorVector errorBak; + ErrorVector errorBeforeNumeric = _error; + + if (iNotFixed) { + //Xi - estimate the jacobian numerically + double add_vi[VertexXiType::Dimension]; + std::fill(add_vi, add_vi + VertexXiType::Dimension, 0.0); + // add small step along the unit vector in each dimension + for (int d = 0; d < VertexXiType::Dimension; ++d) { + vi->push(); + add_vi[d] = delta; + vi->oplus(add_vi); + computeError(); + errorBak = _error; + vi->pop(); + vi->push(); + add_vi[d] = -delta; + vi->oplus(add_vi); + computeError(); + errorBak -= _error; + vi->pop(); + add_vi[d] = 0.0; + + _jacobianOplusXi.col(d) = scalar * errorBak; + } // end dimension + } + + if (jNotFixed) { + //Xj - estimate the jacobian numerically + double add_vj[VertexXjType::Dimension]; + std::fill(add_vj, add_vj + VertexXjType::Dimension, 0.0); + // add small step along the unit vector in each dimension + for (int d = 0; d < VertexXjType::Dimension; ++d) { + vj->push(); + add_vj[d] = delta; + vj->oplus(add_vj); + computeError(); + errorBak = _error; + vj->pop(); + vj->push(); + add_vj[d] = -delta; + vj->oplus(add_vj); + computeError(); + errorBak -= _error; + vj->pop(); + add_vj[d] = 0.0; + + _jacobianOplusXj.col(d) = scalar * errorBak; + } + } // end dimension + + _error = errorBeforeNumeric; +#ifdef G2O_OPENMP + vj->unlockQuadraticForm(); + vi->unlockQuadraticForm(); +#endif +} + +template +void BaseBinaryEdge::mapHessianMemory(double* d, int i, int j, bool rowMajor) +{ + (void) i; (void) j; + //assert(i == 0 && j == 1); + if (rowMajor) { + new (&_hessianTransposed) HessianBlockTransposedType(d, VertexXjType::Dimension, VertexXiType::Dimension); + } else { + new (&_hessian) HessianBlockType(d, VertexXiType::Dimension, VertexXjType::Dimension); + } + _hessianRowMajor = rowMajor; +} diff --git a/Thirdparty/g2o/g2o/core/base_edge.h b/Thirdparty/g2o/g2o/core/base_edge.h new file mode 100644 index 0000000000..91139e4f0d --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_edge.h @@ -0,0 +1,110 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BASE_EDGE_H +#define G2O_BASE_EDGE_H + +#include +#include + +#include + +#include "optimizable_graph.h" + +namespace g2o { + + using namespace Eigen; + + template + class BaseEdge : public OptimizableGraph::Edge + { + public: + + static const int Dimension = D; + typedef E Measurement; + typedef Matrix ErrorVector; + typedef Matrix InformationType; + + BaseEdge() : OptimizableGraph::Edge() + { + _dimension = D; + } + + virtual ~BaseEdge() {} + + virtual double chi2() const + { + return _error.dot(information()*_error); + } + + virtual const double* errorData() const { return _error.data();} + virtual double* errorData() { return _error.data();} + const ErrorVector& error() const { return _error;} + ErrorVector& error() { return _error;} + + //! information matrix of the constraint + const InformationType& information() const { return _information;} + InformationType& information() { return _information;} + void setInformation(const InformationType& information) { _information = information;} + + virtual const double* informationData() const { return _information.data();} + virtual double* informationData() { return _information.data();} + + //! accessor functions for the measurement represented by the edge + const Measurement& measurement() const { return _measurement;} + virtual void setMeasurement(const Measurement& m) { _measurement = m;} + + virtual int rank() const {return _dimension;} + + virtual void initialEstimate(const OptimizableGraph::VertexSet&, OptimizableGraph::Vertex*) + { + std::cerr << "inititialEstimate() is not implemented, please give implementation in your derived class" << std::endl; + } + + protected: + + Measurement _measurement; + InformationType _information; + ErrorVector _error; + + /** + * calculate the robust information matrix by updating the information matrix of the error + */ + InformationType robustInformation(const Eigen::Vector3d& rho) + { + InformationType result = rho[1] * _information; + //ErrorVector weightedErrror = _information * _error; + //result.noalias() += 2 * rho[2] * (weightedErrror * weightedErrror.transpose()); + return result; + } + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/base_multi_edge.h b/Thirdparty/g2o/g2o/core/base_multi_edge.h new file mode 100644 index 0000000000..dd2261fd48 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_multi_edge.h @@ -0,0 +1,113 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BASE_MULTI_EDGE_H +#define G2O_BASE_MULTI_EDGE_H + +#include +#include +#include + +#include + +#include "base_edge.h" +#include "robust_kernel.h" +#include "../../config.h" + +namespace g2o { + + using namespace Eigen; + + /** + * \brief base class to represent an edge connecting an arbitrary number of nodes + * + * D - Dimension of the measurement + * E - type to represent the measurement + */ + template + class BaseMultiEdge : public BaseEdge + { + public: + /** + * \brief helper for mapping the Hessian memory of the upper triangular block + */ + struct HessianHelper { + Eigen::Map matrix; ///< the mapped memory + bool transposed; ///< the block has to be transposed + HessianHelper() : matrix(0, 0, 0), transposed(false) {} + }; + + public: + static const int Dimension = BaseEdge::Dimension; + typedef typename BaseEdge::Measurement Measurement; + typedef MatrixXd::MapType JacobianType; + typedef typename BaseEdge::ErrorVector ErrorVector; + typedef typename BaseEdge::InformationType InformationType; + typedef Eigen::Map HessianBlockType; + + BaseMultiEdge() : BaseEdge() + { + } + + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace); + + /** + * Linearizes the oplus operator in the vertex, and stores + * the result in temporary variable vector _jacobianOplus + */ + virtual void linearizeOplus(); + + virtual void resize(size_t size); + + virtual bool allVerticesFixed() const; + + virtual void constructQuadraticForm() ; + + virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor); + + using BaseEdge::computeError; + + protected: + using BaseEdge::_measurement; + using BaseEdge::_information; + using BaseEdge::_error; + using BaseEdge::_vertices; + using BaseEdge::_dimension; + + std::vector _hessian; + std::vector > _jacobianOplus; ///< jacobians of the edge (w.r.t. oplus) + + void computeQuadraticForm(const InformationType& omega, const ErrorVector& weightedError); + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#include "base_multi_edge.hpp" + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/base_multi_edge.hpp b/Thirdparty/g2o/g2o/core/base_multi_edge.hpp new file mode 100644 index 0000000000..a2fa66d955 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_multi_edge.hpp @@ -0,0 +1,222 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +namespace internal { + inline int computeUpperTriangleIndex(int i, int j) + { + int elemsUpToCol = ((j-1) * j) / 2; + return elemsUpToCol + i; + } +} + +template +void BaseMultiEdge::constructQuadraticForm() +{ + if (this->robustKernel()) { + double error = this->chi2(); + Eigen::Vector3d rho; + this->robustKernel()->robustify(error, rho); + Matrix omega_r = - _information * _error; + omega_r *= rho[1]; + computeQuadraticForm(this->robustInformation(rho), omega_r); + } else { + computeQuadraticForm(_information, - _information * _error); + } +} + + +template +void BaseMultiEdge::linearizeOplus(JacobianWorkspace& jacobianWorkspace) +{ + for (size_t i = 0; i < _vertices.size(); ++i) { + OptimizableGraph::Vertex* v = static_cast(_vertices[i]); + assert(v->dimension() >= 0); + new (&_jacobianOplus[i]) JacobianType(jacobianWorkspace.workspaceForVertex(i), D, v->dimension()); + } + linearizeOplus(); +} + +template +void BaseMultiEdge::linearizeOplus() +{ +#ifdef G2O_OPENMP + for (size_t i = 0; i < _vertices.size(); ++i) { + OptimizableGraph::Vertex* v = static_cast(_vertices[i]); + v->lockQuadraticForm(); + } +#endif + + const double delta = 1e-9; + const double scalar = 1.0 / (2*delta); + ErrorVector errorBak; + ErrorVector errorBeforeNumeric = _error; + + for (size_t i = 0; i < _vertices.size(); ++i) { + //Xi - estimate the jacobian numerically + OptimizableGraph::Vertex* vi = static_cast(_vertices[i]); + + if (vi->fixed()) + continue; + + const int vi_dim = vi->dimension(); + assert(vi_dim >= 0); +#ifdef _MSC_VER + double* add_vi = new double[vi_dim]; +#else + double add_vi[vi_dim]; +#endif + std::fill(add_vi, add_vi + vi_dim, 0.0); + assert(_dimension >= 0); + assert(_jacobianOplus[i].rows() == _dimension && _jacobianOplus[i].cols() == vi_dim && "jacobian cache dimension does not match"); + _jacobianOplus[i].resize(_dimension, vi_dim); + // add small step along the unit vector in each dimension + for (int d = 0; d < vi_dim; ++d) { + vi->push(); + add_vi[d] = delta; + vi->oplus(add_vi); + computeError(); + errorBak = _error; + vi->pop(); + vi->push(); + add_vi[d] = -delta; + vi->oplus(add_vi); + computeError(); + errorBak -= _error; + vi->pop(); + add_vi[d] = 0.0; + + _jacobianOplus[i].col(d) = scalar * errorBak; + } // end dimension +#ifdef _MSC_VER + delete[] add_vi; +#endif + } + _error = errorBeforeNumeric; + +#ifdef G2O_OPENMP + for (int i = (int)(_vertices.size()) - 1; i >= 0; --i) { + OptimizableGraph::Vertex* v = static_cast(_vertices[i]); + v->unlockQuadraticForm(); + } +#endif + +} + +template +void BaseMultiEdge::mapHessianMemory(double* d, int i, int j, bool rowMajor) +{ + int idx = internal::computeUpperTriangleIndex(i, j); + assert(idx < (int)_hessian.size()); + OptimizableGraph::Vertex* vi = static_cast(HyperGraph::Edge::vertex(i)); + OptimizableGraph::Vertex* vj = static_cast(HyperGraph::Edge::vertex(j)); + assert(vi->dimension() >= 0); + assert(vj->dimension() >= 0); + HessianHelper& h = _hessian[idx]; + if (rowMajor) { + if (h.matrix.data() != d || h.transposed != rowMajor) + new (&h.matrix) HessianBlockType(d, vj->dimension(), vi->dimension()); + } else { + if (h.matrix.data() != d || h.transposed != rowMajor) + new (&h.matrix) HessianBlockType(d, vi->dimension(), vj->dimension()); + } + h.transposed = rowMajor; +} + +template +void BaseMultiEdge::resize(size_t size) +{ + BaseEdge::resize(size); + int n = (int)_vertices.size(); + int maxIdx = (n * (n-1))/2; + assert(maxIdx >= 0); + _hessian.resize(maxIdx); + _jacobianOplus.resize(size, JacobianType(0,0,0)); +} + +template +bool BaseMultiEdge::allVerticesFixed() const +{ + for (size_t i = 0; i < _vertices.size(); ++i) { + if (!static_cast (_vertices[i])->fixed()) { + return false; + } + } + return true; +} + +template +void BaseMultiEdge::computeQuadraticForm(const InformationType& omega, const ErrorVector& weightedError) +{ + for (size_t i = 0; i < _vertices.size(); ++i) { + OptimizableGraph::Vertex* from = static_cast(_vertices[i]); + bool istatus = !(from->fixed()); + + if (istatus) { + const MatrixXd& A = _jacobianOplus[i]; + + MatrixXd AtO = A.transpose() * omega; + int fromDim = from->dimension(); + assert(fromDim >= 0); + Eigen::Map fromMap(from->hessianData(), fromDim, fromDim); + Eigen::Map fromB(from->bData(), fromDim); + + // ii block in the hessian +#ifdef G2O_OPENMP + from->lockQuadraticForm(); +#endif + fromMap.noalias() += AtO * A; + fromB.noalias() += A.transpose() * weightedError; + + // compute the off-diagonal blocks ij for all j + for (size_t j = i+1; j < _vertices.size(); ++j) { + OptimizableGraph::Vertex* to = static_cast(_vertices[j]); +#ifdef G2O_OPENMP + to->lockQuadraticForm(); +#endif + bool jstatus = !(to->fixed()); + if (jstatus) { + const MatrixXd& B = _jacobianOplus[j]; + int idx = internal::computeUpperTriangleIndex(i, j); + assert(idx < (int)_hessian.size()); + HessianHelper& hhelper = _hessian[idx]; + if (hhelper.transposed) { // we have to write to the block as transposed + hhelper.matrix.noalias() += B.transpose() * AtO.transpose(); + } else { + hhelper.matrix.noalias() += AtO * B; + } + } +#ifdef G2O_OPENMP + to->unlockQuadraticForm(); +#endif + } + +#ifdef G2O_OPENMP + from->unlockQuadraticForm(); +#endif + } + + } +} diff --git a/Thirdparty/g2o/g2o/core/base_unary_edge.h b/Thirdparty/g2o/g2o/core/base_unary_edge.h new file mode 100644 index 0000000000..28df8a564b --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_unary_edge.h @@ -0,0 +1,100 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BASE_UNARY_EDGE_H +#define G2O_BASE_UNARY_EDGE_H + +#include +#include +#include + +#include "base_edge.h" +#include "robust_kernel.h" +#include "../../config.h" + +namespace g2o { + + using namespace Eigen; + + template + class BaseUnaryEdge : public BaseEdge + { + public: + static const int Dimension = BaseEdge::Dimension; + typedef typename BaseEdge::Measurement Measurement; + typedef VertexXi VertexXiType; + typedef typename Matrix::AlignedMapType JacobianXiOplusType; + typedef typename BaseEdge::ErrorVector ErrorVector; + typedef typename BaseEdge::InformationType InformationType; + + BaseUnaryEdge() : BaseEdge(), + _jacobianOplusXi(0, D, VertexXiType::Dimension) + { + _vertices.resize(1); + } + + virtual void resize(size_t size); + + virtual bool allVerticesFixed() const; + + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace); + + /** + * Linearizes the oplus operator in the vertex, and stores + * the result in temporary variables _jacobianOplusXi and _jacobianOplusXj + */ + virtual void linearizeOplus(); + + //! returns the result of the linearization in the manifold space for the node xi + const JacobianXiOplusType& jacobianOplusXi() const { return _jacobianOplusXi;} + + virtual void constructQuadraticForm(); + + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to); + + virtual void mapHessianMemory(double*, int, int, bool) {assert(0 && "BaseUnaryEdge does not map memory of the Hessian");} + + using BaseEdge::resize; + using BaseEdge::computeError; + + protected: + using BaseEdge::_measurement; + using BaseEdge::_information; + using BaseEdge::_error; + using BaseEdge::_vertices; + using BaseEdge::_dimension; + + JacobianXiOplusType _jacobianOplusXi; + + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + +#include "base_unary_edge.hpp" + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/base_unary_edge.hpp b/Thirdparty/g2o/g2o/core/base_unary_edge.hpp new file mode 100644 index 0000000000..464900fb1e --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_unary_edge.hpp @@ -0,0 +1,129 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +template +void BaseUnaryEdge::resize(size_t size) +{ + if (size != 1) { + std::cerr << "WARNING, attempting to resize unary edge " << BaseEdge::id() << " to " << size << std::endl; + } + BaseEdge::resize(size); +} + +template +bool BaseUnaryEdge::allVerticesFixed() const +{ + return static_cast (_vertices[0])->fixed(); +} + +template +void BaseUnaryEdge::constructQuadraticForm() +{ + VertexXiType* from=static_cast(_vertices[0]); + + // chain rule to get the Jacobian of the nodes in the manifold domain + const JacobianXiOplusType& A = jacobianOplusXi(); + const InformationType& omega = _information; + + bool istatus = !from->fixed(); + if (istatus) { +#ifdef G2O_OPENMP + from->lockQuadraticForm(); +#endif + if (this->robustKernel()) { + double error = this->chi2(); + Eigen::Vector3d rho; + this->robustKernel()->robustify(error, rho); + InformationType weightedOmega = this->robustInformation(rho); + + from->b().noalias() -= rho[1] * A.transpose() * omega * _error; + from->A().noalias() += A.transpose() * weightedOmega * A; + } else { + from->b().noalias() -= A.transpose() * omega * _error; + from->A().noalias() += A.transpose() * omega * A; + } +#ifdef G2O_OPENMP + from->unlockQuadraticForm(); +#endif + } +} + +template +void BaseUnaryEdge::linearizeOplus(JacobianWorkspace& jacobianWorkspace) +{ + new (&_jacobianOplusXi) JacobianXiOplusType(jacobianWorkspace.workspaceForVertex(0), D, VertexXiType::Dimension); + linearizeOplus(); +} + +template +void BaseUnaryEdge::linearizeOplus() +{ + //Xi - estimate the jacobian numerically + VertexXiType* vi = static_cast(_vertices[0]); + + if (vi->fixed()) + return; + +#ifdef G2O_OPENMP + vi->lockQuadraticForm(); +#endif + + const double delta = 1e-9; + const double scalar = 1.0 / (2*delta); + ErrorVector error1; + ErrorVector errorBeforeNumeric = _error; + + double add_vi[VertexXiType::Dimension]; + std::fill(add_vi, add_vi + VertexXiType::Dimension, 0.0); + // add small step along the unit vector in each dimension + for (int d = 0; d < VertexXiType::Dimension; ++d) { + vi->push(); + add_vi[d] = delta; + vi->oplus(add_vi); + computeError(); + error1 = _error; + vi->pop(); + vi->push(); + add_vi[d] = -delta; + vi->oplus(add_vi); + computeError(); + vi->pop(); + add_vi[d] = 0.0; + + _jacobianOplusXi.col(d) = scalar * (error1 - _error); + } // end dimension + + _error = errorBeforeNumeric; +#ifdef G2O_OPENMP + vi->unlockQuadraticForm(); +#endif +} + +template +void BaseUnaryEdge::initialEstimate(const OptimizableGraph::VertexSet&, OptimizableGraph::Vertex*) +{ + std::cerr << __PRETTY_FUNCTION__ << " is not implemented, please give implementation in your derived class" << std::endl; +} diff --git a/Thirdparty/g2o/g2o/core/base_vertex.h b/Thirdparty/g2o/g2o/core/base_vertex.h new file mode 100644 index 0000000000..e375fdeef9 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_vertex.h @@ -0,0 +1,120 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BASE_VERTEX_H +#define G2O_BASE_VERTEX_H + +#include "optimizable_graph.h" +#include "creators.h" +#include "../stuff/macros.h" + +#include +#include +#include +#include +#include + +namespace g2o { + + using namespace Eigen; + + +/** + * \brief Templatized BaseVertex + * + * Templatized BaseVertex + * D : minimal dimension of the vertex, e.g., 3 for rotation in 3D + * T : internal type to represent the estimate, e.g., Quaternion for rotation in 3D + */ + template + class BaseVertex : public OptimizableGraph::Vertex { + public: + typedef T EstimateType; + typedef std::stack > > + BackupStackType; + + static const int Dimension = D; ///< dimension of the estimate (minimal) in the manifold space + + typedef Eigen::Map, Matrix::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType; + + public: + BaseVertex(); + + virtual const double& hessian(int i, int j) const { assert(i(_hessian.data());} + + virtual void mapHessianMemory(double* d); + + virtual int copyB(double* b_) const { + memcpy(b_, _b.data(), Dimension * sizeof(double)); + return Dimension; + } + + virtual const double& b(int i) const { assert(i < D); return _b(i);} + virtual double& b(int i) { assert(i < D); return _b(i);} + virtual double* bData() { return _b.data();} + + virtual void clearQuadraticForm(); + + //! updates the current vertex with the direct solution x += H_ii\b_ii + //! @returns the determinant of the inverted hessian + virtual double solveDirect(double lambda=0); + + //! return right hand side b of the constructed linear system + Matrix& b() { return _b;} + const Matrix& b() const { return _b;} + //! return the hessian block associated with the vertex + HessianBlockType& A() { return _hessian;} + const HessianBlockType& A() const { return _hessian;} + + virtual void push() { _backup.push(_estimate);} + virtual void pop() { assert(!_backup.empty()); _estimate = _backup.top(); _backup.pop(); updateCache();} + virtual void discardTop() { assert(!_backup.empty()); _backup.pop();} + virtual int stackSize() const {return _backup.size();} + + //! return the current estimate of the vertex + const EstimateType& estimate() const { return _estimate;} + //! set the estimate for the vertex also calls updateCache() + void setEstimate(const EstimateType& et) { _estimate = et; updateCache();} + + protected: + HessianBlockType _hessian; + Matrix _b; + EstimateType _estimate; + BackupStackType _backup; + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +#include "base_vertex.hpp" + +} // end namespace g2o + + +#endif diff --git a/Thirdparty/g2o/g2o/core/base_vertex.hpp b/Thirdparty/g2o/g2o/core/base_vertex.hpp new file mode 100644 index 0000000000..f21ff165c1 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/base_vertex.hpp @@ -0,0 +1,55 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +template +BaseVertex::BaseVertex() : + OptimizableGraph::Vertex(), + _hessian(0, D, D) +{ + _dimension = D; +} + +template +double BaseVertex::solveDirect(double lambda) { + Matrix tempA=_hessian + Matrix ::Identity()*lambda; + double det=tempA.determinant(); + if (g2o_isnan(det) || det < std::numeric_limits::epsilon()) + return det; + Matrix dx=tempA.llt().solve(_b); + oplus(&dx[0]); + return det; +} + +template +void BaseVertex::clearQuadraticForm() { + _b.setZero(); +} + +template +void BaseVertex::mapHessianMemory(double* d) +{ + new (&_hessian) HessianBlockType(d, D, D); +} diff --git a/Thirdparty/g2o/g2o/core/batch_stats.cpp b/Thirdparty/g2o/g2o/core/batch_stats.cpp new file mode 100644 index 0000000000..a6beb69b23 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/batch_stats.cpp @@ -0,0 +1,90 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "batch_stats.h" +#include + +namespace g2o { + using namespace std; + + G2OBatchStatistics* G2OBatchStatistics::_globalStats=0; + + #ifndef PTHING + #define PTHING(s) \ + #s << "= " << (st.s) << "\t " + #endif + + G2OBatchStatistics::G2OBatchStatistics(){ + // zero all. + memset (this, 0, sizeof(G2OBatchStatistics)); + + // set the iteration to -1 to show that it isn't valid + iteration = -1; + } + + std::ostream& operator << (std::ostream& os , const G2OBatchStatistics& st) + { + os << PTHING(iteration); + + os << PTHING( numVertices ); // how many vertices are involved + os << PTHING( numEdges ); // hoe many edges + os << PTHING( chi2 ); // total chi2 + + /** timings **/ + // nonlinear part + os << PTHING( timeResiduals ); + os << PTHING( timeLinearize ); // jacobians + os << PTHING( timeQuadraticForm ); // construct the quadratic form in the graph + + // block_solver (constructs Ax=b, plus maybe schur); + os << PTHING( timeSchurComplement ); // compute schur complement (0 if not done); + + // linear solver (computes Ax=b); ); + os << PTHING( timeSymbolicDecomposition ); // symbolic decomposition (0 if not done); + os << PTHING( timeNumericDecomposition ); // numeric decomposition (0 if not done); + os << PTHING( timeLinearSolution ); // total time for solving Ax=b + os << PTHING( iterationsLinearSolver ); // iterations of PCG + os << PTHING( timeUpdate ); // oplus + os << PTHING( timeIteration ); // total time ); + + os << PTHING( levenbergIterations ); + os << PTHING( timeLinearSolver); + + os << PTHING(hessianDimension); + os << PTHING(hessianPoseDimension); + os << PTHING(hessianLandmarkDimension); + os << PTHING(choleskyNNZ); + os << PTHING(timeMarginals); + + return os; + }; + + void G2OBatchStatistics::setGlobalStats(G2OBatchStatistics* b) + { + _globalStats = b; + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/batch_stats.h b/Thirdparty/g2o/g2o/core/batch_stats.h new file mode 100644 index 0000000000..d039f65677 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/batch_stats.h @@ -0,0 +1,83 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BATCH_STATS_H_ +#define G2O_BATCH_STATS_H_ + +#include +#include + + +namespace g2o { + + /** + * \brief statistics about the optimization + */ + struct G2OBatchStatistics { + G2OBatchStatistics(); + int iteration; ///< which iteration + int numVertices; ///< how many vertices are involved + int numEdges; ///< how many edges + double chi2; ///< total chi2 + + /** timings **/ + // nonlinear part + double timeResiduals; ///< residuals + double timeLinearize; ///< jacobians + double timeQuadraticForm; ///< construct the quadratic form in the graph + int levenbergIterations; ///< number of iterations performed by LM + // block_solver (constructs Ax=b, plus maybe schur) + double timeSchurComplement; ///< compute schur complement (0 if not done) + + // linear solver (computes Ax=b); + double timeSymbolicDecomposition; ///< symbolic decomposition (0 if not done) + double timeNumericDecomposition; ///< numeric decomposition (0 if not done) + double timeLinearSolution; ///< total time for solving Ax=b (including detup for schur) + double timeLinearSolver; ///< time for solving, excluding Schur setup + int iterationsLinearSolver; ///< iterations of PCG, (0 if not used, i.e., Cholesky) + double timeUpdate; ///< time to apply the update + double timeIteration; ///< total time; + + double timeMarginals; ///< computing the inverse elements (solve blocks) and thus the marginal covariances + + // information about the Hessian matrix + size_t hessianDimension; ///< rows / cols of the Hessian + size_t hessianPoseDimension; ///< dimension of the pose matrix in Schur + size_t hessianLandmarkDimension; ///< dimension of the landmark matrix in Schur + size_t choleskyNNZ; ///< number of non-zeros in the cholesky factor + + static G2OBatchStatistics* globalStats() {return _globalStats;} + static void setGlobalStats(G2OBatchStatistics* b); + protected: + static G2OBatchStatistics* _globalStats; + }; + + std::ostream& operator<<(std::ostream&, const G2OBatchStatistics&); + + typedef std::vector BatchStatisticsContainer; +} + +#endif diff --git a/Thirdparty/g2o/g2o/core/block_solver.h b/Thirdparty/g2o/g2o/core/block_solver.h new file mode 100644 index 0000000000..a393398962 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/block_solver.h @@ -0,0 +1,193 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_BLOCK_SOLVER_H +#define G2O_BLOCK_SOLVER_H +#include +#include "solver.h" +#include "linear_solver.h" +#include "sparse_block_matrix.h" +#include "sparse_block_matrix_diagonal.h" +#include "openmp_mutex.h" +#include "../../config.h" + +namespace g2o { + using namespace Eigen; + + /** + * \brief traits to summarize the properties of the fixed size optimization problem + */ + template + struct BlockSolverTraits + { + static const int PoseDim = _PoseDim; + static const int LandmarkDim = _LandmarkDim; + typedef Matrix PoseMatrixType; + typedef Matrix LandmarkMatrixType; + typedef Matrix PoseLandmarkMatrixType; + typedef Matrix PoseVectorType; + typedef Matrix LandmarkVectorType; + + typedef SparseBlockMatrix PoseHessianType; + typedef SparseBlockMatrix LandmarkHessianType; + typedef SparseBlockMatrix PoseLandmarkHessianType; + typedef LinearSolver LinearSolverType; + }; + + /** + * \brief traits to summarize the properties of the dynamic size optimization problem + */ + template <> + struct BlockSolverTraits + { + static const int PoseDim = Eigen::Dynamic; + static const int LandmarkDim = Eigen::Dynamic; + typedef MatrixXd PoseMatrixType; + typedef MatrixXd LandmarkMatrixType; + typedef MatrixXd PoseLandmarkMatrixType; + typedef VectorXd PoseVectorType; + typedef VectorXd LandmarkVectorType; + + typedef SparseBlockMatrix PoseHessianType; + typedef SparseBlockMatrix LandmarkHessianType; + typedef SparseBlockMatrix PoseLandmarkHessianType; + typedef LinearSolver LinearSolverType; + }; + + /** + * \brief base for the block solvers with some basic function interfaces + */ + class BlockSolverBase : public Solver + { + public: + virtual ~BlockSolverBase() {} + /** + * compute dest = H * src + */ + virtual void multiplyHessian(double* dest, const double* src) const = 0; + }; + + /** + * \brief Implementation of a solver operating on the blocks of the Hessian + */ + template + class BlockSolver: public BlockSolverBase { + public: + + static const int PoseDim = Traits::PoseDim; + static const int LandmarkDim = Traits::LandmarkDim; + typedef typename Traits::PoseMatrixType PoseMatrixType; + typedef typename Traits::LandmarkMatrixType LandmarkMatrixType; + typedef typename Traits::PoseLandmarkMatrixType PoseLandmarkMatrixType; + typedef typename Traits::PoseVectorType PoseVectorType; + typedef typename Traits::LandmarkVectorType LandmarkVectorType; + + typedef typename Traits::PoseHessianType PoseHessianType; + typedef typename Traits::LandmarkHessianType LandmarkHessianType; + typedef typename Traits::PoseLandmarkHessianType PoseLandmarkHessianType; + typedef typename Traits::LinearSolverType LinearSolverType; + + public: + + /** + * allocate a block solver ontop of the underlying linear solver. + * NOTE: The BlockSolver assumes exclusive access to the linear solver and will therefore free the pointer + * in its destructor. + */ + BlockSolver(LinearSolverType* linearSolver); + ~BlockSolver(); + + virtual bool init(SparseOptimizer* optmizer, bool online = false); + virtual bool buildStructure(bool zeroBlocks = false); + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges); + virtual bool buildSystem(); + virtual bool solve(); + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); + virtual bool setLambda(double lambda, bool backup = false); + virtual void restoreDiagonal(); + virtual bool supportsSchur() {return true;} + virtual bool schur() { return _doSchur;} + virtual void setSchur(bool s) { _doSchur = s;} + + LinearSolver* linearSolver() const { return _linearSolver;} + + virtual void setWriteDebug(bool writeDebug); + virtual bool writeDebug() const {return _linearSolver->writeDebug();} + + virtual bool saveHessian(const std::string& fileName) const; + + virtual void multiplyHessian(double* dest, const double* src) const { _Hpp->multiplySymmetricUpperTriangle(dest, src);} + + protected: + void resize(int* blockPoseIndices, int numPoseBlocks, + int* blockLandmarkIndices, int numLandmarkBlocks, int totalDim); + + void deallocate(); + + SparseBlockMatrix* _Hpp; + SparseBlockMatrix* _Hll; + SparseBlockMatrix* _Hpl; + + SparseBlockMatrix* _Hschur; + SparseBlockMatrixDiagonal* _DInvSchur; + + SparseBlockMatrixCCS* _HplCCS; + SparseBlockMatrixCCS* _HschurTransposedCCS; + + LinearSolver* _linearSolver; + + std::vector > _diagonalBackupPose; + std::vector > _diagonalBackupLandmark; + +# ifdef G2O_OPENMP + std::vector _coefficientsMutex; +# endif + + bool _doSchur; + + double* _coefficients; + double* _bschur; + + int _numPoses, _numLandmarks; + int _sizePoses, _sizeLandmarks; + }; + + + //variable size solver + typedef BlockSolver< BlockSolverTraits > BlockSolverX; + // solver for BA/3D SLAM + typedef BlockSolver< BlockSolverTraits<6, 3> > BlockSolver_6_3; + // solver fo BA with scale + typedef BlockSolver< BlockSolverTraits<7, 3> > BlockSolver_7_3; + // 2Dof landmarks 3Dof poses + typedef BlockSolver< BlockSolverTraits<3, 2> > BlockSolver_3_2; + +} // end namespace + +#include "block_solver.hpp" + + +#endif diff --git a/Thirdparty/g2o/g2o/core/block_solver.hpp b/Thirdparty/g2o/g2o/core/block_solver.hpp new file mode 100644 index 0000000000..f8b032eedf --- /dev/null +++ b/Thirdparty/g2o/g2o/core/block_solver.hpp @@ -0,0 +1,634 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "sparse_optimizer.h" +#include +#include +#include + +#include "../stuff/timeutil.h" +#include "../stuff/macros.h" +#include "../stuff/misc.h" + +namespace g2o { + +using namespace std; +using namespace Eigen; + +template +BlockSolver::BlockSolver(LinearSolverType* linearSolver) : + BlockSolverBase(), + _linearSolver(linearSolver) +{ + // workspace + _Hpp=0; + _Hll=0; + _Hpl=0; + _HplCCS = 0; + _HschurTransposedCCS = 0; + _Hschur=0; + _DInvSchur=0; + _coefficients=0; + _bschur = 0; + _xSize=0; + _numPoses=0; + _numLandmarks=0; + _sizePoses=0; + _sizeLandmarks=0; + _doSchur=true; +} + +template +void BlockSolver::resize(int* blockPoseIndices, int numPoseBlocks, + int* blockLandmarkIndices, int numLandmarkBlocks, + int s) +{ + deallocate(); + + resizeVector(s); + + if (_doSchur) { + // the following two are only used in schur + assert(_sizePoses > 0 && "allocating with wrong size"); + _coefficients = new double [s]; + _bschur = new double[_sizePoses]; + } + + _Hpp=new PoseHessianType(blockPoseIndices, blockPoseIndices, numPoseBlocks, numPoseBlocks); + if (_doSchur) { + _Hschur=new PoseHessianType(blockPoseIndices, blockPoseIndices, numPoseBlocks, numPoseBlocks); + _Hll=new LandmarkHessianType(blockLandmarkIndices, blockLandmarkIndices, numLandmarkBlocks, numLandmarkBlocks); + _DInvSchur = new SparseBlockMatrixDiagonal(_Hll->colBlockIndices()); + _Hpl=new PoseLandmarkHessianType(blockPoseIndices, blockLandmarkIndices, numPoseBlocks, numLandmarkBlocks); + _HplCCS = new SparseBlockMatrixCCS(_Hpl->rowBlockIndices(), _Hpl->colBlockIndices()); + _HschurTransposedCCS = new SparseBlockMatrixCCS(_Hschur->colBlockIndices(), _Hschur->rowBlockIndices()); +#ifdef G2O_OPENMP + _coefficientsMutex.resize(numPoseBlocks); +#endif + } +} + +template +void BlockSolver::deallocate() +{ + if (_Hpp){ + delete _Hpp; + _Hpp=0; + } + if (_Hll){ + delete _Hll; + _Hll=0; + } + if (_Hpl){ + delete _Hpl; + _Hpl = 0; + } + if (_Hschur){ + delete _Hschur; + _Hschur=0; + } + if (_DInvSchur){ + delete _DInvSchur; + _DInvSchur=0; + } + if (_coefficients) { + delete[] _coefficients; + _coefficients = 0; + } + if (_bschur) { + delete[] _bschur; + _bschur = 0; + } + if (_HplCCS) { + delete _HplCCS; + _HplCCS = 0; + } + if (_HschurTransposedCCS) { + delete _HschurTransposedCCS; + _HschurTransposedCCS = 0; + } +} + +template +BlockSolver::~BlockSolver() +{ + delete _linearSolver; + deallocate(); +} + +template +bool BlockSolver::buildStructure(bool zeroBlocks) +{ + assert(_optimizer); + + size_t sparseDim = 0; + _numPoses=0; + _numLandmarks=0; + _sizePoses=0; + _sizeLandmarks=0; + int* blockPoseIndices = new int[_optimizer->indexMapping().size()]; + int* blockLandmarkIndices = new int[_optimizer->indexMapping().size()]; + + for (size_t i = 0; i < _optimizer->indexMapping().size(); ++i) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[i]; + int dim = v->dimension(); + if (! v->marginalized()){ + v->setColInHessian(_sizePoses); + _sizePoses+=dim; + blockPoseIndices[_numPoses]=_sizePoses; + ++_numPoses; + } else { + v->setColInHessian(_sizeLandmarks); + _sizeLandmarks+=dim; + blockLandmarkIndices[_numLandmarks]=_sizeLandmarks; + ++_numLandmarks; + } + sparseDim += dim; + } + resize(blockPoseIndices, _numPoses, blockLandmarkIndices, _numLandmarks, sparseDim); + delete[] blockLandmarkIndices; + delete[] blockPoseIndices; + + // allocate the diagonal on Hpp and Hll + int poseIdx = 0; + int landmarkIdx = 0; + for (size_t i = 0; i < _optimizer->indexMapping().size(); ++i) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[i]; + if (! v->marginalized()){ + //assert(poseIdx == v->hessianIndex()); + PoseMatrixType* m = _Hpp->block(poseIdx, poseIdx, true); + if (zeroBlocks) + m->setZero(); + v->mapHessianMemory(m->data()); + ++poseIdx; + } else { + LandmarkMatrixType* m = _Hll->block(landmarkIdx, landmarkIdx, true); + if (zeroBlocks) + m->setZero(); + v->mapHessianMemory(m->data()); + ++landmarkIdx; + } + } + assert(poseIdx == _numPoses && landmarkIdx == _numLandmarks); + + // temporary structures for building the pattern of the Schur complement + SparseBlockMatrixHashMap* schurMatrixLookup = 0; + if (_doSchur) { + schurMatrixLookup = new SparseBlockMatrixHashMap(_Hschur->rowBlockIndices(), _Hschur->colBlockIndices()); + schurMatrixLookup->blockCols().resize(_Hschur->blockCols().size()); + } + + // here we assume that the landmark indices start after the pose ones + // create the structure in Hpp, Hll and in Hpl + for (SparseOptimizer::EdgeContainer::const_iterator it=_optimizer->activeEdges().begin(); it!=_optimizer->activeEdges().end(); ++it){ + OptimizableGraph::Edge* e = *it; + + for (size_t viIdx = 0; viIdx < e->vertices().size(); ++viIdx) { + OptimizableGraph::Vertex* v1 = (OptimizableGraph::Vertex*) e->vertex(viIdx); + int ind1 = v1->hessianIndex(); + if (ind1 == -1) + continue; + int indexV1Bak = ind1; + for (size_t vjIdx = viIdx + 1; vjIdx < e->vertices().size(); ++vjIdx) { + OptimizableGraph::Vertex* v2 = (OptimizableGraph::Vertex*) e->vertex(vjIdx); + int ind2 = v2->hessianIndex(); + if (ind2 == -1) + continue; + ind1 = indexV1Bak; + bool transposedBlock = ind1 > ind2; + if (transposedBlock){ // make sure, we allocate the upper triangle block + swap(ind1, ind2); + } + if (! v1->marginalized() && !v2->marginalized()){ + PoseMatrixType* m = _Hpp->block(ind1, ind2, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, transposedBlock); + if (_Hschur) {// assume this is only needed in case we solve with the schur complement + schurMatrixLookup->addBlock(ind1, ind2); + } + } else if (v1->marginalized() && v2->marginalized()){ + // RAINER hmm.... should we ever reach this here???? + LandmarkMatrixType* m = _Hll->block(ind1-_numPoses, ind2-_numPoses, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, false); + } else { + if (v1->marginalized()){ + PoseLandmarkMatrixType* m = _Hpl->block(v2->hessianIndex(),v1->hessianIndex()-_numPoses, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, true); // transpose the block before writing to it + } else { + PoseLandmarkMatrixType* m = _Hpl->block(v1->hessianIndex(),v2->hessianIndex()-_numPoses, true); + if (zeroBlocks) + m->setZero(); + e->mapHessianMemory(m->data(), viIdx, vjIdx, false); // directly the block + } + } + } + } + } + + if (! _doSchur) + return true; + + _DInvSchur->diagonal().resize(landmarkIdx); + _Hpl->fillSparseBlockMatrixCCS(*_HplCCS); + + for (size_t i = 0; i < _optimizer->indexMapping().size(); ++i) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[i]; + if (v->marginalized()){ + const HyperGraph::EdgeSet& vedges=v->edges(); + for (HyperGraph::EdgeSet::const_iterator it1=vedges.begin(); it1!=vedges.end(); ++it1){ + for (size_t i=0; i<(*it1)->vertices().size(); ++i) + { + OptimizableGraph::Vertex* v1= (OptimizableGraph::Vertex*) (*it1)->vertex(i); + if (v1->hessianIndex()==-1 || v1==v) + continue; + for (HyperGraph::EdgeSet::const_iterator it2=vedges.begin(); it2!=vedges.end(); ++it2){ + for (size_t j=0; j<(*it2)->vertices().size(); ++j) + { + OptimizableGraph::Vertex* v2= (OptimizableGraph::Vertex*) (*it2)->vertex(j); + if (v2->hessianIndex()==-1 || v2==v) + continue; + int i1=v1->hessianIndex(); + int i2=v2->hessianIndex(); + if (i1<=i2) { + schurMatrixLookup->addBlock(i1, i2); + } + } + } + } + } + } + } + + _Hschur->takePatternFromHash(*schurMatrixLookup); + delete schurMatrixLookup; + _Hschur->fillSparseBlockMatrixCCSTransposed(*_HschurTransposedCCS); + + return true; +} + +template +bool BlockSolver::updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) +{ + for (std::vector::const_iterator vit = vset.begin(); vit != vset.end(); ++vit) { + OptimizableGraph::Vertex* v = static_cast(*vit); + int dim = v->dimension(); + if (! v->marginalized()){ + v->setColInHessian(_sizePoses); + _sizePoses+=dim; + _Hpp->rowBlockIndices().push_back(_sizePoses); + _Hpp->colBlockIndices().push_back(_sizePoses); + _Hpp->blockCols().push_back(typename SparseBlockMatrix::IntBlockMap()); + ++_numPoses; + int ind = v->hessianIndex(); + PoseMatrixType* m = _Hpp->block(ind, ind, true); + v->mapHessianMemory(m->data()); + } else { + std::cerr << "updateStructure(): Schur not supported" << std::endl; + abort(); + } + } + resizeVector(_sizePoses + _sizeLandmarks); + + for (HyperGraph::EdgeSet::const_iterator it = edges.begin(); it != edges.end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + + for (size_t viIdx = 0; viIdx < e->vertices().size(); ++viIdx) { + OptimizableGraph::Vertex* v1 = (OptimizableGraph::Vertex*) e->vertex(viIdx); + int ind1 = v1->hessianIndex(); + int indexV1Bak = ind1; + if (ind1 == -1) + continue; + for (size_t vjIdx = viIdx + 1; vjIdx < e->vertices().size(); ++vjIdx) { + OptimizableGraph::Vertex* v2 = (OptimizableGraph::Vertex*) e->vertex(vjIdx); + int ind2 = v2->hessianIndex(); + if (ind2 == -1) + continue; + ind1 = indexV1Bak; + bool transposedBlock = ind1 > ind2; + if (transposedBlock) // make sure, we allocate the upper triangular block + swap(ind1, ind2); + + if (! v1->marginalized() && !v2->marginalized()) { + PoseMatrixType* m = _Hpp->block(ind1, ind2, true); + e->mapHessianMemory(m->data(), viIdx, vjIdx, transposedBlock); + } else { + std::cerr << __PRETTY_FUNCTION__ << ": not supported" << std::endl; + } + } + } + + } + + return true; +} + +template +bool BlockSolver::solve(){ + //cerr << __PRETTY_FUNCTION__ << endl; + if (! _doSchur){ + double t=get_monotonic_time(); + bool ok = _linearSolver->solve(*_Hpp, _x, _b); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeLinearSolver = get_monotonic_time() - t; + globalStats->hessianDimension = globalStats->hessianPoseDimension = _Hpp->cols(); + } + return ok; + } + + // schur thing + + // backup the coefficient matrix + double t=get_monotonic_time(); + + // _Hschur = _Hpp, but keeping the pattern of _Hschur + _Hschur->clear(); + _Hpp->add(_Hschur); + + //_DInvSchur->clear(); + memset (_coefficients, 0, _sizePoses*sizeof(double)); +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int landmarkIndex = 0; landmarkIndex < static_cast(_Hll->blockCols().size()); ++landmarkIndex) { + const typename SparseBlockMatrix::IntBlockMap& marginalizeColumn = _Hll->blockCols()[landmarkIndex]; + assert(marginalizeColumn.size() == 1 && "more than one block in _Hll column"); + + // calculate inverse block for the landmark + const LandmarkMatrixType * D = marginalizeColumn.begin()->second; + assert (D && D->rows()==D->cols() && "Error in landmark matrix"); + LandmarkMatrixType& Dinv = _DInvSchur->diagonal()[landmarkIndex]; + Dinv = D->inverse(); + + LandmarkVectorType db(D->rows()); + for (int j=0; jrows(); ++j) { + db[j]=_b[_Hll->rowBaseOfBlock(landmarkIndex) + _sizePoses + j]; + } + db=Dinv*db; + + assert((size_t)landmarkIndex < _HplCCS->blockCols().size() && "Index out of bounds"); + const typename SparseBlockMatrixCCS::SparseColumn& landmarkColumn = _HplCCS->blockCols()[landmarkIndex]; + + for (typename SparseBlockMatrixCCS::SparseColumn::const_iterator it_outer = landmarkColumn.begin(); + it_outer != landmarkColumn.end(); ++it_outer) { + int i1 = it_outer->row; + + const PoseLandmarkMatrixType* Bi = it_outer->block; + assert(Bi); + + PoseLandmarkMatrixType BDinv = (*Bi)*(Dinv); + assert(_HplCCS->rowBaseOfBlock(i1) < _sizePoses && "Index out of bounds"); + typename PoseVectorType::MapType Bb(&_coefficients[_HplCCS->rowBaseOfBlock(i1)], Bi->rows()); +# ifdef G2O_OPENMP + ScopedOpenMPMutex mutexLock(&_coefficientsMutex[i1]); +# endif + Bb.noalias() += (*Bi)*db; + + assert(i1 >= 0 && i1 < static_cast(_HschurTransposedCCS->blockCols().size()) && "Index out of bounds"); + typename SparseBlockMatrixCCS::SparseColumn::iterator targetColumnIt = _HschurTransposedCCS->blockCols()[i1].begin(); + + typename SparseBlockMatrixCCS::RowBlock aux(i1, 0); + typename SparseBlockMatrixCCS::SparseColumn::const_iterator it_inner = lower_bound(landmarkColumn.begin(), landmarkColumn.end(), aux); + for (; it_inner != landmarkColumn.end(); ++it_inner) { + int i2 = it_inner->row; + const PoseLandmarkMatrixType* Bj = it_inner->block; + assert(Bj); + while (targetColumnIt->row < i2 /*&& targetColumnIt != _HschurTransposedCCS->blockCols()[i1].end()*/) + ++targetColumnIt; + assert(targetColumnIt != _HschurTransposedCCS->blockCols()[i1].end() && targetColumnIt->row == i2 && "invalid iterator, something wrong with the matrix structure"); + PoseMatrixType* Hi1i2 = targetColumnIt->block;//_Hschur->block(i1,i2); + assert(Hi1i2); + (*Hi1i2).noalias() -= BDinv*Bj->transpose(); + } + } + } + //cerr << "Solve [marginalize] = " << get_monotonic_time()-t << endl; + + // _bschur = _b for calling solver, and not touching _b + memcpy(_bschur, _b, _sizePoses * sizeof(double)); + for (int i=0; i<_sizePoses; ++i){ + _bschur[i]-=_coefficients[i]; + } + + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats){ + globalStats->timeSchurComplement = get_monotonic_time() - t; + } + + t=get_monotonic_time(); + bool solvedPoses = _linearSolver->solve(*_Hschur, _x, _bschur); + if (globalStats) { + globalStats->timeLinearSolver = get_monotonic_time() - t; + globalStats->hessianPoseDimension = _Hpp->cols(); + globalStats->hessianLandmarkDimension = _Hll->cols(); + globalStats->hessianDimension = globalStats->hessianPoseDimension + globalStats->hessianLandmarkDimension; + } + //cerr << "Solve [decompose and solve] = " << get_monotonic_time()-t << endl; + + if (! solvedPoses) + return false; + + // _x contains the solution for the poses, now applying it to the landmarks to get the new part of the + // solution; + double* xp = _x; + double* cp = _coefficients; + + double* xl=_x+_sizePoses; + double* cl=_coefficients + _sizePoses; + double* bl=_b+_sizePoses; + + // cp = -xp + for (int i=0; i<_sizePoses; ++i) + cp[i]=-xp[i]; + + // cl = bl + memcpy(cl,bl,_sizeLandmarks*sizeof(double)); + + // cl = bl - Bt * xp + //Bt->multiply(cl, cp); + _HplCCS->rightMultiply(cl, cp); + + // xl = Dinv * cl + memset(xl,0, _sizeLandmarks*sizeof(double)); + _DInvSchur->multiply(xl,cl); + //_DInvSchur->rightMultiply(xl,cl); + //cerr << "Solve [landmark delta] = " << get_monotonic_time()-t << endl; + + return true; +} + + +template +bool BlockSolver::computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) +{ + double t = get_monotonic_time(); + bool ok = _linearSolver->solvePattern(spinv, blockIndices, *_Hpp); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeMarginals = get_monotonic_time() - t; + } + return ok; +} + +template +bool BlockSolver::buildSystem() +{ + // clear b vector +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_optimizer->indexMapping().size() > 1000) +# endif + for (int i = 0; i < static_cast(_optimizer->indexMapping().size()); ++i) { + OptimizableGraph::Vertex* v=_optimizer->indexMapping()[i]; + assert(v); + v->clearQuadraticForm(); + } + _Hpp->clear(); + if (_doSchur) { + _Hll->clear(); + _Hpl->clear(); + } + + // resetting the terms for the pairwise constraints + // built up the current system by storing the Hessian blocks in the edges and vertices +# ifndef G2O_OPENMP + // no threading, we do not need to copy the workspace + JacobianWorkspace& jacobianWorkspace = _optimizer->jacobianWorkspace(); +# else + // if running with threads need to produce copies of the workspace for each thread + JacobianWorkspace jacobianWorkspace = _optimizer->jacobianWorkspace(); +# pragma omp parallel for default (shared) firstprivate(jacobianWorkspace) if (_optimizer->activeEdges().size() > 100) +# endif + for (int k = 0; k < static_cast(_optimizer->activeEdges().size()); ++k) { + OptimizableGraph::Edge* e = _optimizer->activeEdges()[k]; + e->linearizeOplus(jacobianWorkspace); // jacobian of the nodes' oplus (manifold) + e->constructQuadraticForm(); +# ifndef NDEBUG + for (size_t i = 0; i < e->vertices().size(); ++i) { + const OptimizableGraph::Vertex* v = static_cast(e->vertex(i)); + if (! v->fixed()) { + bool hasANan = arrayHasNaN(jacobianWorkspace.workspaceForVertex(i), e->dimension() * v->dimension()); + if (hasANan) { + cerr << "buildSystem(): NaN within Jacobian for edge " << e << " for vertex " << i << endl; + break; + } + } + } +# endif + } + + // flush the current system in a sparse block matrix +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_optimizer->indexMapping().size() > 1000) +# endif + for (int i = 0; i < static_cast(_optimizer->indexMapping().size()); ++i) { + OptimizableGraph::Vertex* v=_optimizer->indexMapping()[i]; + int iBase = v->colInHessian(); + if (v->marginalized()) + iBase+=_sizePoses; + v->copyB(_b+iBase); + } + + return 0; +} + + +template +bool BlockSolver::setLambda(double lambda, bool backup) +{ + if (backup) { + _diagonalBackupPose.resize(_numPoses); + _diagonalBackupLandmark.resize(_numLandmarks); + } +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_numPoses > 100) +# endif + for (int i = 0; i < _numPoses; ++i) { + PoseMatrixType *b=_Hpp->block(i,i); + if (backup) + _diagonalBackupPose[i] = b->diagonal(); + b->diagonal().array() += lambda; + } +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_numLandmarks > 100) +# endif + for (int i = 0; i < _numLandmarks; ++i) { + LandmarkMatrixType *b=_Hll->block(i,i); + if (backup) + _diagonalBackupLandmark[i] = b->diagonal(); + b->diagonal().array() += lambda; + } + return true; +} + +template +void BlockSolver::restoreDiagonal() +{ + assert((int) _diagonalBackupPose.size() == _numPoses && "Mismatch in dimensions"); + assert((int) _diagonalBackupLandmark.size() == _numLandmarks && "Mismatch in dimensions"); + for (int i = 0; i < _numPoses; ++i) { + PoseMatrixType *b=_Hpp->block(i,i); + b->diagonal() = _diagonalBackupPose[i]; + } + for (int i = 0; i < _numLandmarks; ++i) { + LandmarkMatrixType *b=_Hll->block(i,i); + b->diagonal() = _diagonalBackupLandmark[i]; + } +} + +template +bool BlockSolver::init(SparseOptimizer* optimizer, bool online) +{ + _optimizer = optimizer; + if (! online) { + if (_Hpp) + _Hpp->clear(); + if (_Hpl) + _Hpl->clear(); + if (_Hll) + _Hll->clear(); + } + _linearSolver->init(); + return true; +} + +template +void BlockSolver::setWriteDebug(bool writeDebug) +{ + _linearSolver->setWriteDebug(writeDebug); +} + +template +bool BlockSolver::saveHessian(const std::string& fileName) const +{ + return _Hpp->writeOctave(fileName.c_str(), true); +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/cache.cpp b/Thirdparty/g2o/g2o/core/cache.cpp new file mode 100644 index 0000000000..89f9c240d7 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/cache.cpp @@ -0,0 +1,183 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 G. Grisetti, R. Kuemmerle, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "cache.h" +#include "optimizable_graph.h" +#include "factory.h" + +#include + +namespace g2o { + using namespace std; + + Cache::CacheKey::CacheKey() : + _type(), _parameters() + { + } + + Cache::CacheKey::CacheKey(const std::string& type_, const ParameterVector& parameters_) : + _type(type_), _parameters(parameters_) + { + } + + Cache::Cache(CacheContainer* container_, const ParameterVector& parameters_) : + _updateNeeded(true), _parameters(parameters_), _container(container_) + { + } + + bool Cache::CacheKey::operator<(const Cache::CacheKey& c) const{ + if (_type < c._type) + return true; + return std::lexicographical_compare (_parameters.begin( ), _parameters.end( ), + c._parameters.begin( ), c._parameters.end( ) ); + } + + + OptimizableGraph::Vertex* Cache::vertex() { + if (container() ) + return container()->vertex(); + return 0; + } + + OptimizableGraph* Cache::graph() { + if (container()) + return container()->graph(); + return 0; + } + + CacheContainer* Cache::container() { + return _container; + } + + ParameterVector& Cache::parameters() { + return _parameters; + } + + Cache::CacheKey Cache::key() const { + Factory* factory=Factory::instance(); + return CacheKey(factory->tag(this), _parameters); + }; + + + void Cache::update(){ + if (! _updateNeeded) + return; + for(std::vector::iterator it=_parentCaches.begin(); it!=_parentCaches.end(); it++){ + (*it)->update(); + } + updateImpl(); + _updateNeeded=false; + } + + Cache* Cache::installDependency(const std::string& type_, const std::vector& parameterIndices){ + ParameterVector pv(parameterIndices.size()); + for (size_t i=0; i=(int)_parameters.size()) + return 0; + pv[i]=_parameters[ parameterIndices[i] ]; + } + CacheKey k(type_, pv); + if (!container()) + return 0; + Cache* c=container()->findCache(k); + if (!c) { + c = container()->createCache(k); + } + if (c) + _parentCaches.push_back(c); + return c; + } + + bool Cache::resolveDependancies(){ + return true; + } + + CacheContainer::CacheContainer(OptimizableGraph::Vertex* vertex_) { + _vertex = vertex_; + } + + Cache* CacheContainer::findCache(const Cache::CacheKey& key) { + iterator it=find(key); + if (it==end()) + return 0; + return it->second; + } + + Cache* CacheContainer::createCache(const Cache::CacheKey& key){ + Factory* f = Factory::instance(); + HyperGraph::HyperGraphElement* e = f->construct(key.type()); + if (!e) { + cerr << __PRETTY_FUNCTION__ << endl; + cerr << "fatal error in creating cache of type " << key.type() << endl; + return 0; + } + Cache* c = dynamic_cast(e); + if (! c){ + cerr << __PRETTY_FUNCTION__ << endl; + cerr << "fatal error in creating cache of type " << key.type() << endl; + return 0; + } + c->_container = this; + c->_parameters = key._parameters; + if (c->resolveDependancies()){ + insert(make_pair(key,c)); + c->update(); + return c; + } + return 0; + } + + OptimizableGraph::Vertex* CacheContainer::vertex() { + return _vertex; + } + + OptimizableGraph* CacheContainer::graph(){ + if (_vertex) + return _vertex->graph(); + return 0; + } + + void CacheContainer::update() { + for (iterator it=begin(); it!=end(); it++){ + (it->second)->update(); + } + _updateNeeded=false; + } + + void CacheContainer::setUpdateNeeded(bool needUpdate) { + _updateNeeded=needUpdate; + for (iterator it=begin(); it!=end(); ++it){ + (it->second)->_updateNeeded = needUpdate; + } + } + + CacheContainer::~CacheContainer(){ + for (iterator it=begin(); it!=end(); ++it){ + delete (it->second); + } + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/cache.h b/Thirdparty/g2o/g2o/core/cache.h new file mode 100644 index 0000000000..c5b00a491e --- /dev/null +++ b/Thirdparty/g2o/g2o/core/cache.h @@ -0,0 +1,140 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_CACHE_HH_ +#define G2O_CACHE_HH_ + +#include + +#include "optimizable_graph.h" + +namespace g2o { + + class CacheContainer; + + class Cache: public HyperGraph::HyperGraphElement + { + public: + friend class CacheContainer; + class CacheKey + { + public: + friend class CacheContainer; + CacheKey(); + CacheKey(const std::string& type_, const ParameterVector& parameters_); + + bool operator<(const CacheKey& c) const; + + const std::string& type() const { return _type;} + const ParameterVector& parameters() const { return _parameters;} + + protected: + std::string _type; + ParameterVector _parameters; + }; + + Cache(CacheContainer* container_ = 0, const ParameterVector& parameters_ = ParameterVector()); + + CacheKey key() const; + + OptimizableGraph::Vertex* vertex(); + OptimizableGraph* graph(); + CacheContainer* container(); + ParameterVector& parameters(); + + void update(); + + virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_CACHE;} + + protected: + //! redefine this to do the update + virtual void updateImpl() = 0; + + /** + * this function installs and satisfies a cache + * @param type_: the typename of the dependency + * @param parameterIndices: a vector containing the indices if the parameters + * in _parameters that will be used to assemble the Key of the cache being created + * For example if I have a cache of type C2, having parameters "A, B, and C", + * and it depends on a cache of type C1 that depends on the parameters A and C, + * the parameterIndices should contain "0, 2", since they are the positions in the + * parameter vector of C2 of the parameters needed to construct C1. + * @returns the newly created cache + */ + Cache* installDependency(const std::string& type_, const std::vector& parameterIndices); + + /** + * Function to be called from a cache that has dependencies. It just invokes a + * sequence of installDependency(). + * Although the caches returned are stored in the _parentCache vector, + * it is better that you redefine your own cache member variables, for better readability + */ + virtual bool resolveDependancies(); + + bool _updateNeeded; + ParameterVector _parameters; + std::vector _parentCaches; + CacheContainer* _container; + }; + + class CacheContainer: public std::map + { + public: + CacheContainer(OptimizableGraph::Vertex* vertex_); + virtual ~CacheContainer(); + OptimizableGraph::Vertex* vertex(); + OptimizableGraph* graph(); + Cache* findCache(const Cache::CacheKey& key); + Cache* createCache(const Cache::CacheKey& key); + void setUpdateNeeded(bool needUpdate=true); + void update(); + protected: + OptimizableGraph::Vertex* _vertex; + bool _updateNeeded; + }; + + + template + void OptimizableGraph::Edge::resolveCache(CacheType*& cache, + OptimizableGraph::Vertex* v, + const std::string& type_, + const ParameterVector& parameters_) + { + cache = 0; + CacheContainer* container= v->cacheContainer(); + Cache::CacheKey key(type_, parameters_); + Cache* c = container->findCache(key); + if (!c) { + c = container->createCache(key); + } + if (c) { + cache = dynamic_cast(c); + } + } + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/creators.h b/Thirdparty/g2o/g2o/core/creators.h new file mode 100644 index 0000000000..9ca9967cb3 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/creators.h @@ -0,0 +1,75 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_CREATORS_H +#define G2O_CREATORS_H + +#include "hyper_graph.h" + +#include +#include + +namespace g2o +{ + + /** + * \brief Abstract interface for allocating HyperGraphElement + */ + class AbstractHyperGraphElementCreator + { + public: + /** + * create a hyper graph element. Has to implemented in derived class. + */ + virtual HyperGraph::HyperGraphElement* construct() = 0; + /** + * name of the class to be created. Has to implemented in derived class. + */ + virtual const std::string& name() const = 0; + + virtual ~AbstractHyperGraphElementCreator() { } + }; + + /** + * \brief templatized creator class which creates graph elements + */ + template + class HyperGraphElementCreator : public AbstractHyperGraphElementCreator + { + public: + HyperGraphElementCreator() : _name(typeid(T).name()) {} +#if defined (WINDOWS) && defined(__GNUC__) // force stack alignment on Windows with GCC + __attribute__((force_align_arg_pointer)) +#endif + HyperGraph::HyperGraphElement* construct() { return new T;} + virtual const std::string& name() const { return _name;} + protected: + std::string _name; + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/eigen_types.h b/Thirdparty/g2o/g2o/core/eigen_types.h new file mode 100644 index 0000000000..f2c6856562 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/eigen_types.h @@ -0,0 +1,73 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_EIGEN_TYPES_H +#define G2O_EIGEN_TYPES_H + +#include +#include + +namespace g2o { + + typedef Eigen::Matrix Vector2I; + typedef Eigen::Matrix Vector3I; + typedef Eigen::Matrix Vector4I; + typedef Eigen::Matrix VectorXI; + + typedef Eigen::Matrix Vector2F; + typedef Eigen::Matrix Vector3F; + typedef Eigen::Matrix Vector4F; + typedef Eigen::Matrix VectorXF; + + typedef Eigen::Matrix Vector2D; + typedef Eigen::Matrix Vector3D; + typedef Eigen::Matrix Vector4D; + typedef Eigen::Matrix VectorXD; + + typedef Eigen::Matrix Matrix2I; + typedef Eigen::Matrix Matrix3I; + typedef Eigen::Matrix Matrix4I; + typedef Eigen::Matrix MatrixXI; + + typedef Eigen::Matrix Matrix2F; + typedef Eigen::Matrix Matrix3F; + typedef Eigen::Matrix Matrix4F; + typedef Eigen::Matrix MatrixXF; + + typedef Eigen::Matrix Matrix2D; + typedef Eigen::Matrix Matrix3D; + typedef Eigen::Matrix Matrix4D; + typedef Eigen::Matrix MatrixXD; + + typedef Eigen::Transform Isometry2D; + typedef Eigen::Transform Isometry3D; + + typedef Eigen::Transform Affine2D; + typedef Eigen::Transform Affine3D; + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/estimate_propagator.cpp b/Thirdparty/g2o/g2o/core/estimate_propagator.cpp new file mode 100644 index 0000000000..010dac1cf6 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/estimate_propagator.cpp @@ -0,0 +1,267 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "estimate_propagator.h" + +#include +#include +#include +#include +#include +#include + +//#define DEBUG_ESTIMATE_PROPAGATOR + +using namespace std; + +namespace g2o { + +# ifdef DEBUG_ESTIMATE_PROPAGATOR + struct FrontierLevelCmp { + bool operator()(EstimatePropagator::AdjacencyMapEntry* e1, EstimatePropagator::AdjacencyMapEntry* e2) const + { + return e1->frontierLevel() < e2->frontierLevel(); + } + }; +# endif + + EstimatePropagator::AdjacencyMapEntry::AdjacencyMapEntry() + { + reset(); + } + + void EstimatePropagator::AdjacencyMapEntry::reset() + { + _child = 0; + _parent.clear(); + _edge = 0; + _distance = numeric_limits::max(); + _frontierLevel = -1; + inQueue = false; + } + + EstimatePropagator::EstimatePropagator(OptimizableGraph* g): _graph(g) + { + for (OptimizableGraph::VertexIDMap::const_iterator it=_graph->vertices().begin(); it!=_graph->vertices().end(); ++it){ + AdjacencyMapEntry entry; + entry._child = static_cast(it->second); + _adjacencyMap.insert(make_pair(entry.child(), entry)); + } + } + + void EstimatePropagator::reset() + { + for (OptimizableGraph::VertexSet::iterator it=_visited.begin(); it!=_visited.end(); ++it){ + OptimizableGraph::Vertex* v = static_cast(*it); + AdjacencyMap::iterator at = _adjacencyMap.find(v); + assert(at != _adjacencyMap.end()); + at->second.reset(); + } + _visited.clear(); + } + + void EstimatePropagator::propagate(OptimizableGraph::Vertex* v, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action, + double maxDistance, + double maxEdgeCost) + { + OptimizableGraph::VertexSet vset; + vset.insert(v); + propagate(vset, cost, action, maxDistance, maxEdgeCost); + } + + void EstimatePropagator::propagate(OptimizableGraph::VertexSet& vset, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action, + double maxDistance, + double maxEdgeCost) + { + reset(); + + PriorityQueue frontier; + for (OptimizableGraph::VertexSet::iterator vit=vset.begin(); vit!=vset.end(); ++vit){ + OptimizableGraph::Vertex* v = static_cast(*vit); + AdjacencyMap::iterator it = _adjacencyMap.find(v); + assert(it != _adjacencyMap.end()); + it->second._distance = 0.; + it->second._parent.clear(); + it->second._frontierLevel = 0; + frontier.push(&it->second); + } + + while(! frontier.empty()){ + AdjacencyMapEntry* entry = frontier.pop(); + OptimizableGraph::Vertex* u = entry->child(); + double uDistance = entry->distance(); + //cerr << "uDistance " << uDistance << endl; + + // initialize the vertex + if (entry->_frontierLevel > 0) { + action(entry->edge(), entry->parent(), u); + } + + /* std::pair< OptimizableGraph::VertexSet::iterator, bool> insertResult = */ _visited.insert(u); + OptimizableGraph::EdgeSet::iterator et = u->edges().begin(); + while (et != u->edges().end()){ + OptimizableGraph::Edge* edge = static_cast(*et); + ++et; + + int maxFrontier = -1; + OptimizableGraph::VertexSet initializedVertices; + for (size_t i = 0; i < edge->vertices().size(); ++i) { + OptimizableGraph::Vertex* z = static_cast(edge->vertex(i)); + AdjacencyMap::iterator ot = _adjacencyMap.find(z); + if (ot->second._distance != numeric_limits::max()) { + initializedVertices.insert(z); + maxFrontier = (max)(maxFrontier, ot->second._frontierLevel); + } + } + assert(maxFrontier >= 0); + + for (size_t i = 0; i < edge->vertices().size(); ++i) { + OptimizableGraph::Vertex* z = static_cast(edge->vertex(i)); + if (z == u) + continue; + + size_t wasInitialized = initializedVertices.erase(z); + + double edgeDistance = cost(edge, initializedVertices, z); + if (edgeDistance > 0. && edgeDistance != std::numeric_limits::max() && edgeDistance < maxEdgeCost) { + double zDistance = uDistance + edgeDistance; + //cerr << z->id() << " " << zDistance << endl; + + AdjacencyMap::iterator ot = _adjacencyMap.find(z); + assert(ot!=_adjacencyMap.end()); + + if (zDistance < ot->second.distance() && zDistance < maxDistance){ + //if (ot->second.inQueue) + //cerr << "Updating" << endl; + ot->second._distance = zDistance; + ot->second._parent = initializedVertices; + ot->second._edge = edge; + ot->second._frontierLevel = maxFrontier + 1; + frontier.push(&ot->second); + } + } + + if (wasInitialized > 0) + initializedVertices.insert(z); + + } + } + } + + // writing debug information like cost for reaching each vertex and the parent used to initialize +#ifdef DEBUG_ESTIMATE_PROPAGATOR + cerr << "Writing cost.dat" << endl; + ofstream costStream("cost.dat"); + for (AdjacencyMap::const_iterator it = _adjacencyMap.begin(); it != _adjacencyMap.end(); ++it) { + HyperGraph::Vertex* u = it->second.child(); + costStream << "vertex " << u->id() << " cost " << it->second._distance << endl; + } + cerr << "Writing init.dat" << endl; + ofstream initStream("init.dat"); + vector frontierLevels; + for (AdjacencyMap::iterator it = _adjacencyMap.begin(); it != _adjacencyMap.end(); ++it) { + if (it->second._frontierLevel > 0) + frontierLevels.push_back(&it->second); + } + sort(frontierLevels.begin(), frontierLevels.end(), FrontierLevelCmp()); + for (vector::const_iterator it = frontierLevels.begin(); it != frontierLevels.end(); ++it) { + AdjacencyMapEntry* entry = *it; + OptimizableGraph::Vertex* to = entry->child(); + + initStream << "calling init level = " << entry->_frontierLevel << "\t ("; + for (OptimizableGraph::VertexSet::iterator pit = entry->parent().begin(); pit != entry->parent().end(); ++pit) { + initStream << " " << (*pit)->id(); + } + initStream << " ) -> " << to->id() << endl; + } +#endif + + } + + void EstimatePropagator::PriorityQueue::push(AdjacencyMapEntry* entry) + { + assert(entry != NULL); + if (entry->inQueue) { + assert(entry->queueIt->second == entry); + erase(entry->queueIt); + } + + entry->queueIt = insert(std::make_pair(entry->distance(), entry)); + assert(entry->queueIt != end()); + entry->inQueue = true; + } + + EstimatePropagator::AdjacencyMapEntry* EstimatePropagator::PriorityQueue::pop() + { + assert(!empty()); + iterator it = begin(); + AdjacencyMapEntry* entry = it->second; + erase(it); + + assert(entry != NULL); + entry->queueIt = end(); + entry->inQueue = false; + return entry; + } + + EstimatePropagatorCost::EstimatePropagatorCost (SparseOptimizer* graph) : + _graph(graph) + { + } + + double EstimatePropagatorCost::operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to_) const + { + OptimizableGraph::Edge* e = dynamic_cast(edge); + OptimizableGraph::Vertex* to = dynamic_cast(to_); + SparseOptimizer::EdgeContainer::const_iterator it = _graph->findActiveEdge(e); + if (it == _graph->activeEdges().end()) // it has to be an active edge + return std::numeric_limits::max(); + return e->initialEstimatePossible(from, to); + } + + EstimatePropagatorCostOdometry::EstimatePropagatorCostOdometry(SparseOptimizer* graph) : + EstimatePropagatorCost(graph) + { + } + + double EstimatePropagatorCostOdometry::operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from_, OptimizableGraph::Vertex* to_) const + { + OptimizableGraph::Edge* e = dynamic_cast(edge); + OptimizableGraph::Vertex* from = dynamic_cast(*from_.begin()); + OptimizableGraph::Vertex* to = dynamic_cast(to_); + if (std::abs(from->id() - to->id()) != 1) // simple method to identify odometry edges in a pose graph + return std::numeric_limits::max(); + SparseOptimizer::EdgeContainer::const_iterator it = _graph->findActiveEdge(e); + if (it == _graph->activeEdges().end()) // it has to be an active edge + return std::numeric_limits::max(); + return e->initialEstimatePossible(from_, to); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/estimate_propagator.h b/Thirdparty/g2o/g2o/core/estimate_propagator.h new file mode 100644 index 0000000000..6a16d11d3a --- /dev/null +++ b/Thirdparty/g2o/g2o/core/estimate_propagator.h @@ -0,0 +1,175 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_ESTIMATE_PROPAGATOR_H +#define G2O_ESTIMATE_PROPAGATOR_H + +#include "optimizable_graph.h" +#include "sparse_optimizer.h" + +#include +#include +#include + +#ifdef _MSC_VER +#include +#else +#include +#endif + +namespace g2o { + + /** + * \brief cost for traversing along active edges in the optimizer + * + * You may derive an own one, if necessary. The default is to return initialEstimatePossible(from, to) for the edge. + */ + class EstimatePropagatorCost { + public: + EstimatePropagatorCost (SparseOptimizer* graph); + virtual double operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to_) const; + virtual const char* name() const { return "spanning tree";} + protected: + SparseOptimizer* _graph; + }; + + /** + * \brief cost for traversing only odometry edges. + * + * Initialize your graph along odometry edges. An odometry edge is assumed to connect vertices + * whose IDs only differs by one. + */ + class EstimatePropagatorCostOdometry : public EstimatePropagatorCost { + public: + EstimatePropagatorCostOdometry(SparseOptimizer* graph); + virtual double operator()(OptimizableGraph::Edge* edge, const OptimizableGraph::VertexSet& from_, OptimizableGraph::Vertex* to_) const; + virtual const char* name() const { return "odometry";} + }; + + /** + * \brief propagation of an initial guess + */ + class EstimatePropagator { + public: + + /** + * \brief Applying the action for propagating. + * + * You may derive an own one, if necessary. The default is to call initialEstimate(from, to) for the edge. + */ + struct PropagateAction { + virtual void operator()(OptimizableGraph::Edge* e, const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) const + { + if (! to->fixed()) + e->initialEstimate(from, to); + } + }; + + typedef EstimatePropagatorCost PropagateCost; + + class AdjacencyMapEntry; + + /** + * \brief priority queue for AdjacencyMapEntry + */ + class PriorityQueue : public std::multimap { + public: + void push(AdjacencyMapEntry* entry); + AdjacencyMapEntry* pop(); + }; + + /** + * \brief data structure for loopuk during Dijkstra + */ + class AdjacencyMapEntry { + public: + friend class EstimatePropagator; + friend class PriorityQueue; + AdjacencyMapEntry(); + void reset(); + OptimizableGraph::Vertex* child() const {return _child;} + const OptimizableGraph::VertexSet& parent() const {return _parent;} + OptimizableGraph::Edge* edge() const {return _edge;} + double distance() const {return _distance;} + int frontierLevel() const { return _frontierLevel;} + + protected: + OptimizableGraph::Vertex* _child; + OptimizableGraph::VertexSet _parent; + OptimizableGraph::Edge* _edge; + double _distance; + int _frontierLevel; + private: // for PriorityQueue + bool inQueue; + PriorityQueue::iterator queueIt; + }; + + /** + * \brief hash function for a vertex + */ + class VertexIDHashFunction { + public: + size_t operator ()(const OptimizableGraph::Vertex* v) const { return v->id();} + }; + + typedef std::tr1::unordered_map AdjacencyMap; + + public: + EstimatePropagator(OptimizableGraph* g); + OptimizableGraph::VertexSet& visited() {return _visited; } + AdjacencyMap& adjacencyMap() {return _adjacencyMap; } + OptimizableGraph* graph() {return _graph;} + + /** + * propagate an initial guess starting from v. The function computes a spanning tree + * whereas the cost for each edge is determined by calling cost() and the action applied to + * each vertex is action(). + */ + void propagate(OptimizableGraph::Vertex* v, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action = PropagateAction(), + double maxDistance=std::numeric_limits::max(), + double maxEdgeCost=std::numeric_limits::max()); + + /** + * same as above but starting to propagate from a set of vertices instead of just a single one. + */ + void propagate(OptimizableGraph::VertexSet& vset, + const EstimatePropagator::PropagateCost& cost, + const EstimatePropagator::PropagateAction& action = PropagateAction(), + double maxDistance=std::numeric_limits::max(), + double maxEdgeCost=std::numeric_limits::max()); + + protected: + void reset(); + + AdjacencyMap _adjacencyMap; + OptimizableGraph::VertexSet _visited; + OptimizableGraph* _graph; + }; + +} +#endif diff --git a/Thirdparty/g2o/g2o/core/factory.cpp b/Thirdparty/g2o/g2o/core/factory.cpp new file mode 100644 index 0000000000..6263ae2d8f --- /dev/null +++ b/Thirdparty/g2o/g2o/core/factory.cpp @@ -0,0 +1,217 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "factory.h" + +#include "creators.h" +#include "parameter.h" +#include "cache.h" +#include "optimizable_graph.h" +#include "../stuff/color_macros.h" + +#include +#include +#include + +using namespace std; + +namespace g2o { + +Factory* Factory::factoryInstance = 0; + +Factory::Factory() +{ +} + +Factory::~Factory() +{ +# ifdef G2O_DEBUG_FACTORY + cerr << "# Factory destroying " << (void*)this << endl; +# endif + for (CreatorMap::iterator it = _creator.begin(); it != _creator.end(); ++it) { + delete it->second->creator; + } + _creator.clear(); + _tagLookup.clear(); +} + +Factory* Factory::instance() +{ + if (factoryInstance == 0) { + factoryInstance = new Factory; +# ifdef G2O_DEBUG_FACTORY + cerr << "# Factory allocated " << (void*)factoryInstance << endl; +# endif + } + + return factoryInstance; +} + +void Factory::registerType(const std::string& tag, AbstractHyperGraphElementCreator* c) +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + cerr << "FACTORY WARNING: Overwriting Vertex tag " << tag << endl; + assert(0); + } + TagLookup::const_iterator tagIt = _tagLookup.find(c->name()); + if (tagIt != _tagLookup.end()) { + cerr << "FACTORY WARNING: Registering same class for two tags " << c->name() << endl; + assert(0); + } + + CreatorInformation* ci = new CreatorInformation(); + ci->creator = c; + +#ifdef G2O_DEBUG_FACTORY + cerr << "# Factory " << (void*)this << " constructing type " << tag << " "; +#endif + // construct an element once to figure out its type + HyperGraph::HyperGraphElement* element = c->construct(); + ci->elementTypeBit = element->elementType(); + +#ifdef G2O_DEBUG_FACTORY + cerr << "done." << endl; + cerr << "# Factory " << (void*)this << " registering " << tag; + cerr << " " << (void*) c << " "; + switch (element->elementType()) { + case HyperGraph::HGET_VERTEX: + cerr << " -> Vertex"; + break; + case HyperGraph::HGET_EDGE: + cerr << " -> Edge"; + break; + case HyperGraph::HGET_PARAMETER: + cerr << " -> Parameter"; + break; + case HyperGraph::HGET_CACHE: + cerr << " -> Cache"; + break; + case HyperGraph::HGET_DATA: + cerr << " -> Data"; + break; + default: + assert(0 && "Unknown element type occured, fix elementTypes"); + break; + } + cerr << endl; +#endif + + _creator[tag] = ci; + _tagLookup[c->name()] = tag; + delete element; +} + + void Factory::unregisterType(const std::string& tag) + { + // Look for the tag + CreatorMap::iterator tagPosition = _creator.find(tag); + + if (tagPosition != _creator.end()) { + + AbstractHyperGraphElementCreator* c = tagPosition->second->creator; + + // If we found it, remove the creator from the tag lookup map + TagLookup::iterator classPosition = _tagLookup.find(c->name()); + if (classPosition != _tagLookup.end()) + { + _tagLookup.erase(classPosition); + } + _creator.erase(tagPosition); + } + } + +HyperGraph::HyperGraphElement* Factory::construct(const std::string& tag) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + //cerr << "tag " << tag << " -> " << (void*) foundIt->second->creator << " " << foundIt->second->creator->name() << endl; + return foundIt->second->creator->construct(); + } + return 0; +} + +const std::string& Factory::tag(const HyperGraph::HyperGraphElement* e) const +{ + static std::string emptyStr(""); + TagLookup::const_iterator foundIt = _tagLookup.find(typeid(*e).name()); + if (foundIt != _tagLookup.end()) + return foundIt->second; + return emptyStr; +} + +void Factory::fillKnownTypes(std::vector& types) const +{ + types.clear(); + for (CreatorMap::const_iterator it = _creator.begin(); it != _creator.end(); ++it) + types.push_back(it->first); +} + +bool Factory::knowsTag(const std::string& tag, int* elementType) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt == _creator.end()) { + if (elementType) + *elementType = -1; + return false; + } + if (elementType) + *elementType = foundIt->second->elementTypeBit; + return true; +} + +void Factory::destroy() +{ + delete factoryInstance; + factoryInstance = 0; +} + +void Factory::printRegisteredTypes(std::ostream& os, bool comment) const +{ + if (comment) + os << "# "; + os << "types:" << endl; + for (CreatorMap::const_iterator it = _creator.begin(); it != _creator.end(); ++it) { + if (comment) + os << "#"; + cerr << "\t" << it->first << endl; + } +} + +HyperGraph::HyperGraphElement* Factory::construct(const std::string& tag, const HyperGraph::GraphElemBitset& elemsToConstruct) const +{ + if (elemsToConstruct.none()) { + return construct(tag); + } + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end() && foundIt->second->elementTypeBit >= 0 && elemsToConstruct.test(foundIt->second->elementTypeBit)) { + return foundIt->second->creator->construct(); + } + return 0; +} + +} // end namespace + diff --git a/Thirdparty/g2o/g2o/core/factory.h b/Thirdparty/g2o/g2o/core/factory.h new file mode 100644 index 0000000000..0e189aedc1 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/factory.h @@ -0,0 +1,179 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_FACTORY_H +#define G2O_FACTORY_H + +#include "../../config.h" +#include "../stuff/misc.h" +#include "hyper_graph.h" +#include "creators.h" + +#include +#include +#include + +// define to get some verbose output +//#define G2O_DEBUG_FACTORY + +namespace g2o { + + class AbstractHyperGraphElementCreator; + + /** + * \brief create vertices and edges based on TAGs in, for example, a file + */ + class Factory + { + public: + + //! return the instance + static Factory* instance(); + + //! free the instance + static void destroy(); + + /** + * register a tag for a specific creator + */ + void registerType(const std::string& tag, AbstractHyperGraphElementCreator* c); + + /** + * unregister a tag for a specific creator + */ + void unregisterType(const std::string& tag); + + /** + * construct a graph element based on its tag + */ + HyperGraph::HyperGraphElement* construct(const std::string& tag) const; + + /** + * construct a graph element based on its tag, but only if it's type (a bitmask) matches. A bitmask without any + * bit set will construct any item. Otherwise a bit has to be set to allow construction of a graph element. + */ + HyperGraph::HyperGraphElement* construct(const std::string& tag, const HyperGraph::GraphElemBitset& elemsToConstruct) const; + + /** + * return whether the factory knows this tag or not + */ + bool knowsTag(const std::string& tag, int* elementType = 0) const; + + //! return the TAG given a vertex + const std::string& tag(const HyperGraph::HyperGraphElement* v) const; + + /** + * get a list of all known types + */ + void fillKnownTypes(std::vector& types) const; + + /** + * print a list of the known registered types to the given stream + */ + void printRegisteredTypes(std::ostream& os, bool comment = false) const; + + protected: + class CreatorInformation + { + public: + AbstractHyperGraphElementCreator* creator; + int elementTypeBit; + CreatorInformation() + { + creator = 0; + elementTypeBit = -1; + } + + ~CreatorInformation() + { + std::cout << "Deleting " << (void*) creator << std::endl; + + delete creator; + } + }; + + typedef std::map CreatorMap; + typedef std::map TagLookup; + Factory(); + ~Factory(); + + CreatorMap _creator; ///< look-up map for the existing creators + TagLookup _tagLookup; ///< reverse look-up, class name to tag + + private: + static Factory* factoryInstance; + }; + + template + class RegisterTypeProxy + { + public: + RegisterTypeProxy(const std::string& name) : _name(name) + { +#ifdef G2O_DEBUG_FACTORY + std::cout << __FUNCTION__ << ": Registering " << _name << " of type " << typeid(T).name() << std::endl; +#endif + Factory::instance()->registerType(_name, new HyperGraphElementCreator()); + } + + ~RegisterTypeProxy() + { +#ifdef G2O_DEBUG_FACTORY + std::cout << __FUNCTION__ << ": Unregistering " << _name << " of type " << typeid(T).name() << std::endl; +#endif + Factory::instance()->unregisterType(_name); + } + + private: + std::string _name; + }; + +#if defined _MSC_VER && defined G2O_SHARED_LIBS +# define G2O_FACTORY_EXPORT __declspec(dllexport) +# define G2O_FACTORY_IMPORT __declspec(dllimport) +#else +# define G2O_FACTORY_EXPORT +# define G2O_FACTORY_IMPORT +#endif + + // These macros are used to automate registering types and forcing linkage +#define G2O_REGISTER_TYPE(name, classname) \ + extern "C" void G2O_FACTORY_EXPORT g2o_type_##classname(void) {} \ + static g2o::RegisterTypeProxy g_type_proxy_##classname(#name); + +#define G2O_USE_TYPE_BY_CLASS_NAME(classname) \ + extern "C" void G2O_FACTORY_IMPORT g2o_type_##classname(void); \ + static g2o::ForceLinker proxy_##classname(g2o_type_##classname); + +#define G2O_REGISTER_TYPE_GROUP(typeGroupName) \ + extern "C" void G2O_FACTORY_EXPORT g2o_type_group_##typeGroupName(void) {} + +#define G2O_USE_TYPE_GROUP(typeGroupName) \ + extern "C" void G2O_FACTORY_IMPORT g2o_type_group_##typeGroupName(void); \ + static g2o::ForceLinker g2o_force_type_link_##typeGroupName(g2o_type_group_##typeGroupName); +} + +#endif diff --git a/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp b/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp new file mode 100644 index 0000000000..a54eca5232 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/hyper_dijkstra.cpp @@ -0,0 +1,261 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include +#include +#include +#include +#include +#include "hyper_dijkstra.h" +#include "../stuff/macros.h" + +namespace g2o{ + + using namespace std; + + double HyperDijkstra::TreeAction::perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e){ + (void) v; + (void) vParent; + (void) e; + return std::numeric_limits::max(); + } + + double HyperDijkstra::TreeAction::perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e, double distance){ + if (distance==-1) + return perform (v,vParent,e); + return std::numeric_limits::max(); + } + + HyperDijkstra::AdjacencyMapEntry::AdjacencyMapEntry(HyperGraph::Vertex* child_, HyperGraph::Vertex* parent_, + HyperGraph::Edge* edge_, double distance_) + { + _child=child_; + _parent=parent_; + _edge=edge_; + _distance=distance_; + } + + HyperDijkstra::HyperDijkstra(HyperGraph* g): _graph(g) + { + for (HyperGraph::VertexIDMap::const_iterator it=_graph->vertices().begin(); it!=_graph->vertices().end(); it++){ + AdjacencyMapEntry entry(it->second, 0,0,std::numeric_limits< double >::max()); + _adjacencyMap.insert(make_pair(entry.child(), entry)); + } + } + + void HyperDijkstra::reset() + { + for (HyperGraph::VertexSet::iterator it=_visited.begin(); it!=_visited.end(); it++){ + AdjacencyMap::iterator at=_adjacencyMap.find(*it); + assert(at!=_adjacencyMap.end()); + at->second=AdjacencyMapEntry(at->first,0,0,std::numeric_limits< double >::max()); + } + _visited.clear(); + } + + + bool operator<(const HyperDijkstra::AdjacencyMapEntry& a, const HyperDijkstra::AdjacencyMapEntry& b) + { + return a.distance()>b.distance(); + } + + + void HyperDijkstra::shortestPaths(HyperGraph::VertexSet& vset, HyperDijkstra::CostFunction* cost, + double maxDistance, double comparisonConditioner, bool directed, double maxEdgeCost) + { + reset(); + std::priority_queue< AdjacencyMapEntry > frontier; + for (HyperGraph::VertexSet::iterator vit=vset.begin(); vit!=vset.end(); ++vit){ + HyperGraph::Vertex* v=*vit; + assert(v!=0); + AdjacencyMap::iterator it=_adjacencyMap.find(v); + if (it == _adjacencyMap.end()) { + cerr << __PRETTY_FUNCTION__ << "Vertex " << v->id() << " is not in the adjacency map" << endl; + } + assert(it!=_adjacencyMap.end()); + it->second._distance=0.; + it->second._parent=0; + frontier.push(it->second); + } + + while(! frontier.empty()){ + AdjacencyMapEntry entry=frontier.top(); + frontier.pop(); + HyperGraph::Vertex* u=entry.child(); + AdjacencyMap::iterator ut=_adjacencyMap.find(u); + if (ut == _adjacencyMap.end()) { + cerr << __PRETTY_FUNCTION__ << "Vertex " << u->id() << " is not in the adjacency map" << endl; + } + assert(ut!=_adjacencyMap.end()); + double uDistance=ut->second.distance(); + + std::pair< HyperGraph::VertexSet::iterator, bool> insertResult=_visited.insert(u); (void) insertResult; + HyperGraph::EdgeSet::iterator et=u->edges().begin(); + while (et != u->edges().end()){ + HyperGraph::Edge* edge=*et; + ++et; + + if (directed && edge->vertex(0) != u) + continue; + + for (size_t i = 0; i < edge->vertices().size(); ++i) { + HyperGraph::Vertex* z = edge->vertex(i); + if (z == u) + continue; + + double edgeDistance=(*cost)(edge, u, z); + if (edgeDistance==std::numeric_limits< double >::max() || edgeDistance > maxEdgeCost) + continue; + double zDistance=uDistance+edgeDistance; + //cerr << z->id() << " " << zDistance << endl; + + AdjacencyMap::iterator ot=_adjacencyMap.find(z); + assert(ot!=_adjacencyMap.end()); + + if (zDistance+comparisonConditionersecond.distance() && zDistancesecond._distance=zDistance; + ot->second._parent=u; + ot->second._edge=edge; + frontier.push(ot->second); + } + } + } + } + } + + void HyperDijkstra::shortestPaths(HyperGraph::Vertex* v, HyperDijkstra::CostFunction* cost, double maxDistance, + double comparisonConditioner, bool directed, double maxEdgeCost) + { + HyperGraph::VertexSet vset; + vset.insert(v); + shortestPaths(vset, cost, maxDistance, comparisonConditioner, directed, maxEdgeCost); + } + + void HyperDijkstra::computeTree(AdjacencyMap& amap) + { + for (AdjacencyMap::iterator it=amap.begin(); it!=amap.end(); ++it){ + AdjacencyMapEntry& entry(it->second); + entry._children.clear(); + } + for (AdjacencyMap::iterator it=amap.begin(); it!=amap.end(); ++it){ + AdjacencyMapEntry& entry(it->second); + HyperGraph::Vertex* parent=entry.parent(); + if (!parent){ + continue; + } + HyperGraph::Vertex* v=entry.child(); + assert (v==it->first); + + AdjacencyMap::iterator pt=amap.find(parent); + assert(pt!=amap.end()); + pt->second._children.insert(v); + } + } + + + void HyperDijkstra::visitAdjacencyMap(AdjacencyMap& amap, TreeAction* action, bool useDistance) + { + + typedef std::deque Deque; + Deque q; + // scans for the vertices without the parent (whcih are the roots of the trees) and applies the action to them. + for (AdjacencyMap::iterator it=amap.begin(); it!=amap.end(); ++it){ + AdjacencyMapEntry& entry(it->second); + if (! entry.parent()) { + action->perform(it->first,0,0); + q.push_back(it->first); + } + } + + //std::cerr << "q.size()" << q.size() << endl; + int count=0; + while (! q.empty()){ + HyperGraph::Vertex* parent=q.front(); + q.pop_front(); + ++count; + AdjacencyMap::iterator parentIt=amap.find(parent); + if (parentIt==amap.end()) { + continue; + } + //cerr << "parent= " << parent << " parent id= " << parent->id() << "\t children id ="; + HyperGraph::VertexSet& childs(parentIt->second.children()); + for (HyperGraph::VertexSet::iterator childsIt=childs.begin(); childsIt!=childs.end(); ++childsIt){ + HyperGraph::Vertex* child=*childsIt; + //cerr << child->id(); + AdjacencyMap::iterator adjacencyIt=amap.find(child); + assert (adjacencyIt!=amap.end()); + HyperGraph::Edge* edge=adjacencyIt->second.edge(); + + assert(adjacencyIt->first==child); + assert(adjacencyIt->second.child()==child); + assert(adjacencyIt->second.parent()==parent); + if (! useDistance) { + action->perform(child, parent, edge); + } else { + action->perform(child, parent, edge, adjacencyIt->second.distance()); + } + q.push_back(child); + } + //cerr << endl; + } + + } + + void HyperDijkstra::connectedSubset(HyperGraph::VertexSet& connected, HyperGraph::VertexSet& visited, + HyperGraph::VertexSet& startingSet, + HyperGraph* g, HyperGraph::Vertex* v, + HyperDijkstra::CostFunction* cost, double distance, + double comparisonConditioner, double maxEdgeCost) + { + typedef std::queue VertexDeque; + visited.clear(); + connected.clear(); + VertexDeque frontier; + HyperDijkstra dv(g); + connected.insert(v); + frontier.push(v); + while (! frontier.empty()){ + HyperGraph::Vertex* v0=frontier.front(); + frontier.pop(); + dv.shortestPaths(v0, cost, distance, comparisonConditioner, false, maxEdgeCost); + for (HyperGraph::VertexSet::iterator it=dv.visited().begin(); it!=dv.visited().end(); ++it){ + visited.insert(*it); + if (startingSet.find(*it)==startingSet.end()) + continue; + std::pair insertOutcome=connected.insert(*it); + if (insertOutcome.second){ // the node was not in the connectedSet; + frontier.push(dynamic_cast(*it)); + } + } + } + } + + double UniformCostFunction::operator () (HyperGraph::Edge* /*edge*/, HyperGraph::Vertex* /*from*/, HyperGraph::Vertex* /*to*/) + { + return 1.; + } + +}; diff --git a/Thirdparty/g2o/g2o/core/hyper_dijkstra.h b/Thirdparty/g2o/g2o/core/hyper_dijkstra.h new file mode 100644 index 0000000000..fe2c2f4bfa --- /dev/null +++ b/Thirdparty/g2o/g2o/core/hyper_dijkstra.h @@ -0,0 +1,112 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_AIS_GENERAL_DIJKSTRA_HH +#define G2O_AIS_GENERAL_DIJKSTRA_HH + +#include +#include +#include + +#include "hyper_graph.h" + +namespace g2o{ + + struct HyperDijkstra{ + struct CostFunction { + virtual double operator() (HyperGraph::Edge* e, HyperGraph::Vertex* from, HyperGraph::Vertex* to)=0; + virtual ~CostFunction() { } + }; + + struct TreeAction { + virtual double perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e); + virtual double perform(HyperGraph::Vertex* v, HyperGraph::Vertex* vParent, HyperGraph::Edge* e, double distance); + }; + + + struct AdjacencyMapEntry{ + friend struct HyperDijkstra; + AdjacencyMapEntry(HyperGraph::Vertex* _child=0, + HyperGraph::Vertex* _parent=0, + HyperGraph::Edge* _edge=0, + double _distance=std::numeric_limits::max()); + HyperGraph::Vertex* child() const {return _child;} + HyperGraph::Vertex* parent() const {return _parent;} + HyperGraph::Edge* edge() const {return _edge;} + double distance() const {return _distance;} + HyperGraph::VertexSet& children() {return _children;} + const HyperGraph::VertexSet& children() const {return _children;} + protected: + HyperGraph::Vertex* _child; + HyperGraph::Vertex* _parent; + HyperGraph::Edge* _edge; + double _distance; + HyperGraph::VertexSet _children; + }; + + typedef std::map AdjacencyMap; + HyperDijkstra(HyperGraph* g); + HyperGraph::VertexSet& visited() {return _visited; } + AdjacencyMap& adjacencyMap() {return _adjacencyMap; } + HyperGraph* graph() {return _graph;} + + void shortestPaths(HyperGraph::Vertex* v, + HyperDijkstra::CostFunction* cost, + double maxDistance=std::numeric_limits< double >::max(), + double comparisonConditioner=1e-3, + bool directed=false, + double maxEdgeCost=std::numeric_limits< double >::max()); + + void shortestPaths(HyperGraph::VertexSet& vset, + HyperDijkstra::CostFunction* cost, + double maxDistance=std::numeric_limits< double >::max(), + double comparisonConditioner=1e-3, + bool directed=false, + double maxEdgeCost=std::numeric_limits< double >::max()); + + + static void computeTree(AdjacencyMap& amap); + static void visitAdjacencyMap(AdjacencyMap& amap, TreeAction* action, bool useDistance=false); + static void connectedSubset(HyperGraph::VertexSet& connected, HyperGraph::VertexSet& visited, + HyperGraph::VertexSet& startingSet, + HyperGraph* g, HyperGraph::Vertex* v, + HyperDijkstra::CostFunction* cost, double distance, double comparisonConditioner, + double maxEdgeCost=std::numeric_limits< double >::max() ); + + protected: + void reset(); + + AdjacencyMap _adjacencyMap; + HyperGraph::VertexSet _visited; + HyperGraph* _graph; + }; + + struct UniformCostFunction: public HyperDijkstra::CostFunction { + virtual double operator ()(HyperGraph::Edge* edge, HyperGraph::Vertex* from, HyperGraph::Vertex* to); + }; + +} +#endif diff --git a/Thirdparty/g2o/g2o/core/hyper_graph.cpp b/Thirdparty/g2o/g2o/core/hyper_graph.cpp new file mode 100644 index 0000000000..1e1ea76e9f --- /dev/null +++ b/Thirdparty/g2o/g2o/core/hyper_graph.cpp @@ -0,0 +1,166 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "hyper_graph.h" + +#include +#include + +namespace g2o { + + HyperGraph::Vertex::Vertex(int id) : _id(id) + { + } + + HyperGraph::Vertex::~Vertex() + { + } + + HyperGraph::Edge::Edge(int id) : _id(id) + { + } + + HyperGraph::Edge::~Edge() + { + } + + void HyperGraph::Edge::resize(size_t size) + { + _vertices.resize(size, 0); + } + + void HyperGraph::Edge::setId(int id) + { + _id = id; + } + + HyperGraph::Vertex* HyperGraph::vertex(int id) + { + VertexIDMap::iterator it=_vertices.find(id); + if (it==_vertices.end()) + return 0; + return it->second; + } + + const HyperGraph::Vertex* HyperGraph::vertex(int id) const + { + VertexIDMap::const_iterator it=_vertices.find(id); + if (it==_vertices.end()) + return 0; + return it->second; + } + + bool HyperGraph::addVertex(Vertex* v) + { + Vertex* vn=vertex(v->id()); + if (vn) + return false; + _vertices.insert( std::make_pair(v->id(),v) ); + return true; + } + + /** + * changes the id of a vertex already in the graph, and updates the bookkeeping + @ returns false if the vertex is not in the graph; + */ + bool HyperGraph::changeId(Vertex* v, int newId){ + Vertex* v2 = vertex(v->id()); + if (v != v2) + return false; + _vertices.erase(v->id()); + v->setId(newId); + _vertices.insert(std::make_pair(v->id(), v)); + return true; + } + + bool HyperGraph::addEdge(Edge* e) + { + std::pair result = _edges.insert(e); + if (! result.second) + return false; + for (std::vector::iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + Vertex* v = *it; + v->edges().insert(e); + } + return true; + } + + bool HyperGraph::removeVertex(Vertex* v) + { + VertexIDMap::iterator it=_vertices.find(v->id()); + if (it==_vertices.end()) + return false; + assert(it->second==v); + //remove all edges which are entering or leaving v; + EdgeSet tmp(v->edges()); + for (EdgeSet::iterator it=tmp.begin(); it!=tmp.end(); ++it){ + if (!removeEdge(*it)){ + assert(0); + } + } + _vertices.erase(it); + delete v; + return true; + } + + bool HyperGraph::removeEdge(Edge* e) + { + EdgeSet::iterator it = _edges.find(e); + if (it == _edges.end()) + return false; + _edges.erase(it); + + for (std::vector::iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) { + Vertex* v = *vit; + it = v->edges().find(e); + assert(it!=v->edges().end()); + v->edges().erase(it); + } + + delete e; + return true; + } + + HyperGraph::HyperGraph() + { + } + + void HyperGraph::clear() + { + for (VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) + delete (it->second); + for (EdgeSet::iterator it=_edges.begin(); it!=_edges.end(); ++it) + delete (*it); + _vertices.clear(); + _edges.clear(); + } + + HyperGraph::~HyperGraph() + { + clear(); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/hyper_graph.h b/Thirdparty/g2o/g2o/core/hyper_graph.h new file mode 100644 index 0000000000..da6bb3d361 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/hyper_graph.h @@ -0,0 +1,220 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_AIS_HYPER_GRAPH_HH +#define G2O_AIS_HYPER_GRAPH_HH + +#include +#include +#include +#include +#include +#include +#include + +#ifdef _MSC_VER +#include +#else +#include +#endif + + +/** @addtogroup graph */ +//@{ +namespace g2o { + + /** + Class that models a directed Hyper-Graph. An hyper graph is a graph where an edge + can connect one or more nodes. Both Vertices and Edges of an hyoper graph + derive from the same class HyperGraphElement, thus one can implement generic algorithms + that operate transparently on edges or vertices (see HyperGraphAction). + + The vertices are uniquely identified by an int id, while the edges are + identfied by their pointers. + */ + class HyperGraph + { + public: + + /** + * \brief enum of all the types we have in our graphs + */ + enum HyperGraphElementType { + HGET_VERTEX, + HGET_EDGE, + HGET_PARAMETER, + HGET_CACHE, + HGET_DATA, + HGET_NUM_ELEMS // keep as last elem + }; + + typedef std::bitset GraphElemBitset; + + class Vertex; + class Edge; + + /** + * base hyper graph element, specialized in vertex and edge + */ + struct HyperGraphElement { + virtual ~HyperGraphElement() {} + /** + * returns the type of the graph element, see HyperGraphElementType + */ + virtual HyperGraphElementType elementType() const = 0; + }; + + typedef std::set EdgeSet; + typedef std::set VertexSet; + + typedef std::tr1::unordered_map VertexIDMap; + typedef std::vector VertexContainer; + + //! abstract Vertex, your types must derive from that one + class Vertex : public HyperGraphElement { + public: + //! creates a vertex having an ID specified by the argument + explicit Vertex(int id=-1); + virtual ~Vertex(); + //! returns the id + int id() const {return _id;} + virtual void setId( int newId) { _id=newId; } + //! returns the set of hyper-edges that are leaving/entering in this vertex + const EdgeSet& edges() const {return _edges;} + //! returns the set of hyper-edges that are leaving/entering in this vertex + EdgeSet& edges() {return _edges;} + virtual HyperGraphElementType elementType() const { return HGET_VERTEX;} + protected: + int _id; + EdgeSet _edges; + }; + + /** + * Abstract Edge class. Your nice edge classes should inherit from that one. + * An hyper-edge has pointers to the vertices it connects and stores them in a vector. + */ + class Edge : public HyperGraphElement { + public: + //! creates and empty edge with no vertices + explicit Edge(int id = -1); + virtual ~Edge(); + + /** + * resizes the number of vertices connected by this edge + */ + virtual void resize(size_t size); + /** + returns the vector of pointers to the vertices connected by the hyper-edge. + */ + const VertexContainer& vertices() const { return _vertices;} + /** + returns the vector of pointers to the vertices connected by the hyper-edge. + */ + VertexContainer& vertices() { return _vertices;} + /** + returns the pointer to the ith vertex connected to the hyper-edge. + */ + const Vertex* vertex(size_t i) const { assert(i < _vertices.size() && "index out of bounds"); return _vertices[i];} + /** + returns the pointer to the ith vertex connected to the hyper-edge. + */ + Vertex* vertex(size_t i) { assert(i < _vertices.size() && "index out of bounds"); return _vertices[i];} + /** + set the ith vertex on the hyper-edge to the pointer supplied + */ + void setVertex(size_t i, Vertex* v) { assert(i < _vertices.size() && "index out of bounds"); _vertices[i]=v;} + + int id() const {return _id;} + void setId(int id); + virtual HyperGraphElementType elementType() const { return HGET_EDGE;} + protected: + VertexContainer _vertices; + int _id; ///< unique id + }; + + public: + //! constructs an empty hyper graph + HyperGraph(); + //! destroys the hyper-graph and all the vertices of the graph + virtual ~HyperGraph(); + + //! returns a vertex id in the hyper-graph, or 0 if the vertex id is not present + Vertex* vertex(int id); + //! returns a vertex id in the hyper-graph, or 0 if the vertex id is not present + const Vertex* vertex(int id) const; + + //! removes a vertex from the graph. Returns true on success (vertex was present) + virtual bool removeVertex(Vertex* v); + //! removes a vertex from the graph. Returns true on success (edge was present) + virtual bool removeEdge(Edge* e); + //! clears the graph and empties all structures. + virtual void clear(); + + //! @returns the map id -> vertex where the vertices are stored + const VertexIDMap& vertices() const {return _vertices;} + //! @returns the map id -> vertex where the vertices are stored + VertexIDMap& vertices() {return _vertices;} + + //! @returns the set of edges of the hyper graph + const EdgeSet& edges() const {return _edges;} + //! @returns the set of edges of the hyper graph + EdgeSet& edges() {return _edges;} + + /** + * adds a vertex to the graph. The id of the vertex should be set before + * invoking this function. the function fails if another vertex + * with the same id is already in the graph. + * returns true, on success, or false on failure. + */ + virtual bool addVertex(Vertex* v); + + /** + * Adds an edge to the graph. If the edge is already in the graph, it + * does nothing and returns false. Otherwise it returns true. + */ + virtual bool addEdge(Edge* e); + + /** + * changes the id of a vertex already in the graph, and updates the bookkeeping + @ returns false if the vertex is not in the graph; + */ + virtual bool changeId(Vertex* v, int newId); + + protected: + VertexIDMap _vertices; + EdgeSet _edges; + + private: + // Disable the copy constructor and assignment operator + HyperGraph(const HyperGraph&) { } + HyperGraph& operator= (const HyperGraph&) { return *this; } + }; + +} // end namespace + +//@} + +#endif diff --git a/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp b/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp new file mode 100644 index 0000000000..1fe2439cc2 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/hyper_graph_action.cpp @@ -0,0 +1,268 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "hyper_graph_action.h" +#include "optimizable_graph.h" +#include "../stuff/macros.h" + + +#include + +namespace g2o { + using namespace std; + + HyperGraphActionLibrary* HyperGraphActionLibrary::actionLibInstance = 0; + + HyperGraphAction::Parameters::~Parameters() + { + } + + HyperGraphAction::ParametersIteration::ParametersIteration(int iter) : + HyperGraphAction::Parameters(), + iteration(iter) + { + } + + HyperGraphAction::~HyperGraphAction() + { + } + + HyperGraphAction* HyperGraphAction::operator()(const HyperGraph*, Parameters*) + { + return 0; + } + + HyperGraphElementAction::Parameters::~Parameters() + { + } + + HyperGraphElementAction::HyperGraphElementAction(const std::string& typeName_) + { + _typeName = typeName_; + } + + void HyperGraphElementAction::setTypeName(const std::string& typeName_) + { + _typeName = typeName_; + } + + + HyperGraphElementAction* HyperGraphElementAction::operator()(HyperGraph::HyperGraphElement* , HyperGraphElementAction::Parameters* ) + { + return 0; + } + + HyperGraphElementAction* HyperGraphElementAction::operator()(const HyperGraph::HyperGraphElement* , HyperGraphElementAction::Parameters* ) + { + return 0; + } + + HyperGraphElementAction::~HyperGraphElementAction() + { + } + + HyperGraphElementActionCollection::HyperGraphElementActionCollection(const std::string& name_) + { + _name = name_; + } + + HyperGraphElementActionCollection::~HyperGraphElementActionCollection() + { + for (ActionMap::iterator it = _actionMap.begin(); it != _actionMap.end(); ++it) { + delete it->second; + } + } + + HyperGraphElementAction* HyperGraphElementActionCollection::operator()(HyperGraph::HyperGraphElement* element, HyperGraphElementAction::Parameters* params) + { + ActionMap::iterator it=_actionMap.find(typeid(*element).name()); + //cerr << typeid(*element).name() << endl; + if (it==_actionMap.end()) + return 0; + HyperGraphElementAction* action=it->second; + return (*action)(element, params); + } + + HyperGraphElementAction* HyperGraphElementActionCollection::operator()(const HyperGraph::HyperGraphElement* element, HyperGraphElementAction::Parameters* params) + { + ActionMap::iterator it=_actionMap.find(typeid(*element).name()); + if (it==_actionMap.end()) + return 0; + HyperGraphElementAction* action=it->second; + return (*action)(element, params); + } + + bool HyperGraphElementActionCollection::registerAction(HyperGraphElementAction* action) + { +# ifdef G2O_DEBUG_ACTIONLIB + cerr << __PRETTY_FUNCTION__ << " " << action->name() << " " << action->typeName() << endl; +# endif + if (action->name()!=name()){ + cerr << __PRETTY_FUNCTION__ << ": invalid attempt to register an action in a collection with a different name " << name() << " " << action->name() << endl; + } + _actionMap.insert(make_pair ( action->typeName(), action) ); + return true; + } + + bool HyperGraphElementActionCollection::unregisterAction(HyperGraphElementAction* action) + { + for (HyperGraphElementAction::ActionMap::iterator it=_actionMap.begin(); it != _actionMap.end(); ++it) { + if (it->second == action){ + _actionMap.erase(it); + return true; + } + } + return false; + } + + HyperGraphActionLibrary::HyperGraphActionLibrary() + { + } + + HyperGraphActionLibrary* HyperGraphActionLibrary::instance() + { + if (actionLibInstance == 0) { + actionLibInstance = new HyperGraphActionLibrary; + } + return actionLibInstance; + } + + void HyperGraphActionLibrary::destroy() + { + delete actionLibInstance; + actionLibInstance = 0; + } + + HyperGraphActionLibrary::~HyperGraphActionLibrary() + { + for (HyperGraphElementAction::ActionMap::iterator it = _actionMap.begin(); it != _actionMap.end(); ++it) { + delete it->second; + } + } + + HyperGraphElementAction* HyperGraphActionLibrary::actionByName(const std::string& name) + { + HyperGraphElementAction::ActionMap::iterator it=_actionMap.find(name); + if (it!=_actionMap.end()) + return it->second; + return 0; + } + + bool HyperGraphActionLibrary::registerAction(HyperGraphElementAction* action) + { + HyperGraphElementAction* oldAction = actionByName(action->name()); + HyperGraphElementActionCollection* collection = 0; + if (oldAction) { + collection = dynamic_cast(oldAction); + if (! collection) { + cerr << __PRETTY_FUNCTION__ << ": fatal error, a collection is not at the first level in the library" << endl; + return 0; + } + } + if (! collection) { +#ifdef G2O_DEBUG_ACTIONLIB + cerr << __PRETTY_FUNCTION__ << ": creating collection for \"" << action->name() << "\"" << endl; +#endif + collection = new HyperGraphElementActionCollection(action->name()); + _actionMap.insert(make_pair(action->name(), collection)); + } + return collection->registerAction(action); + } + + bool HyperGraphActionLibrary::unregisterAction(HyperGraphElementAction* action) + { + list collectionDeleteList; + + // Search all the collections and delete the registered actions; if a collection becomes empty, schedule it for deletion; note that we can't delete the collections as we go because this will screw up the state of the iterators + for (HyperGraphElementAction::ActionMap::iterator it=_actionMap.begin(); it != _actionMap.end(); ++it) { + HyperGraphElementActionCollection* collection = dynamic_cast (it->second); + if (collection != 0) { + collection->unregisterAction(action); + if (collection->actionMap().size() == 0) { + collectionDeleteList.push_back(collection); + } + } + } + + // Delete any empty action collections + for (list::iterator itc = collectionDeleteList.begin(); itc != collectionDeleteList.end(); ++itc) { + //cout << "Deleting collection " << (*itc)->name() << endl; + _actionMap.erase((*itc)->name()); + } + + return true; + } + + + WriteGnuplotAction::WriteGnuplotAction(const std::string& typeName_) + : HyperGraphElementAction(typeName_) + { + _name="writeGnuplot"; + } + + DrawAction::Parameters::Parameters(){ + } + + DrawAction::DrawAction(const std::string& typeName_) + : HyperGraphElementAction(typeName_) + { + _name="draw"; + _previousParams = (Parameters*)0x42; + refreshPropertyPtrs(0); + } + + bool DrawAction::refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_){ + if (_previousParams == params_) + return false; + DrawAction::Parameters* p=dynamic_cast(params_); + if (! p){ + _previousParams = 0; + _show = 0; + _showId = 0; + } else { + _previousParams = p; + _show = p->makeProperty(_typeName+"::SHOW", true); + _showId = p->makeProperty(_typeName+"::SHOW_ID", false); + } + return true; + } + + void applyAction(HyperGraph* graph, HyperGraphElementAction* action, HyperGraphElementAction::Parameters* params, const std::string& typeName) + { + for (HyperGraph::VertexIDMap::iterator it=graph->vertices().begin(); + it!=graph->vertices().end(); ++it){ + if ( typeName.empty() || typeid(*it->second).name()==typeName){ + (*action)(it->second, params); + } + } + for (HyperGraph::EdgeSet::iterator it=graph->edges().begin(); + it!=graph->edges().end(); ++it){ + if ( typeName.empty() || typeid(**it).name()==typeName) + (*action)(*it, params); + } + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/hyper_graph_action.h b/Thirdparty/g2o/g2o/core/hyper_graph_action.h new file mode 100644 index 0000000000..21417c9ba1 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/hyper_graph_action.h @@ -0,0 +1,222 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_HYPER_GRAPH_ACTION_H +#define G2O_HYPER_GRAPH_ACTION_H + +#include "hyper_graph.h" +#include "../stuff/property.h" + +#include +#include +#include +#include +#include + + +// define to get verbose output +//#define G2O_DEBUG_ACTIONLIB + +namespace g2o { + + /** + * \brief Abstract action that operates on an entire graph + */ + class HyperGraphAction { + public: + class Parameters { + public: + virtual ~Parameters(); + }; + + class ParametersIteration : public Parameters { + public: + explicit ParametersIteration(int iter); + int iteration; + }; + + virtual ~HyperGraphAction(); + + /** + * re-implement to carry out an action given the graph + */ + virtual HyperGraphAction* operator()(const HyperGraph* graph, Parameters* parameters = 0); + }; + + /** + * \brief Abstract action that operates on a graph entity + */ + class HyperGraphElementAction{ + public: + struct Parameters{ + virtual ~Parameters(); + }; + typedef std::map ActionMap; + //! an action should be instantiated with the typeid.name of the graph element + //! on which it operates + HyperGraphElementAction(const std::string& typeName_=""); + + //! redefine this to do the action stuff. If successful, the action returns a pointer to itself + virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, Parameters* parameters); + + //! redefine this to do the action stuff. If successful, the action returns a pointer to itself + virtual HyperGraphElementAction* operator()(const HyperGraph::HyperGraphElement* element, Parameters* parameters); + + //! destroyed actions release the memory + virtual ~HyperGraphElementAction(); + + //! returns the typeid name of the action + const std::string& typeName() const { return _typeName;} + + //! returns the name of an action, e.g "draw" + const std::string& name() const{ return _name;} + + //! sets the type on which an action has to operate + void setTypeName(const std::string& typeName_); + + protected: + std::string _typeName; + std::string _name; + }; + + /** + * \brief collection of actions + * + * collection of actions calls contains homogeneous actions operating on different types + * all collected actions have the same name and should have the same functionality + */ + class HyperGraphElementActionCollection: public HyperGraphElementAction{ + public: + //! constructor. name_ is the name of the action e.g.draw). + HyperGraphElementActionCollection(const std::string& name_); + //! destructor: it deletes all actions in the pool. + virtual ~HyperGraphElementActionCollection(); + //! calling functions, they return a pointer to the instance of action in actionMap + //! that was active on element + virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, Parameters* parameters); + virtual HyperGraphElementAction* operator()(const HyperGraph::HyperGraphElement* element, Parameters* parameters); + ActionMap& actionMap() {return _actionMap;} + //! inserts an action in the pool. The action should have the same name of the container. + //! returns false on failure (the container has a different name than the action); + bool registerAction(HyperGraphElementAction* action); + bool unregisterAction(HyperGraphElementAction* action); + protected: + ActionMap _actionMap; + }; + + /** + * \brief library of actions, indexed by the action name; + * + * library of actions, indexed by the action name; + * one can use ti to register a collection of actions + */ + class HyperGraphActionLibrary{ + public: + //! return the single instance of the HyperGraphActionLibrary + static HyperGraphActionLibrary* instance(); + //! free the instance + static void destroy(); + + // returns a pointer to a collection indexed by name + HyperGraphElementAction* actionByName(const std::string& name); + // registers a basic action in the pool. If necessary a container is created + bool registerAction(HyperGraphElementAction* action); + bool unregisterAction(HyperGraphElementAction* action); + + inline HyperGraphElementAction::ActionMap& actionMap() {return _actionMap;} + protected: + HyperGraphActionLibrary(); + ~HyperGraphActionLibrary(); + HyperGraphElementAction::ActionMap _actionMap; + private: + static HyperGraphActionLibrary* actionLibInstance; + }; + + /** + * apply an action to all the elements of the graph. + */ + void applyAction(HyperGraph* graph, HyperGraphElementAction* action, HyperGraphElementAction::Parameters* parameters=0, const std::string& typeName=""); + + /** + * brief write into gnuplot + */ + class WriteGnuplotAction: public HyperGraphElementAction{ + public: + struct Parameters: public HyperGraphElementAction::Parameters{ + std::ostream* os; + }; + WriteGnuplotAction(const std::string& typeName_); + }; + + /** + * \brief draw actions + */ + + class DrawAction : public HyperGraphElementAction{ + public: + class Parameters: public HyperGraphElementAction::Parameters, public PropertyMap{ + public: + Parameters(); + }; + DrawAction(const std::string& typeName_); + protected: + virtual bool refreshPropertyPtrs(HyperGraphElementAction::Parameters* params_); + Parameters* _previousParams; + BoolProperty* _show; + BoolProperty* _showId; + }; + + template class RegisterActionProxy + { + public: + RegisterActionProxy() + { +#ifdef G2O_DEBUG_ACTIONLIB + std::cout << __FUNCTION__ << ": Registering action of type " << typeid(T).name() << std::endl; +#endif + _action = new T(); + HyperGraphActionLibrary::instance()->registerAction(_action); + } + + ~RegisterActionProxy() + { +#ifdef G2O_DEBUG_ACTIONLIB + std::cout << __FUNCTION__ << ": Unregistering action of type " << typeid(T).name() << std::endl; +#endif + HyperGraphActionLibrary::instance()->unregisterAction(_action); + delete _action; + } + + private: + HyperGraphElementAction* _action; + }; + +#define G2O_REGISTER_ACTION(classname) \ + extern "C" void g2o_action_##classname(void) {} \ + static g2o::RegisterActionProxy g_action_proxy_##classname; +}; + +#endif diff --git a/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp b/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp new file mode 100644 index 0000000000..9890a181d0 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/jacobian_workspace.cpp @@ -0,0 +1,89 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "jacobian_workspace.h" + +#include + +#include "optimizable_graph.h" + +using namespace std; + +namespace g2o { + +JacobianWorkspace::JacobianWorkspace() : + _maxNumVertices(-1), _maxDimension(-1) +{ +} + +JacobianWorkspace::~JacobianWorkspace() +{ +} + +bool JacobianWorkspace::allocate() +{ + //cerr << __PRETTY_FUNCTION__ << " " << PVAR(this) << " " << PVAR(_maxNumVertices) << " " << PVAR(_maxDimension) << endl; + if (_maxNumVertices <=0 || _maxDimension <= 0) + return false; + _workspace.resize(_maxNumVertices); + for (WorkspaceVector::iterator it = _workspace.begin(); it != _workspace.end(); ++it) { + it->resize(_maxDimension); + it->setZero(); + } + return true; +} + +void JacobianWorkspace::updateSize(const HyperGraph::Edge* e_) +{ + const OptimizableGraph::Edge* e = static_cast(e_); + int errorDimension = e->dimension(); + int numVertices = e->vertices().size(); + int maxDimensionForEdge = -1; + for (int i = 0; i < numVertices; ++i) { + const OptimizableGraph::Vertex* v = static_cast(e->vertex(i)); + assert(v && "Edge has no vertex assigned"); + maxDimensionForEdge = max(v->dimension() * errorDimension, maxDimensionForEdge); + } + _maxNumVertices = max(numVertices, _maxNumVertices); + _maxDimension = max(maxDimensionForEdge, _maxDimension); + //cerr << __PRETTY_FUNCTION__ << " " << PVAR(this) << " " << PVAR(_maxNumVertices) << " " << PVAR(_maxDimension) << endl; +} + +void JacobianWorkspace::updateSize(const OptimizableGraph& graph) +{ + for (OptimizableGraph::EdgeSet::const_iterator it = graph.edges().begin(); it != graph.edges().end(); ++it) { + const OptimizableGraph::Edge* e = static_cast(*it); + updateSize(e); + } +} + +void JacobianWorkspace::updateSize(int numVertices, int dimension) +{ + _maxNumVertices = max(numVertices, _maxNumVertices); + _maxDimension = max(dimension, _maxDimension); +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/jacobian_workspace.h b/Thirdparty/g2o/g2o/core/jacobian_workspace.h new file mode 100644 index 0000000000..e1f1602633 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/jacobian_workspace.h @@ -0,0 +1,96 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef JACOBIAN_WORKSPACE_H +#define JACOBIAN_WORKSPACE_H + +#include +#include + +#include +#include + +#include "hyper_graph.h" + +namespace g2o { + + struct OptimizableGraph; + + /** + * \brief provide memory workspace for computing the Jacobians + * + * The workspace is used by an OptimizableGraph to provide temporary memory + * for computing the Jacobian of the error functions. + * Before calling linearizeOplus on an edge, the workspace needs to be allocated + * by calling allocate(). + */ + class JacobianWorkspace + { + public: + typedef std::vector > WorkspaceVector; + + public: + JacobianWorkspace(); + ~JacobianWorkspace(); + + /** + * allocate the workspace + */ + bool allocate(); + + /** + * update the maximum required workspace needed by taking into account this edge + */ + void updateSize(const HyperGraph::Edge* e); + + /** + * update the required workspace by looking at a full graph + */ + void updateSize(const OptimizableGraph& graph); + + /** + * manually update with the given parameters + */ + void updateSize(int numVertices, int dimension); + + /** + * return the workspace for a vertex in an edge + */ + double* workspaceForVertex(int vertexIndex) + { + assert(vertexIndex >= 0 && (size_t)vertexIndex < _workspace.size() && "Index out of bounds"); + return _workspace[vertexIndex].data(); + } + + protected: + WorkspaceVector _workspace; ///< the memory pre-allocated for computing the Jacobians + int _maxNumVertices; ///< the maximum number of vertices connected by a hyper-edge + int _maxDimension; ///< the maximum dimension (number of elements) for a Jacobian + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/linear_solver.h b/Thirdparty/g2o/g2o/core/linear_solver.h new file mode 100644 index 0000000000..20213d439b --- /dev/null +++ b/Thirdparty/g2o/g2o/core/linear_solver.h @@ -0,0 +1,109 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_LINEAR_SOLVER_H +#define G2O_LINEAR_SOLVER_H +#include "sparse_block_matrix.h" +#include "sparse_block_matrix_ccs.h" + +namespace g2o { + +/** + * \brief basic solver for Ax = b + * + * basic solver for Ax = b which has to reimplemented for different linear algebra libraries. + * A is assumed to be symmetric (only upper triangular block is stored) and positive-semi-definit. + */ +template +class LinearSolver +{ + public: + LinearSolver() {}; + virtual ~LinearSolver() {} + + /** + * init for operating on matrices with a different non-zero pattern like before + */ + virtual bool init() = 0; + + /** + * Assumes that A is the same matrix for several calls. + * Among other assumptions, the non-zero pattern does not change! + * If the matrix changes call init() before. + * solve system Ax = b, x and b have to allocated beforehand!! + */ + virtual bool solve(const SparseBlockMatrix& A, double* x, double* b) = 0; + + /** + * Inverts the diagonal blocks of A + * @returns false if not defined. + */ + virtual bool solveBlocks(double**&blocks, const SparseBlockMatrix& A) { (void)blocks; (void) A; return false; } + + + /** + * Inverts the a block pattern of A in spinv + * @returns false if not defined. + */ + virtual bool solvePattern(SparseBlockMatrix& spinv, const std::vector >& blockIndices, const SparseBlockMatrix& A){ + (void) spinv; + (void) blockIndices; + (void) A; + return false; + } + + //! write a debug dump of the system matrix if it is not PSD in solve + virtual bool writeDebug() const { return false;} + virtual void setWriteDebug(bool) {} +}; + +/** + * \brief Solver with faster iterating structure for the linear matrix + */ +template +class LinearSolverCCS : public LinearSolver +{ + public: + LinearSolverCCS() : LinearSolver(), _ccsMatrix(0) {} + ~LinearSolverCCS() + { + delete _ccsMatrix; + } + + protected: + SparseBlockMatrixCCS* _ccsMatrix; + + void initMatrixStructure(const SparseBlockMatrix& A) + { + delete _ccsMatrix; + _ccsMatrix = new SparseBlockMatrixCCS(A.rowBlockIndices(), A.colBlockIndices()); + A.fillSparseBlockMatrixCCS(*_ccsMatrix); + } +}; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp b/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp new file mode 100644 index 0000000000..bc11f5ccca --- /dev/null +++ b/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.cpp @@ -0,0 +1,222 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "marginal_covariance_cholesky.h" + +#include +#include +using namespace std; + +namespace g2o { + +struct MatrixElem +{ + int r, c; + MatrixElem(int r_, int c_) : r(r_), c(c_) {} + bool operator<(const MatrixElem& other) const + { + return c > other.c || (c == other.c && r > other.r); + } +}; + +MarginalCovarianceCholesky::MarginalCovarianceCholesky() : + _n(0), _Ap(0), _Ai(0), _Ax(0), _perm(0) +{ +} + +MarginalCovarianceCholesky::~MarginalCovarianceCholesky() +{ +} + +void MarginalCovarianceCholesky::setCholeskyFactor(int n, int* Lp, int* Li, double* Lx, int* permInv) +{ + _n = n; + _Ap = Lp; + _Ai = Li; + _Ax = Lx; + _perm = permInv; + + // pre-compute reciprocal values of the diagonal of L + _diag.resize(n); + for (int r = 0; r < n; ++r) { + const int& sc = _Ap[r]; // L is lower triangular, thus the first elem in the column is the diagonal entry + assert(r == _Ai[sc] && "Error in CCS storage of L"); + _diag[r] = 1.0 / _Ax[sc]; + } +} + +double MarginalCovarianceCholesky::computeEntry(int r, int c) +{ + assert(r <= c); + int idx = computeIndex(r, c); + + LookupMap::const_iterator foundIt = _map.find(idx); + if (foundIt != _map.end()) { + return foundIt->second; + } + + // compute the summation over column r + double s = 0.; + const int& sc = _Ap[r]; + const int& ec = _Ap[r+1]; + for (int j = sc+1; j < ec; ++j) { // sum over row r while skipping the element on the diagonal + const int& rr = _Ai[j]; + double val = rr < c ? computeEntry(rr, c) : computeEntry(c, rr); + s += val * _Ax[j]; + } + + double result; + if (r == c) { + const double& diagElem = _diag[r]; + result = diagElem * (diagElem - s); + } else { + result = -s * _diag[r]; + } + _map[idx] = result; + return result; +} + +void MarginalCovarianceCholesky::computeCovariance(double** covBlocks, const std::vector& blockIndices) +{ + _map.clear(); + int base = 0; + vector elemsToCompute; + for (size_t i = 0; i < blockIndices.size(); ++i) { + int nbase = blockIndices[i]; + int vdim = nbase - base; + for (int rr = 0; rr < vdim; ++rr) + for (int cc = rr; cc < vdim; ++cc) { + int r = _perm ? _perm[rr + base] : rr + base; // apply permutation + int c = _perm ? _perm[cc + base] : cc + base; + if (r > c) // make sure it's still upper triangular after applying the permutation + swap(r, c); + elemsToCompute.push_back(MatrixElem(r, c)); + } + base = nbase; + } + + // sort the elems to reduce the recursive calls + sort(elemsToCompute.begin(), elemsToCompute.end()); + + // compute the inverse elements we need + for (size_t i = 0; i < elemsToCompute.size(); ++i) { + const MatrixElem& me = elemsToCompute[i]; + computeEntry(me.r, me.c); + } + + // set the marginal covariance for the vertices, by writing to the blocks memory + base = 0; + for (size_t i = 0; i < blockIndices.size(); ++i) { + int nbase = blockIndices[i]; + int vdim = nbase - base; + double* cov = covBlocks[i]; + for (int rr = 0; rr < vdim; ++rr) + for (int cc = rr; cc < vdim; ++cc) { + int r = _perm ? _perm[rr + base] : rr + base; // apply permutation + int c = _perm ? _perm[cc + base] : cc + base; + if (r > c) // upper triangle + swap(r, c); + int idx = computeIndex(r, c); + LookupMap::const_iterator foundIt = _map.find(idx); + assert(foundIt != _map.end()); + cov[rr*vdim + cc] = foundIt->second; + if (rr != cc) + cov[cc*vdim + rr] = foundIt->second; + } + base = nbase; + } +} + + +void MarginalCovarianceCholesky::computeCovariance(SparseBlockMatrix& spinv, const std::vector& rowBlockIndices, const std::vector< std::pair >& blockIndices) +{ + // allocate the sparse + spinv = SparseBlockMatrix(&rowBlockIndices[0], + &rowBlockIndices[0], + rowBlockIndices.size(), + rowBlockIndices.size(), true); + _map.clear(); + vector elemsToCompute; + for (size_t i = 0; i < blockIndices.size(); ++i) { + int blockRow=blockIndices[i].first; + int blockCol=blockIndices[i].second; + assert(blockRow>=0); + assert(blockRow < (int)rowBlockIndices.size()); + assert(blockCol>=0); + assert(blockCol < (int)rowBlockIndices.size()); + + int rowBase=spinv.rowBaseOfBlock(blockRow); + int colBase=spinv.colBaseOfBlock(blockCol); + + MatrixXd *block=spinv.block(blockRow, blockCol, true); + assert(block); + for (int iRow=0; iRowrows(); ++iRow) + for (int iCol=0; iColcols(); ++iCol){ + int rr=rowBase+iRow; + int cc=colBase+iCol; + int r = _perm ? _perm[rr] : rr; // apply permutation + int c = _perm ? _perm[cc] : cc; + if (r > c) + swap(r, c); + elemsToCompute.push_back(MatrixElem(r, c)); + } + } + + // sort the elems to reduce the number of recursive calls + sort(elemsToCompute.begin(), elemsToCompute.end()); + + // compute the inverse elements we need + for (size_t i = 0; i < elemsToCompute.size(); ++i) { + const MatrixElem& me = elemsToCompute[i]; + computeEntry(me.r, me.c); + } + + // set the marginal covariance + for (size_t i = 0; i < blockIndices.size(); ++i) { + int blockRow=blockIndices[i].first; + int blockCol=blockIndices[i].second; + int rowBase=spinv.rowBaseOfBlock(blockRow); + int colBase=spinv.colBaseOfBlock(blockCol); + + MatrixXd *block=spinv.block(blockRow, blockCol); + assert(block); + for (int iRow=0; iRowrows(); ++iRow) + for (int iCol=0; iColcols(); ++iCol){ + int rr=rowBase+iRow; + int cc=colBase+iCol; + int r = _perm ? _perm[rr] : rr; // apply permutation + int c = _perm ? _perm[cc] : cc; + if (r > c) + swap(r, c); + int idx = computeIndex(r, c); + LookupMap::const_iterator foundIt = _map.find(idx); + assert(foundIt != _map.end()); + (*block)(iRow, iCol) = foundIt->second; + } + } +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h b/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h new file mode 100644 index 0000000000..e7dfce88f8 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/marginal_covariance_cholesky.h @@ -0,0 +1,103 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_MARGINAL_COVARIANCE_CHOLESKY_H +#define G2O_MARGINAL_COVARIANCE_CHOLESKY_H + +#include "optimizable_graph.h" +#include "sparse_block_matrix.h" + +#include +#include + +#ifdef _MSC_VER +#include +#else +#include +#endif + + +namespace g2o { + + /** + * \brief computing the marginal covariance given a cholesky factor (lower triangle of the factor) + */ + class MarginalCovarianceCholesky { + protected: + /** + * hash struct for storing the matrix elements needed to compute the covariance + */ + typedef std::tr1::unordered_map LookupMap; + + public: + MarginalCovarianceCholesky(); + ~MarginalCovarianceCholesky(); + + /** + * compute the marginal cov for the given block indices, write the result to the covBlocks memory (which has to + * be provided by the caller). + */ + void computeCovariance(double** covBlocks, const std::vector& blockIndices); + + + /** + * compute the marginal cov for the given block indices, write the result in spinv). + */ + void computeCovariance(SparseBlockMatrix& spinv, const std::vector& rowBlockIndices, const std::vector< std::pair >& blockIndices); + + + /** + * set the CCS representation of the cholesky factor along with the inverse permutation used to reduce the fill-in. + * permInv might be 0, will then not permute the entries. + * + * The pointers provided by the user need to be still valid when calling computeCovariance(). The pointers + * are owned by the caller, MarginalCovarianceCholesky does not free the pointers. + */ + void setCholeskyFactor(int n, int* Lp, int* Li, double* Lx, int* permInv); + + protected: + // information about the cholesky factor (lower triangle) + int _n; ///< L is an n X n matrix + int* _Ap; ///< column pointer of the CCS storage + int* _Ai; ///< row indices of the CCS storage + double* _Ax; ///< values of the cholesky factor + int* _perm; ///< permutation of the cholesky factor. Variable re-ordering for better fill-in + + LookupMap _map; ///< hash look up table for the already computed entries + std::vector _diag; ///< cache 1 / H_ii to avoid recalculations + + //! compute the index used for hashing + int computeIndex(int r, int c) const { /*assert(r <= c);*/ return r*_n + c;} + /** + * compute one entry in the covariance, r and c are values after applying the permutation, and upper triangular. + * May issue recursive calls to itself to compute the missing values. + */ + double computeEntry(int r, int c); + }; + +} + +#endif diff --git a/Thirdparty/g2o/g2o/core/matrix_operations.h b/Thirdparty/g2o/g2o/core/matrix_operations.h new file mode 100644 index 0000000000..28e6fbefc7 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/matrix_operations.h @@ -0,0 +1,74 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_CORE_MATRIX_OPERATIONS_H +#define G2O_CORE_MATRIX_OPERATIONS_H + +#include + +namespace g2o { + namespace internal { + + template + inline void axpy(const MatrixType& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff) += A * x.segment(xoff); + } + + template + inline void axpy(const Eigen::Matrix& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff, A.rows()) += A * x.segment::ColsAtCompileTime>(xoff); + } + + template<> + inline void axpy(const Eigen::MatrixXd& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff, A.rows()) += A * x.segment(xoff, A.cols()); + } + + template + inline void atxpy(const MatrixType& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff) += A.transpose() * x.segment(xoff); + } + + template + inline void atxpy(const Eigen::Matrix& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment::ColsAtCompileTime>(yoff) += A.transpose() * x.segment(xoff, A.rows()); + } + + template<> + inline void atxpy(const Eigen::MatrixXd& A, const Eigen::Map& x, int xoff, Eigen::Map& y, int yoff) + { + y.segment(yoff, A.cols()) += A.transpose() * x.segment(xoff, A.rows()); + } + + } // end namespace internal +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/matrix_structure.cpp b/Thirdparty/g2o/g2o/core/matrix_structure.cpp new file mode 100644 index 0000000000..3152195a33 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/matrix_structure.cpp @@ -0,0 +1,125 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "matrix_structure.h" + +#include +#include +#include +#include +using namespace std; + +namespace g2o { + +struct ColSort +{ + bool operator()(const pair& e1, const pair& e2) const + { + return e1.second < e2.second || (e1.second == e2.second && e1.first < e2.first); + } +}; + +MatrixStructure::MatrixStructure() : + n(0), m(0), Ap(0), Aii(0), maxN(0), maxNz(0) +{ +} + +MatrixStructure::~MatrixStructure() +{ + free(); +} + +void MatrixStructure::alloc(int n_, int nz) +{ + if (n == 0) { + maxN = n = n_; + maxNz = nz; + Ap = new int[maxN + 1]; + Aii = new int[maxNz]; + } + else { + n = n_; + if (maxNz < nz) { + maxNz = 2 * nz; + delete[] Aii; + Aii = new int[maxNz]; + } + if (maxN < n) { + maxN = 2 * n; + delete[] Ap; + Ap = new int[maxN + 1]; + } + } +} + +void MatrixStructure::free() +{ + n = 0; + m = 0; + maxN = 0; + maxNz = 0; + delete[] Aii; Aii = 0; + delete[] Ap; Ap = 0; +} + +bool MatrixStructure::write(const char* filename) const +{ + const int& cols = n; + const int& rows = m; + + string name = filename; + std::string::size_type lastDot = name.find_last_of('.'); + if (lastDot != std::string::npos) + name = name.substr(0, lastDot); + + vector > entries; + for (int i=0; i < cols; ++i) { + const int& rbeg = Ap[i]; + const int& rend = Ap[i+1]; + for (int j = rbeg; j < rend; ++j) { + entries.push_back(make_pair(Aii[j], i)); + if (Aii[j] != i) + entries.push_back(make_pair(i, Aii[j])); + } + } + + sort(entries.begin(), entries.end(), ColSort()); + + std::ofstream fout(filename); + fout << "# name: " << name << std::endl; + fout << "# type: sparse matrix" << std::endl; + fout << "# nnz: " << entries.size() << std::endl; + fout << "# rows: " << rows << std::endl; + fout << "# columns: " << cols << std::endl; + for (vector >::const_iterator it = entries.begin(); it != entries.end(); ++it) { + const pair& entry = *it; + fout << entry.first << " " << entry.second << " 0" << std::endl; // write a constant value of 0 + } + + return fout.good(); +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/matrix_structure.h b/Thirdparty/g2o/g2o/core/matrix_structure.h new file mode 100644 index 0000000000..fd70e53111 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/matrix_structure.h @@ -0,0 +1,69 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_MATRIX_STRUCTURE_H +#define G2O_MATRIX_STRUCTURE_H + + +namespace g2o { + +/** + * \brief representing the structure of a matrix in column compressed structure (only the upper triangular part of the matrix) + */ +class MatrixStructure +{ + public: + MatrixStructure(); + ~MatrixStructure(); + /** + * allocate space for the Matrix Structure. You may call this on an already allocated struct, it will + * then reallocate the memory + additional space (double the required space). + */ + void alloc(int n_, int nz); + + void free(); + + /** + * Write the matrix pattern to a file. File is also loadable by octave, e.g., then use spy(matrix) + */ + bool write(const char* filename) const; + + int n; ///< A is m-by-n. n must be >= 0. + int m; ///< A is m-by-n. m must be >= 0. + int* Ap; ///< column pointers for A, of size n+1 + int* Aii; ///< row indices of A, of size nz = Ap [n] + + //! max number of non-zeros blocks + int nzMax() const { return maxNz;} + + protected: + int maxN; ///< size of the allocated memory + int maxNz; ///< size of the allocated memory +}; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/openmp_mutex.h b/Thirdparty/g2o/g2o/core/openmp_mutex.h new file mode 100644 index 0000000000..6a9b8f4a66 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/openmp_mutex.h @@ -0,0 +1,97 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPENMP_MUTEX +#define G2O_OPENMP_MUTEX + +#include "../../config.h" + +#ifdef G2O_OPENMP +#include +#else +#include +#endif + +namespace g2o { + +#ifdef G2O_OPENMP + + /** + * \brief Mutex realized via OpenMP + */ + class OpenMPMutex + { + public: + OpenMPMutex() { omp_init_lock(&_lock); } + ~OpenMPMutex() { omp_destroy_lock(&_lock); } + void lock() { omp_set_lock(&_lock); } + void unlock() { omp_unset_lock(&_lock); } + protected: + omp_lock_t _lock; + }; + +#else + + /* + * dummy which does nothing in case we don't have OpenMP support. + * In debug mode, the mutex allows to verify the correct lock and unlock behavior + */ + class OpenMPMutex + { + public: +#ifdef NDEBUG + OpenMPMutex() {} +#else + OpenMPMutex() : _cnt(0) {} +#endif + ~OpenMPMutex() { assert(_cnt == 0 && "Freeing locked mutex");} + void lock() { assert(++_cnt == 1 && "Locking already locked mutex");} + void unlock() { assert(--_cnt == 0 && "Trying to unlock a mutex which is not locked");} + protected: +#ifndef NDEBUG + char _cnt; +#endif + }; + +#endif + + /** + * \brief lock a mutex within a scope + */ + class ScopedOpenMPMutex + { + public: + explicit ScopedOpenMPMutex(OpenMPMutex* mutex) : _mutex(mutex) { _mutex->lock(); } + ~ScopedOpenMPMutex() { _mutex->unlock(); } + private: + OpenMPMutex* const _mutex; + ScopedOpenMPMutex(const ScopedOpenMPMutex&); + void operator=(const ScopedOpenMPMutex&); + }; + +} + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimizable_graph.cpp b/Thirdparty/g2o/g2o/core/optimizable_graph.cpp new file mode 100644 index 0000000000..bb6b54bd6a --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimizable_graph.cpp @@ -0,0 +1,910 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "optimizable_graph.h" + +#include +#include +#include +#include +#include + +#include + +#include "estimate_propagator.h" +#include "factory.h" +#include "optimization_algorithm_property.h" +#include "hyper_graph_action.h" +#include "cache.h" +#include "robust_kernel.h" + +#include "../stuff/macros.h" +#include "../stuff/color_macros.h" +#include "../stuff/string_tools.h" +#include "../stuff/misc.h" + +namespace g2o { + + using namespace std; + + OptimizableGraph::Data::Data(){ + _next = 0; + } + + OptimizableGraph::Data::~Data(){ + if (_next) + delete _next; + } + + + OptimizableGraph::Vertex::Vertex() : + HyperGraph::Vertex(), + _graph(0), _userData(0), _hessianIndex(-1), _fixed(false), _marginalized(false), + _colInHessian(-1), _cacheContainer(0) + { + } + + CacheContainer* OptimizableGraph::Vertex::cacheContainer(){ + if (! _cacheContainer) + _cacheContainer = new CacheContainer(this); + return _cacheContainer; + } + + + void OptimizableGraph::Vertex::updateCache(){ + if (_cacheContainer){ + _cacheContainer->setUpdateNeeded(); + _cacheContainer->update(); + } + } + + OptimizableGraph::Vertex::~Vertex() + { + if (_cacheContainer) + delete (_cacheContainer); + if (_userData) + delete _userData; + } + + OptimizableGraph::Vertex* OptimizableGraph::Vertex::clone() const + { + return 0; + } + + bool OptimizableGraph::Vertex::setEstimateData(const double* v) + { + bool ret = setEstimateDataImpl(v); + updateCache(); + return ret; + } + + bool OptimizableGraph::Vertex::getEstimateData(double *) const + { + return false; + } + + int OptimizableGraph::Vertex::estimateDimension() const + { + return -1; + } + + bool OptimizableGraph::Vertex::setMinimalEstimateData(const double* v) + { + bool ret = setMinimalEstimateDataImpl(v); + updateCache(); + return ret; + } + + bool OptimizableGraph::Vertex::getMinimalEstimateData(double *) const + { + return false; + } + + int OptimizableGraph::Vertex::minimalEstimateDimension() const + { + return -1; + } + + + OptimizableGraph::Edge::Edge() : + HyperGraph::Edge(), + _dimension(-1), _level(0), _robustKernel(0) + { + } + + OptimizableGraph::Edge::~Edge() + { + delete _robustKernel; + } + + OptimizableGraph* OptimizableGraph::Edge::graph(){ + if (! _vertices.size()) + return 0; + OptimizableGraph::Vertex* v=(OptimizableGraph::Vertex*)_vertices[0]; + if (!v) + return 0; + return v->graph(); + } + + const OptimizableGraph* OptimizableGraph::Edge::graph() const{ + if (! _vertices.size()) + return 0; + const OptimizableGraph::Vertex* v=(const OptimizableGraph::Vertex*) _vertices[0]; + if (!v) + return 0; + return v->graph(); + } + + bool OptimizableGraph::Edge::setParameterId(int argNum, int paramId){ + if ((int)_parameters.size()<=argNum) + return false; + if (argNum<0) + return false; + *_parameters[argNum] = 0; + _parameterIds[argNum] = paramId; + return true; + } + + bool OptimizableGraph::Edge::resolveParameters() { + if (!graph()) { + cerr << __PRETTY_FUNCTION__ << ": edge not registered with a graph" << endl; + return false; + } + + assert (_parameters.size() == _parameterIds.size()); + //cerr << __PRETTY_FUNCTION__ << ": encountered " << _parameters.size() << " parameters" << endl; + for (size_t i=0; i<_parameters.size(); i++){ + int index = _parameterIds[i]; + *_parameters[i] = graph()->parameter(index); + if (typeid(**_parameters[i]).name()!=_parameterTypes[i]){ + cerr << __PRETTY_FUNCTION__ << ": FATAL, parameter type mismatch - encountered " << typeid(**_parameters[i]).name() << "; should be " << _parameterTypes[i] << endl; + } + if (!*_parameters[i]) { + cerr << __PRETTY_FUNCTION__ << ": FATAL, *_parameters[i] == 0" << endl; + return false; + } + } + return true; + } + + void OptimizableGraph::Edge::setRobustKernel(RobustKernel* ptr) + { + if (_robustKernel) + delete _robustKernel; + _robustKernel = ptr; + } + + bool OptimizableGraph::Edge::resolveCaches() { + return true; + } + + bool OptimizableGraph::Edge::setMeasurementData(const double *) + { + return false; + } + + bool OptimizableGraph::Edge::getMeasurementData(double *) const + { + return false; + } + + int OptimizableGraph::Edge::measurementDimension() const + { + return -1; + } + + bool OptimizableGraph::Edge::setMeasurementFromState(){ + return false; + } + + + OptimizableGraph::Edge* OptimizableGraph::Edge::clone() const + { + // TODO + return 0; + } + + + OptimizableGraph::OptimizableGraph() + { + _nextEdgeId = 0; _edge_has_id = false; + _graphActions.resize(AT_NUM_ELEMENTS); + } + + OptimizableGraph::~OptimizableGraph() + { + clear(); + clearParameters(); + } + + bool OptimizableGraph::addVertex(HyperGraph::Vertex* v, Data* userData) + { + Vertex* inserted = vertex(v->id()); + if (inserted) { + cerr << __FUNCTION__ << ": FATAL, a vertex with ID " << v->id() << " has already been registered with this graph" << endl; + assert(0 && "Vertex with this ID already contained in the graph"); + return false; + } + OptimizableGraph::Vertex* ov=dynamic_cast(v); + assert(ov && "Vertex does not inherit from OptimizableGraph::Vertex"); + if (ov->_graph != 0 && ov->_graph != this) { + cerr << __FUNCTION__ << ": FATAL, vertex with ID " << v->id() << " has already registered with another graph " << ov->_graph << endl; + assert(0 && "Vertex already registered with another graph"); + return false; + } + if (userData) + ov->setUserData(userData); + ov->_graph=this; + return HyperGraph::addVertex(v); + } + + bool OptimizableGraph::addEdge(HyperGraph::Edge* e_) + { + OptimizableGraph::Edge* e = dynamic_cast(e_); + assert(e && "Edge does not inherit from OptimizableGraph::Edge"); + if (! e) + return false; + bool eresult = HyperGraph::addEdge(e); + if (! eresult) + return false; + e->_internalId = _nextEdgeId++; + if (! e->resolveParameters()){ + cerr << __FUNCTION__ << ": FATAL, cannot resolve parameters for edge " << e << endl; + return false; + } + if (! e->resolveCaches()){ + cerr << __FUNCTION__ << ": FATAL, cannot resolve caches for edge " << e << endl; + return false; + } + _jacobianWorkspace.updateSize(e); + + return true; + } + + int OptimizableGraph::optimize(int /*iterations*/, bool /*online*/) {return 0;} + +double OptimizableGraph::chi2() const +{ + double chi = 0.0; + for (OptimizableGraph::EdgeSet::const_iterator it = this->edges().begin(); it != this->edges().end(); ++it) { + const OptimizableGraph::Edge* e = static_cast(*it); + chi += e->chi2(); + } + return chi; +} + +void OptimizableGraph::push() +{ + for (OptimizableGraph::VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + v->push(); + } +} + +void OptimizableGraph::pop() +{ + for (OptimizableGraph::VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) { + OptimizableGraph::Vertex* v= static_cast(it->second); + v->pop(); + } +} + +void OptimizableGraph::discardTop() +{ + for (OptimizableGraph::VertexIDMap::iterator it=_vertices.begin(); it!=_vertices.end(); ++it) { + OptimizableGraph::Vertex* v= static_cast(it->second); + v->discardTop(); + } +} + +void OptimizableGraph::push(HyperGraph::VertexSet& vset) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->push(); + } +} + +void OptimizableGraph::pop(HyperGraph::VertexSet& vset) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->pop(); + } +} + +void OptimizableGraph::discardTop(HyperGraph::VertexSet& vset) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->discardTop(); + } +} + + void OptimizableGraph::setFixed(HyperGraph::VertexSet& vset, bool fixed) +{ + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + v->setFixed(fixed); + } +} + + +bool OptimizableGraph::load(istream& is, bool createEdges) +{ + // scna for the paramers in the whole file + if (!_parameters.read(is,&_renamedTypesLookup)) + return false; +#ifndef NDEBUG + cerr << "Loaded " << _parameters.size() << " parameters" << endl; +#endif + is.clear(); + is.seekg(ios_base::beg); + set warnedUnknownTypes; + stringstream currentLine; + string token; + + Factory* factory = Factory::instance(); + HyperGraph::GraphElemBitset elemBitset; + elemBitset[HyperGraph::HGET_PARAMETER] = 1; + elemBitset.flip(); + + Vertex* previousVertex = 0; + Data* previousData = 0; + + while (1) { + int bytesRead = readLine(is, currentLine); + if (bytesRead == -1) + break; + currentLine >> token; + //cerr << "Token=" << token << endl; + if (bytesRead == 0 || token.size() == 0 || token[0] == '#') + continue; + + // handle commands encoded in the file + bool handledCommand = false; + + if (token == "FIX") { + handledCommand = true; + int id; + while (currentLine >> id) { + OptimizableGraph::Vertex* v = static_cast(vertex(id)); + if (v) { +# ifndef NDEBUG + cerr << "Fixing vertex " << v->id() << endl; +# endif + v->setFixed(true); + } else { + cerr << "Warning: Unable to fix vertex with id " << id << ". Not found in the graph." << endl; + } + } + } + + if (handledCommand) + continue; + + // do the mapping to an internal type if it matches + if (_renamedTypesLookup.size() > 0) { + map::const_iterator foundIt = _renamedTypesLookup.find(token); + if (foundIt != _renamedTypesLookup.end()) { + token = foundIt->second; + } + } + + if (! factory->knowsTag(token)) { + if (warnedUnknownTypes.count(token) != 1) { + warnedUnknownTypes.insert(token); + cerr << CL_RED(__PRETTY_FUNCTION__ << " unknown type: " << token) << endl; + } + continue; + } + + HyperGraph::HyperGraphElement* element = factory->construct(token, elemBitset); + if (dynamic_cast(element)) { // it's a vertex type + //cerr << "it is a vertex" << endl; + previousData = 0; + Vertex* v = static_cast(element); + int id; + currentLine >> id; + bool r = v->read(currentLine); + if (! r) + cerr << __PRETTY_FUNCTION__ << ": Error reading vertex " << token << " " << id << endl; + v->setId(id); + if (!addVertex(v)) { + cerr << __PRETTY_FUNCTION__ << ": Failure adding Vertex, " << token << " " << id << endl; + delete v; + } else { + previousVertex = v; + } + } + else if (dynamic_cast(element)) { + //cerr << "it is an edge" << endl; + previousData = 0; + Edge* e = static_cast(element); + int numV = e->vertices().size(); + if (_edge_has_id){ + int id; + currentLine >> id; + e->setId(id); + } + //cerr << PVAR(token) << " " << PVAR(numV) << endl; + if (numV == 2) { // it's a pairwise / binary edge type which we handle in a special way + int id1, id2; + currentLine >> id1 >> id2; + Vertex* from = vertex(id1); + Vertex* to = vertex(id2); + int doInit=0; + if ((!from || !to) ) { + if (! createEdges) { + cerr << __PRETTY_FUNCTION__ << ": Unable to find vertices for edge " << token << " " << id1 << " <-> " << id2 << endl; + delete e; + } else { + if (! from) { + from=e->createFrom(); + from->setId(id1); + addVertex(from); + doInit=2; + } + if (! to) { + to=e->createTo(); + to->setId(id2); + addVertex(to); + doInit=1; + } + } + } + if (from && to) { + e->setVertex(0, from); + e->setVertex(1, to); + e->read(currentLine); + if (!addEdge(e)) { + cerr << __PRETTY_FUNCTION__ << ": Unable to add edge " << token << " " << id1 << " <-> " << id2 << endl; + delete e; + } else { + switch (doInit){ + case 1: + { + HyperGraph::VertexSet fromSet; + fromSet.insert(from); + e->initialEstimate(fromSet, to); + break; + } + case 2: + { + HyperGraph::VertexSet toSet; + toSet.insert(to); + e->initialEstimate(toSet, from); + break; + } + default:; + } + } + } + } + else { + vector ids; + ids.resize(numV); + for (int l = 0; l < numV; ++l) + currentLine >> ids[l]; + bool vertsOkay = true; + for (int l = 0; l < numV; ++l) { + e->setVertex(l, vertex(ids[l])); + if (e->vertex(l) == 0) { + vertsOkay = false; + break; + } + } + if (! vertsOkay) { + cerr << __PRETTY_FUNCTION__ << ": Unable to find vertices for edge " << token; + for (int l = 0; l < numV; ++l) { + if (l > 0) + cerr << " <->"; + cerr << " " << ids[l]; + } + delete e; + } else { + bool r = e->read(currentLine); + if (!r || !addEdge(e)) { + cerr << __PRETTY_FUNCTION__ << ": Unable to add edge " << token; + for (int l = 0; l < numV; ++l) { + if (l > 0) + cerr << " <->"; + cerr << " " << ids[l]; + } + delete e; + } + } + } + } else if (dynamic_cast(element)) { // reading in the data packet for the vertex + //cerr << "read data packet " << token << " vertex " << previousVertex->id() << endl; + Data* d = static_cast(element); + bool r = d->read(currentLine); + if (! r) { + cerr << __PRETTY_FUNCTION__ << ": Error reading data " << token << " for vertex " << previousVertex->id() << endl; + delete d; + previousData = 0; + } else if (previousData){ + //cerr << "chaining" << endl; + previousData->setNext(d); + previousData = d; + //cerr << "done" << endl; + } else if (previousVertex){ + //cerr << "embedding in vertex" << endl; + previousVertex->setUserData(d); + previousData = d; + previousVertex = 0; + //cerr << "done" << endl; + } else { + cerr << __PRETTY_FUNCTION__ << ": got data element, but no vertex available" << endl; + delete d; + previousData = 0; + } + } + } // while read line + + return true; +} + +bool OptimizableGraph::load(const char* filename, bool createEdges) +{ + ifstream ifs(filename); + if (!ifs) { + cerr << __PRETTY_FUNCTION__ << " unable to open file " << filename << endl; + return false; + } + return load(ifs, createEdges); +} + +bool OptimizableGraph::save(const char* filename, int level) const +{ + ofstream ofs(filename); + if (!ofs) + return false; + return save(ofs, level); +} + +bool OptimizableGraph::save(ostream& os, int level) const +{ + if (! _parameters.write(os)) + return false; + set verticesToSave; + for (HyperGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + if (e->level() == level) { + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + verticesToSave.insert(static_cast(*it)); + } + } + } + + for (set::const_iterator it = verticesToSave.begin(); it != verticesToSave.end(); ++it){ + OptimizableGraph::Vertex* v = *it; + saveVertex(os, v); + } + + EdgeContainer edgesToSave; + for (HyperGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + const OptimizableGraph::Edge* e = dynamic_cast(*it); + if (e->level() == level) + edgesToSave.push_back(const_cast(e)); + } + sort(edgesToSave.begin(), edgesToSave.end(), EdgeIDCompare()); + + for (EdgeContainer::const_iterator it = edgesToSave.begin(); it != edgesToSave.end(); ++it) { + OptimizableGraph::Edge* e = *it; + saveEdge(os, e); + } + + return os.good(); +} + + +bool OptimizableGraph::saveSubset(ostream& os, HyperGraph::VertexSet& vset, int level) +{ + if (! _parameters.write(os)) + return false; + + for (HyperGraph::VertexSet::const_iterator it=vset.begin(); it!=vset.end(); it++){ + OptimizableGraph::Vertex* v = dynamic_cast(*it); + saveVertex(os, v); + } + for (HyperGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + OptimizableGraph::Edge* e = dynamic_cast< OptimizableGraph::Edge*>(*it); + if (e->level() != level) + continue; + + bool verticesInEdge = true; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + if (vset.find(*it) == vset.end()) { + verticesInEdge = false; + break; + } + } + if (! verticesInEdge) + continue; + + saveEdge(os, e); + } + + return os.good(); +} + +bool OptimizableGraph::saveSubset(ostream& os, HyperGraph::EdgeSet& eset) +{ + if (!_parameters.write(os)) + return false; + std::set vset; + for (HyperGraph::EdgeSet::const_iterator it = eset.begin(); it != eset.end(); ++it) { + HyperGraph::Edge* e = *it; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + vset.insert(v); + } + } + + for (std::set::const_iterator it=vset.begin(); it!=vset.end(); ++it){ + OptimizableGraph::Vertex* v = dynamic_cast(*it); + saveVertex(os, v); + } + + for (HyperGraph::EdgeSet::const_iterator it = eset.begin(); it != eset.end(); ++it) { + OptimizableGraph::Edge* e = dynamic_cast< OptimizableGraph::Edge*>(*it); + saveEdge(os, e); + } + + return os.good(); +} + +void OptimizableGraph::addGraph(OptimizableGraph* g){ + for (HyperGraph::VertexIDMap::iterator it=g->vertices().begin(); it!=g->vertices().end(); ++it){ + OptimizableGraph::Vertex* v= (OptimizableGraph::Vertex*)(it->second); + if (vertex(v->id())) + continue; + OptimizableGraph::Vertex* v2=v->clone(); + v2->edges().clear(); + v2->setHessianIndex(-1); + addVertex(v2); + } + for (HyperGraph::EdgeSet::iterator it=g->edges().begin(); it!=g->edges().end(); ++it){ + OptimizableGraph::Edge* e = (OptimizableGraph::Edge*)(*it); + OptimizableGraph::Edge* en = e->clone(); + en->resize(e->vertices().size()); + int cnt = 0; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = (OptimizableGraph::Vertex*) vertex((*it)->id()); + assert(v); + en->setVertex(cnt++, v); + } + addEdge(en); + } +} + +int OptimizableGraph::maxDimension() const{ + int maxDim=0; + for (HyperGraph::VertexIDMap::const_iterator it=vertices().begin(); it!=vertices().end(); ++it){ + const OptimizableGraph::Vertex* v= static_cast< const OptimizableGraph::Vertex*>(it->second); + maxDim = (std::max)(maxDim, v->dimension()); + } + return maxDim; +} + +void OptimizableGraph::setRenamedTypesFromString(const std::string& types) +{ + Factory* factory = Factory::instance(); + vector typesMap = strSplit(types, ","); + for (size_t i = 0; i < typesMap.size(); ++i) { + vector m = strSplit(typesMap[i], "="); + if (m.size() != 2) { + cerr << __PRETTY_FUNCTION__ << ": unable to extract type map from " << typesMap[i] << endl; + continue; + } + string typeInFile = trim(m[0]); + string loadedType = trim(m[1]); + if (! factory->knowsTag(loadedType)) { + cerr << __PRETTY_FUNCTION__ << ": unknown type " << loadedType << endl; + continue; + } + + _renamedTypesLookup[typeInFile] = loadedType; + } + + cerr << "# load look up table" << endl; + for (std::map::const_iterator it = _renamedTypesLookup.begin(); it != _renamedTypesLookup.end(); ++it) { + cerr << "#\t" << it->first << " -> " << it->second << endl; + } +} + +bool OptimizableGraph::isSolverSuitable(const OptimizationAlgorithmProperty& solverProperty, const std::set& vertDims_) const +{ + std::set auxDims; + if (vertDims_.size() == 0) { + auxDims = dimensions(); + } + const set& vertDims = vertDims_.size() == 0 ? auxDims : vertDims_; + bool suitableSolver = true; + if (vertDims.size() == 2) { + if (solverProperty.requiresMarginalize) { + suitableSolver = vertDims.count(solverProperty.poseDim) == 1 && vertDims.count(solverProperty.landmarkDim) == 1; + } + else { + suitableSolver = solverProperty.poseDim == -1; + } + } else if (vertDims.size() == 1) { + suitableSolver = vertDims.count(solverProperty.poseDim) == 1 || solverProperty.poseDim == -1; + } else { + suitableSolver = solverProperty.poseDim == -1 && !solverProperty.requiresMarginalize; + } + return suitableSolver; +} + +std::set OptimizableGraph::dimensions() const +{ + std::set auxDims; + for (VertexIDMap::const_iterator it = vertices().begin(); it != vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + auxDims.insert(v->dimension()); + } + return auxDims; +} + +void OptimizableGraph::preIteration(int iter) +{ + HyperGraphActionSet& actions = _graphActions[AT_PREITERATION]; + if (actions.size() > 0) { + HyperGraphAction::ParametersIteration params(iter); + for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it) { + (*(*it))(this, ¶ms); + } + } +} + +void OptimizableGraph::postIteration(int iter) +{ + HyperGraphActionSet& actions = _graphActions[AT_POSTITERATION]; + if (actions.size() > 0) { + HyperGraphAction::ParametersIteration params(iter); + for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it) { + (*(*it))(this, ¶ms); + } + } +} + +bool OptimizableGraph::addPostIterationAction(HyperGraphAction* action) +{ + std::pair insertResult = _graphActions[AT_POSTITERATION].insert(action); + return insertResult.second; +} + +bool OptimizableGraph::addPreIterationAction(HyperGraphAction* action) +{ + std::pair insertResult = _graphActions[AT_PREITERATION].insert(action); + return insertResult.second; +} + +bool OptimizableGraph::removePreIterationAction(HyperGraphAction* action) +{ + return _graphActions[AT_PREITERATION].erase(action) > 0; +} + +bool OptimizableGraph::removePostIterationAction(HyperGraphAction* action) +{ + return _graphActions[AT_POSTITERATION].erase(action) > 0; +} + +bool OptimizableGraph::saveVertex(std::ostream& os, OptimizableGraph::Vertex* v) const +{ + Factory* factory = Factory::instance(); + string tag = factory->tag(v); + if (tag.size() > 0) { + os << tag << " " << v->id() << " "; + v->write(os); + os << endl; + Data* d=v->userData(); + while (d) { // write the data packet for the vertex + tag = factory->tag(d); + if (tag.size() > 0) { + os << tag << " "; + d->write(os); + os << endl; + } + d=d->next(); + } + if (v->fixed()) { + os << "FIX " << v->id() << endl; + } + return os.good(); + } + return false; +} + +bool OptimizableGraph::saveEdge(std::ostream& os, OptimizableGraph::Edge* e) const +{ + Factory* factory = Factory::instance(); + string tag = factory->tag(e); + if (tag.size() > 0) { + os << tag << " "; + if (_edge_has_id) + os << e->id() << " "; + for (vector::const_iterator it = e->vertices().begin(); it != e->vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(*it); + os << v->id() << " "; + } + e->write(os); + os << endl; + return os.good(); + } + return false; +} + +void OptimizableGraph::clearParameters() +{ + _parameters.clear(); +} + +bool OptimizableGraph::verifyInformationMatrices(bool verbose) const +{ + bool allEdgeOk = true; + SelfAdjointEigenSolver eigenSolver; + for (OptimizableGraph::EdgeSet::const_iterator it = edges().begin(); it != edges().end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + Eigen::MatrixXd::MapType information(e->informationData(), e->dimension(), e->dimension()); + // test on symmetry + bool isSymmetric = information.transpose() == information; + bool okay = isSymmetric; + if (isSymmetric) { + // compute the eigenvalues + eigenSolver.compute(information, Eigen::EigenvaluesOnly); + bool isSPD = eigenSolver.eigenvalues()(0) >= 0.; + okay = okay && isSPD; + } + allEdgeOk = allEdgeOk && okay; + if (! okay) { + if (verbose) { + if (! isSymmetric) + cerr << "Information Matrix for an edge is not symmetric:"; + else + cerr << "Information Matrix for an edge is not SPD:"; + for (size_t i = 0; i < e->vertices().size(); ++i) + cerr << " " << e->vertex(i)->id(); + if (isSymmetric) + cerr << "\teigenvalues: " << eigenSolver.eigenvalues().transpose(); + cerr << endl; + } + } + } + return allEdgeOk; +} + +bool OptimizableGraph::initMultiThreading() +{ +# if (defined G2O_OPENMP) && EIGEN_VERSION_AT_LEAST(3,1,0) + Eigen::initParallel(); +# endif + return true; +} + +} // end namespace + diff --git a/Thirdparty/g2o/g2o/core/optimizable_graph.h b/Thirdparty/g2o/g2o/core/optimizable_graph.h new file mode 100644 index 0000000000..9d9b561cc2 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimizable_graph.h @@ -0,0 +1,688 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_AIS_OPTIMIZABLE_GRAPH_HH_ +#define G2O_AIS_OPTIMIZABLE_GRAPH_HH_ + +#include +#include +#include +#include +#include +#include + +#include "openmp_mutex.h" +#include "hyper_graph.h" +#include "parameter.h" +#include "parameter_container.h" +#include "jacobian_workspace.h" + +#include "../stuff/macros.h" + +namespace g2o { + + class HyperGraphAction; + struct OptimizationAlgorithmProperty; + class Cache; + class CacheContainer; + class RobustKernel; + + /** + @addtogroup g2o + */ + /** + This is an abstract class that represents one optimization + problem. It specializes the general graph to contain special + vertices and edges. The vertices represent parameters that can + be optimized, while the edges represent constraints. This class + also provides basic functionalities to handle the backup/restore + of portions of the vertices. + */ + struct OptimizableGraph : public HyperGraph { + + enum ActionType { + AT_PREITERATION, AT_POSTITERATION, + AT_NUM_ELEMENTS, // keep as last element + }; + + typedef std::set HyperGraphActionSet; + + // forward declarations + class Vertex; + class Edge; + + /** + * \brief data packet for a vertex. Extend this class to store in the vertices + * the potential additional information you need (e.g. images, laser scans, ...). + */ + class Data : public HyperGraph::HyperGraphElement + { + friend struct OptimizableGraph; + public: + virtual ~Data(); + Data(); + //! read the data from a stream + virtual bool read(std::istream& is) = 0; + //! write the data to a stream + virtual bool write(std::ostream& os) const = 0; + virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_DATA;} + const Data* next() const {return _next;} + Data* next() {return _next;} + void setNext(Data* next_) { _next = next_; } + protected: + Data* _next; // linked list of multiple data; + }; + + /** + * \brief order vertices based on their ID + */ + struct VertexIDCompare { + bool operator() (const Vertex* v1, const Vertex* v2) const + { + return v1->id() < v2->id(); + } + }; + + /** + * \brief order edges based on the internal ID, which is assigned to the edge in addEdge() + */ + struct EdgeIDCompare { + bool operator() (const Edge* e1, const Edge* e2) const + { + return e1->internalId() < e2->internalId(); + } + }; + + //! vector container for vertices + typedef std::vector VertexContainer; + //! vector container for edges + typedef std::vector EdgeContainer; + + /** + * \brief A general case Vertex for optimization + */ + class Vertex : public HyperGraph::Vertex { + private: + friend struct OptimizableGraph; + public: + Vertex(); + + //! returns a deep copy of the current vertex + virtual Vertex* clone() const ; + + //! the user data associated with this vertex + const Data* userData() const { return _userData; } + Data* userData() { return _userData; } + + void setUserData(Data* obs) { _userData = obs;} + void addUserData(Data* obs) { + if (obs) { + obs->setNext(_userData); + _userData=obs; + } + } + + virtual ~Vertex(); + + //! sets the node to the origin (used in the multilevel stuff) + void setToOrigin() { setToOriginImpl(); updateCache();} + + //! get the element from the hessian matrix + virtual const double& hessian(int i, int j) const = 0; + virtual double& hessian(int i, int j) = 0; + virtual double hessianDeterminant() const = 0; + virtual double* hessianData() = 0; + + /** maps the internal matrix to some external memory location */ + virtual void mapHessianMemory(double* d) = 0; + + /** + * copies the b vector in the array b_ + * @return the number of elements copied + */ + virtual int copyB(double* b_) const = 0; + + //! get the b vector element + virtual const double& b(int i) const = 0; + virtual double& b(int i) = 0; + //! return a pointer to the b vector associated with this vertex + virtual double* bData() = 0; + + /** + * set the b vector part of this vertex to zero + */ + virtual void clearQuadraticForm() = 0; + + /** + * updates the current vertex with the direct solution x += H_ii\b_ii + * @return the determinant of the inverted hessian + */ + virtual double solveDirect(double lambda=0) = 0; + + /** + * sets the initial estimate from an array of double + * Implement setEstimateDataImpl() + * @return true on success + */ + bool setEstimateData(const double* estimate); + + /** + * sets the initial estimate from an array of double + * Implement setEstimateDataImpl() + * @return true on success + */ + bool setEstimateData(const std::vector& estimate) { +#ifndef NDEBUG + int dim = estimateDimension(); + assert((dim == -1) || (estimate.size() == std::size_t(dim))); +#endif + return setEstimateData(&estimate[0]); + }; + + /** + * writes the estimater to an array of double + * @returns true on success + */ + virtual bool getEstimateData(double* estimate) const; + + /** + * writes the estimater to an array of double + * @returns true on success + */ + virtual bool getEstimateData(std::vector& estimate) const { + int dim = estimateDimension(); + if (dim < 0) + return false; + estimate.resize(dim); + return getEstimateData(&estimate[0]); + }; + + /** + * returns the dimension of the extended representation used by get/setEstimate(double*) + * -1 if it is not supported + */ + virtual int estimateDimension() const; + + /** + * sets the initial estimate from an array of double. + * Implement setMinimalEstimateDataImpl() + * @return true on success + */ + bool setMinimalEstimateData(const double* estimate); + + /** + * sets the initial estimate from an array of double. + * Implement setMinimalEstimateDataImpl() + * @return true on success + */ + bool setMinimalEstimateData(const std::vector& estimate) { +#ifndef NDEBUG + int dim = minimalEstimateDimension(); + assert((dim == -1) || (estimate.size() == std::size_t(dim))); +#endif + return setMinimalEstimateData(&estimate[0]); + }; + + /** + * writes the estimate to an array of double + * @returns true on success + */ + virtual bool getMinimalEstimateData(double* estimate) const ; + + /** + * writes the estimate to an array of double + * @returns true on success + */ + virtual bool getMinimalEstimateData(std::vector& estimate) const { + int dim = minimalEstimateDimension(); + if (dim < 0) + return false; + estimate.resize(dim); + return getMinimalEstimateData(&estimate[0]); + }; + + /** + * returns the dimension of the extended representation used by get/setEstimate(double*) + * -1 if it is not supported + */ + virtual int minimalEstimateDimension() const; + + //! backup the position of the vertex to a stack + virtual void push() = 0; + + //! restore the position of the vertex by retrieving the position from the stack + virtual void pop() = 0; + + //! pop the last element from the stack, without restoring the current estimate + virtual void discardTop() = 0; + + //! return the stack size + virtual int stackSize() const = 0; + + /** + * Update the position of the node from the parameters in v. + * Depends on the implementation of oplusImpl in derived classes to actually carry + * out the update. + * Will also call updateCache() to update the caches of depending on the vertex. + */ + void oplus(const double* v) + { + oplusImpl(v); + updateCache(); + } + + //! temporary index of this node in the parameter vector obtained from linearization + int hessianIndex() const { return _hessianIndex;} + int G2O_ATTRIBUTE_DEPRECATED(tempIndex() const) { return hessianIndex();} + //! set the temporary index of the vertex in the parameter blocks + void setHessianIndex(int ti) { _hessianIndex = ti;} + void G2O_ATTRIBUTE_DEPRECATED(setTempIndex(int ti)) { setHessianIndex(ti);} + + //! true => this node is fixed during the optimization + bool fixed() const {return _fixed;} + //! true => this node should be considered fixed during the optimization + void setFixed(bool fixed) { _fixed = fixed;} + + //! true => this node is marginalized out during the optimization + bool marginalized() const {return _marginalized;} + //! true => this node should be marginalized out during the optimization + void setMarginalized(bool marginalized) { _marginalized = marginalized;} + + //! dimension of the estimated state belonging to this node + int dimension() const { return _dimension;} + + //! sets the id of the node in the graph be sure that the graph keeps consistent after changing the id + virtual void setId(int id) {_id = id;} + + //! set the row of this vertex in the Hessian + void setColInHessian(int c) { _colInHessian = c;} + //! get the row of this vertex in the Hessian + int colInHessian() const {return _colInHessian;} + + const OptimizableGraph* graph() const {return _graph;} + + OptimizableGraph* graph() {return _graph;} + + /** + * lock for the block of the hessian and the b vector associated with this vertex, to avoid + * race-conditions if multi-threaded. + */ + void lockQuadraticForm() { _quadraticFormMutex.lock();} + /** + * unlock the block of the hessian and the b vector associated with this vertex + */ + void unlockQuadraticForm() { _quadraticFormMutex.unlock();} + + //! read the vertex from a stream, i.e., the internal state of the vertex + virtual bool read(std::istream& is) = 0; + //! write the vertex to a stream + virtual bool write(std::ostream& os) const = 0; + + virtual void updateCache(); + + CacheContainer* cacheContainer(); + protected: + OptimizableGraph* _graph; + Data* _userData; + int _hessianIndex; + bool _fixed; + bool _marginalized; + int _dimension; + int _colInHessian; + OpenMPMutex _quadraticFormMutex; + + CacheContainer* _cacheContainer; + + /** + * update the position of the node from the parameters in v. + * Implement in your class! + */ + virtual void oplusImpl(const double* v) = 0; + + //! sets the node to the origin (used in the multilevel stuff) + virtual void setToOriginImpl() = 0; + + /** + * writes the estimater to an array of double + * @returns true on success + */ + virtual bool setEstimateDataImpl(const double* ) { return false;} + + /** + * sets the initial estimate from an array of double + * @return true on success + */ + virtual bool setMinimalEstimateDataImpl(const double* ) { return false;} + + }; + + class Edge: public HyperGraph::Edge { + private: + friend struct OptimizableGraph; + public: + Edge(); + virtual ~Edge(); + virtual Edge* clone() const; + + // indicates if all vertices are fixed + virtual bool allVerticesFixed() const = 0; + + // computes the error of the edge and stores it in an internal structure + virtual void computeError() = 0; + + //! sets the measurement from an array of double + //! @returns true on success + virtual bool setMeasurementData(const double* m); + + //! writes the measurement to an array of double + //! @returns true on success + virtual bool getMeasurementData(double* m) const; + + //! returns the dimension of the measurement in the extended representation which is used + //! by get/setMeasurement; + virtual int measurementDimension() const; + + /** + * sets the estimate to have a zero error, based on the current value of the state variables + * returns false if not supported. + */ + virtual bool setMeasurementFromState(); + + //! if NOT NULL, error of this edge will be robustifed with the kernel + RobustKernel* robustKernel() const { return _robustKernel;} + /** + * specify the robust kernel to be used in this edge + */ + void setRobustKernel(RobustKernel* ptr); + + //! returns the error vector cached after calling the computeError; + virtual const double* errorData() const = 0; + virtual double* errorData() = 0; + + //! returns the memory of the information matrix, usable for example with a Eigen::Map + virtual const double* informationData() const = 0; + virtual double* informationData() = 0; + + //! computes the chi2 based on the cached error value, only valid after computeError has been called. + virtual double chi2() const = 0; + + /** + * Linearizes the constraint in the edge. + * Makes side effect on the vertices of the graph by changing + * the parameter vector b and the hessian blocks ii and jj. + * The off diagoinal block is accesed via _hessian. + */ + virtual void constructQuadraticForm() = 0; + + /** + * maps the internal matrix to some external memory location, + * you need to provide the memory before calling constructQuadraticForm + * @param d the memory location to which we map + * @param i index of the vertex i + * @param j index of the vertex j (j > i, upper triangular fashion) + * @param rowMajor if true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed + */ + virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor) = 0; + + /** + * Linearizes the constraint in the edge in the manifold space, and store + * the result in the given workspace + */ + virtual void linearizeOplus(JacobianWorkspace& jacobianWorkspace) = 0; + + /** set the estimate of the to vertex, based on the estimate of the from vertices in the edge. */ + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) = 0; + + /** + * override in your class if it's possible to initialize the vertices in certain combinations. + * The return value may correspond to the cost for initiliaizng the vertex but should be positive if + * the initialization is possible and negative if not possible. + */ + virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) { (void) from; (void) to; return -1.;} + + //! returns the level of the edge + int level() const { return _level;} + //! sets the level of the edge + void setLevel(int l) { _level=l;} + + //! returns the dimensions of the error function + int dimension() const { return _dimension;} + + virtual Vertex* createFrom() {return 0;} + virtual Vertex* createTo() {return 0;} + + //! read the vertex from a stream, i.e., the internal state of the vertex + virtual bool read(std::istream& is) = 0; + //! write the vertex to a stream + virtual bool write(std::ostream& os) const = 0; + + //! the internal ID of the edge + long long internalId() const { return _internalId;} + + OptimizableGraph* graph(); + const OptimizableGraph* graph() const; + + bool setParameterId(int argNum, int paramId); + inline const Parameter* parameter(int argNo) const {return *_parameters.at(argNo);} + inline size_t numParameters() const {return _parameters.size();} + inline void resizeParameters(size_t newSize) { + _parameters.resize(newSize, 0); + _parameterIds.resize(newSize, -1); + _parameterTypes.resize(newSize, typeid(void*).name()); + } + protected: + int _dimension; + int _level; + RobustKernel* _robustKernel; + long long _internalId; + + std::vector _cacheIds; + + template + bool installParameter(ParameterType*& p, size_t argNo, int paramId=-1){ + if (argNo>=_parameters.size()) + return false; + _parameterIds[argNo] = paramId; + _parameters[argNo] = (Parameter**)&p; + _parameterTypes[argNo] = typeid(ParameterType).name(); + return true; + } + + template + void resolveCache(CacheType*& cache, OptimizableGraph::Vertex*, + const std::string& _type, + const ParameterVector& parameters); + + bool resolveParameters(); + virtual bool resolveCaches(); + + std::vector _parameterTypes; + std::vector _parameters; + std::vector _parameterIds; + }; + + //! returns the vertex number id appropriately casted + inline Vertex* vertex(int id) { return reinterpret_cast(HyperGraph::vertex(id));} + + //! returns the vertex number id appropriately casted + inline const Vertex* vertex (int id) const{ return reinterpret_cast(HyperGraph::vertex(id));} + + //! empty constructor + OptimizableGraph(); + virtual ~OptimizableGraph(); + + //! adds all edges and vertices of the graph g to this graph. + void addGraph(OptimizableGraph* g); + + /** + * adds a new vertex. The new vertex is then "taken". + * @return false if a vertex with the same id as v is already in the graph, true otherwise. + */ + virtual bool addVertex(HyperGraph::Vertex* v, Data* userData); + virtual bool addVertex(HyperGraph::Vertex* v) { return addVertex(v, 0);} + + /** + * adds a new edge. + * The edge should point to the vertices that it is connecting (setFrom/setTo). + * @return false if the insertion does not work (incompatible types of the vertices/missing vertex). true otherwise. + */ + virtual bool addEdge(HyperGraph::Edge* e); + + //! returns the chi2 of the current configuration + double chi2() const; + + //! return the maximum dimension of all vertices in the graph + int maxDimension() const; + + /** + * iterates over all vertices and returns a set of all the vertex dimensions in the graph + */ + std::set dimensions() const; + + /** + * carry out n iterations + * @return the number of performed iterations + */ + virtual int optimize(int iterations, bool online=false); + + //! called at the beginning of an iteration (argument is the number of the iteration) + virtual void preIteration(int); + //! called at the end of an iteration (argument is the number of the iteration) + virtual void postIteration(int); + + //! add an action to be executed before each iteration + bool addPreIterationAction(HyperGraphAction* action); + //! add an action to be executed after each iteration + bool addPostIterationAction(HyperGraphAction* action); + + //! remove an action that should no longer be execured before each iteration + bool removePreIterationAction(HyperGraphAction* action); + //! remove an action that should no longer be execured after each iteration + bool removePostIterationAction(HyperGraphAction* action); + + //! push the estimate of all variables onto a stack + virtual void push(); + //! pop (restore) the estimate of all variables from the stack + virtual void pop(); + //! discard the last backup of the estimate for all variables by removing it from the stack + virtual void discardTop(); + + //! load the graph from a stream. Uses the Factory singleton for creating the vertices and edges. + virtual bool load(std::istream& is, bool createEdges=true); + bool load(const char* filename, bool createEdges=true); + //! save the graph to a stream. Again uses the Factory system. + virtual bool save(std::ostream& os, int level = 0) const; + //! function provided for convenience, see save() above + bool save(const char* filename, int level = 0) const; + + + //! save a subgraph to a stream. Again uses the Factory system. + bool saveSubset(std::ostream& os, HyperGraph::VertexSet& vset, int level = 0); + + //! save a subgraph to a stream. Again uses the Factory system. + bool saveSubset(std::ostream& os, HyperGraph::EdgeSet& eset); + + //! push the estimate of a subset of the variables onto a stack + virtual void push(HyperGraph::VertexSet& vset); + //! pop (restore) the estimate a subset of the variables from the stack + virtual void pop(HyperGraph::VertexSet& vset); + //! ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate + virtual void discardTop(HyperGraph::VertexSet& vset); + + //! fixes/releases a set of vertices + virtual void setFixed(HyperGraph::VertexSet& vset, bool fixed); + + /** + * set the renamed types lookup from a string, format is for example: + * VERTEX_CAM=VERTEX_SE3:EXPMAP,EDGE_PROJECT_P2MC=EDGE_PROJECT_XYZ:EXPMAP + * This will change the occurance of VERTEX_CAM in the file to VERTEX_SE3:EXPMAP + */ + void setRenamedTypesFromString(const std::string& types); + + /** + * test whether a solver is suitable for optimizing this graph. + * @param solverProperty the solver property to evaluate. + * @param vertDims should equal to the set returned by dimensions() to avoid re-evaluating. + */ + bool isSolverSuitable(const OptimizationAlgorithmProperty& solverProperty, const std::set& vertDims = std::set()) const; + + /** + * remove the parameters of the graph + */ + virtual void clearParameters(); + + bool addParameter(Parameter* p) { + return _parameters.addParameter(p); + } + + Parameter* parameter(int id) { + return _parameters.getParameter(id); + } + + /** + * verify that all the information of the edges are semi positive definite, i.e., + * all Eigenvalues are >= 0. + * @param verbose output edges with not PSD information matrix on cerr + * @return true if all edges have PSD information matrix + */ + bool verifyInformationMatrices(bool verbose = false) const; + + // helper functions to save an individual vertex + bool saveVertex(std::ostream& os, Vertex* v) const; + + // helper functions to save an individual edge + bool saveEdge(std::ostream& os, Edge* e) const; + //! the workspace for storing the Jacobians of the graph + JacobianWorkspace& jacobianWorkspace() { return _jacobianWorkspace;} + const JacobianWorkspace& jacobianWorkspace() const { return _jacobianWorkspace;} + + /** + * Eigen starting from version 3.1 requires that we call an initialize + * function, if we perform calls to Eigen from several threads. + * Currently, this function calls Eigen::initParallel if g2o is compiled + * with OpenMP support and Eigen's version is at least 3.1 + */ + static bool initMultiThreading(); + + protected: + std::map _renamedTypesLookup; + long long _nextEdgeId; + std::vector _graphActions; + + // do not watch this. To be removed soon, or integrated in a nice way + bool _edge_has_id; + + ParameterContainer _parameters; + JacobianWorkspace _jacobianWorkspace; + }; + + /** + @} + */ + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp b/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp new file mode 100644 index 0000000000..0888176ff5 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm.cpp @@ -0,0 +1,62 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "optimization_algorithm.h" + +using namespace std; + +namespace g2o { + +OptimizationAlgorithm::OptimizationAlgorithm() : + _optimizer(0) +{ +} + +OptimizationAlgorithm::~OptimizationAlgorithm() +{ +} + +void OptimizationAlgorithm::printProperties(std::ostream& os) const +{ + os << "------------- Algorithm Properties -------------" << endl; + for (PropertyMap::const_iterator it = _properties.begin(); it != _properties.end(); ++it) { + BaseProperty* p = it->second; + os << it->first << "\t" << p->toString() << endl; + } + os << "------------------------------------------------" << endl; +} + +bool OptimizationAlgorithm::updatePropertiesFromString(const std::string& propString) +{ + return _properties.updateMapFromString(propString); +} + +void OptimizationAlgorithm::setOptimizer(SparseOptimizer* optimizer) +{ + _optimizer = optimizer; +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm.h b/Thirdparty/g2o/g2o/core/optimization_algorithm.h new file mode 100644 index 0000000000..470a4501aa --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm.h @@ -0,0 +1,117 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_H +#define G2O_OPTIMIZATION_ALGORITHM_H + +#include +#include +#include + +#include "../stuff/property.h" + +#include "hyper_graph.h" +#include "sparse_block_matrix.h" + +namespace g2o { + + class SparseOptimizer; + + /** + * \brief Generic interface for a non-linear solver operating on a graph + */ + class OptimizationAlgorithm + { + public: + enum SolverResult {Terminate=2, OK=1, Fail=-1}; + OptimizationAlgorithm(); + virtual ~OptimizationAlgorithm(); + + /** + * initialize the solver, called once before the first call to solve() + */ + virtual bool init(bool online = false) = 0; + + /** + * Solve one iteration. The SparseOptimizer running on-top will call this + * for the given number of iterations. + * @param iteration indicates the current iteration + */ + virtual SolverResult solve(int iteration, bool online = false) = 0; + + /** + * computes the block diagonal elements of the pattern specified in the input + * and stores them in given SparseBlockMatrix. + * If your solver does not support computing the marginals, return false. + */ + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) = 0; + + /** + * update the structures for online processing + */ + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) = 0; + + /** + * called by the optimizer if verbose. re-implement, if you want to print something + */ + virtual void printVerbose(std::ostream& os) const {(void) os;}; + + public: + //! return the optimizer operating on + const SparseOptimizer* optimizer() const { return _optimizer;} + SparseOptimizer* optimizer() { return _optimizer;} + + /** + * specify on which optimizer the solver should work on + */ + void setOptimizer(SparseOptimizer* optimizer); + + //! return the properties of the solver + const PropertyMap& properties() const { return _properties;} + + /** + * update the properties from a string, see PropertyMap::updateMapFromString() + */ + bool updatePropertiesFromString(const std::string& propString); + + /** + * print the properties to a stream in a human readable fashion + */ + void printProperties(std::ostream& os) const; + + protected: + SparseOptimizer* _optimizer; ///< the optimizer the solver is working on + PropertyMap _properties; ///< the properties of your solver, use this to store the parameters of your solver + + private: + // Disable the copy constructor and assignment operator + OptimizationAlgorithm(const OptimizationAlgorithm&) { } + OptimizationAlgorithm& operator= (const OptimizationAlgorithm&) { return *this; } + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.cpp b/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.cpp new file mode 100644 index 0000000000..f63e0718a8 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.cpp @@ -0,0 +1,229 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "optimization_algorithm_dogleg.h" + +#include + +#include "../stuff/timeutil.h" + +#include "block_solver.h" +#include "sparse_optimizer.h" +#include "solver.h" +#include "batch_stats.h" +using namespace std; + +namespace g2o { + + OptimizationAlgorithmDogleg::OptimizationAlgorithmDogleg(BlockSolverBase* solver) : + OptimizationAlgorithmWithHessian(solver) + { + _userDeltaInit = _properties.makeProperty >("initialDelta", 1e4); + _maxTrialsAfterFailure = _properties.makeProperty >("maxTrialsAfterFailure", 100); + _initialLambda = _properties.makeProperty >("initialLambda", 1e-7); + _lamdbaFactor = _properties.makeProperty >("lambdaFactor", 10.); + _delta = _userDeltaInit->value(); + _lastStep = STEP_UNDEFINED; + _wasPDInAllIterations = true; + } + + OptimizationAlgorithmDogleg::~OptimizationAlgorithmDogleg() + { + } + + OptimizationAlgorithm::SolverResult OptimizationAlgorithmDogleg::solve(int iteration, bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph"); + assert(dynamic_cast(_solver) && "underlying linear solver is not a block solver"); + + BlockSolverBase* blockSolver = static_cast(_solver); + + if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure + bool ok = _solver->buildStructure(); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl; + return OptimizationAlgorithm::Fail; + } + + // init some members to the current size of the problem + _hsd.resize(_solver->vectorSize()); + _hdl.resize(_solver->vectorSize()); + _auxVector.resize(_solver->vectorSize()); + _delta = _userDeltaInit->value(); + _currentLambda = _initialLambda->value(); + _wasPDInAllIterations = true; + } + + double t=get_monotonic_time(); + _optimizer->computeActiveErrors(); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeResiduals = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + double currentChi = _optimizer->activeRobustChi2(); + + _solver->buildSystem(); + if (globalStats) { + globalStats->timeQuadraticForm = get_monotonic_time()-t; + } + + Eigen::VectorXd::ConstMapType b(_solver->b(), _solver->vectorSize()); + + // compute alpha + _auxVector.setZero(); + blockSolver->multiplyHessian(_auxVector.data(), _solver->b()); + double bNormSquared = b.squaredNorm(); + double alpha = bNormSquared / _auxVector.dot(b); + + _hsd = alpha * b; + double hsdNorm = _hsd.norm(); + double hgnNorm = -1.; + + bool solvedGaussNewton = false; + bool goodStep = false; + int& numTries = _lastNumTries; + numTries = 0; + do { + ++numTries; + + if (! solvedGaussNewton) { + const double minLambda = 1e-12; + const double maxLambda = 1e3; + solvedGaussNewton = true; + // apply a damping factor to enforce positive definite Hessian, if the matrix appeared + // to be not positive definite in at least one iteration before. + // We apply a damping factor to obtain a PD matrix. + bool solverOk = false; + while(!solverOk) { + if (! _wasPDInAllIterations) + _solver->setLambda(_currentLambda, true); // add _currentLambda to the diagonal + solverOk = _solver->solve(); + if (! _wasPDInAllIterations) + _solver->restoreDiagonal(); + _wasPDInAllIterations = _wasPDInAllIterations && solverOk; + if (! _wasPDInAllIterations) { + // simple strategy to control the damping factor + if (solverOk) { + _currentLambda = std::max(minLambda, _currentLambda / (0.5 * _lamdbaFactor->value())); + } else { + _currentLambda *= _lamdbaFactor->value(); + if (_currentLambda > maxLambda) { + _currentLambda = maxLambda; + return Fail; + } + } + } + } + if (!solverOk) { + return Fail; + } + hgnNorm = Eigen::VectorXd::ConstMapType(_solver->x(), _solver->vectorSize()).norm(); + } + + Eigen::VectorXd::ConstMapType hgn(_solver->x(), _solver->vectorSize()); + assert(hgnNorm >= 0. && "Norm of the GN step is not computed"); + + if (hgnNorm < _delta) { + _hdl = hgn; + _lastStep = STEP_GN; + } + else if (hsdNorm > _delta) { + _hdl = _delta / hsdNorm * _hsd; + _lastStep = STEP_SD; + } else { + _auxVector = hgn - _hsd; // b - a + double c = _hsd.dot(_auxVector); + double bmaSquaredNorm = _auxVector.squaredNorm(); + double beta; + if (c <= 0.) + beta = (-c + sqrt(c*c + bmaSquaredNorm * (_delta*_delta - _hsd.squaredNorm()))) / bmaSquaredNorm; + else { + double hsdSqrNorm = _hsd.squaredNorm(); + beta = (_delta*_delta - hsdSqrNorm) / (c + sqrt(c*c + bmaSquaredNorm * (_delta*_delta - hsdSqrNorm))); + } + assert(beta > 0. && beta < 1 && "Error while computing beta"); + _hdl = _hsd + beta * (hgn - _hsd); + _lastStep = STEP_DL; + assert(_hdl.norm() < _delta + 1e-5 && "Computed step does not correspond to the trust region"); + } + + // compute the linear gain + _auxVector.setZero(); + blockSolver->multiplyHessian(_auxVector.data(), _hdl.data()); + double linearGain = -1 * (_auxVector.dot(_hdl)) + 2 * (b.dot(_hdl)); + + // apply the update and see what happens + _optimizer->push(); + _optimizer->update(_hdl.data()); + _optimizer->computeActiveErrors(); + double newChi = _optimizer-> activeRobustChi2(); + double nonLinearGain = currentChi - newChi; + if (fabs(linearGain) < 1e-12) + linearGain = 1e-12; + double rho = nonLinearGain / linearGain; + //cerr << PVAR(nonLinearGain) << " " << PVAR(linearGain) << " " << PVAR(rho) << endl; + if (rho > 0) { // step is good and will be accepted + _optimizer->discardTop(); + goodStep = true; + } else { // recover previous state + _optimizer->pop(); + } + + // update trust region based on the step quality + if (rho > 0.75) + _delta = std::max(_delta, 3. * _hdl.norm()); + else if (rho < 0.25) + _delta *= 0.5; + } while (!goodStep && numTries < _maxTrialsAfterFailure->value()); + if (numTries == _maxTrialsAfterFailure->value() || !goodStep) + return Terminate; + return OK; + } + + void OptimizationAlgorithmDogleg::printVerbose(std::ostream& os) const + { + os + << "\t Delta= " << _delta + << "\t step= " << stepType2Str(_lastStep) + << "\t tries= " << _lastNumTries; + if (! _wasPDInAllIterations) + os << "\t lambda= " << _currentLambda; + } + + const char* OptimizationAlgorithmDogleg::stepType2Str(int stepType) + { + switch (stepType) { + case STEP_SD: return "Descent"; + case STEP_GN: return "GN"; + case STEP_DL: return "Dogleg"; + default: return "Undefined"; + } + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.h b/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.h new file mode 100644 index 0000000000..e49761ca05 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_dogleg.h @@ -0,0 +1,89 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_DOGLEG_H +#define G2O_OPTIMIZATION_ALGORITHM_DOGLEG_H + +#include "optimization_algorithm_with_hessian.h" + +namespace g2o { + + class BlockSolverBase; + + /** + * \brief Implementation of Powell's Dogleg Algorithm + */ + class OptimizationAlgorithmDogleg : public OptimizationAlgorithmWithHessian + { + public: + /** \brief type of the step to take */ + enum { + STEP_UNDEFINED, + STEP_SD, STEP_GN, STEP_DL + }; + + public: + /** + * construct the Dogleg algorithm, which will use the given Solver for solving the + * linearized system. + */ + explicit OptimizationAlgorithmDogleg(BlockSolverBase* solver); + virtual ~OptimizationAlgorithmDogleg(); + + virtual SolverResult solve(int iteration, bool online = false); + + virtual void printVerbose(std::ostream& os) const; + + //! return the type of the last step taken by the algorithm + int lastStep() const { return _lastStep;} + //! return the diameter of the trust region + double trustRegion() const { return _delta;} + + //! convert the type into an integer + static const char* stepType2Str(int stepType); + + protected: + // parameters + Property* _maxTrialsAfterFailure; + Property* _userDeltaInit; + // damping to enforce positive definite matrix + Property* _initialLambda; + Property* _lamdbaFactor; + + Eigen::VectorXd _hsd; ///< steepest decent step + Eigen::VectorXd _hdl; ///< final dogleg step + Eigen::VectorXd _auxVector; ///< auxilary vector used to perform multiplications or other stuff + + double _currentLambda; ///< the damping factor to force positive definite matrix + double _delta; ///< trust region + int _lastStep; ///< type of the step taken by the algorithm + bool _wasPDInAllIterations; ///< the matrix we solve was positive definite in all iterations -> if not apply damping + int _lastNumTries; + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp b/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp new file mode 100644 index 0000000000..a9be96e834 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.cpp @@ -0,0 +1,137 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "optimization_algorithm_factory.h" + +#include +#include +#include + +using namespace std; + +namespace g2o { + + AbstractOptimizationAlgorithmCreator::AbstractOptimizationAlgorithmCreator(const OptimizationAlgorithmProperty& p) : + _property(p) + { + } + + OptimizationAlgorithmFactory* OptimizationAlgorithmFactory::factoryInstance = 0; + + OptimizationAlgorithmFactory::OptimizationAlgorithmFactory() + { + } + + OptimizationAlgorithmFactory::~OptimizationAlgorithmFactory() + { + for (CreatorList::iterator it = _creator.begin(); it != _creator.end(); ++it) + delete *it; + } + + OptimizationAlgorithmFactory* OptimizationAlgorithmFactory::instance() + { + if (factoryInstance == 0) { + factoryInstance = new OptimizationAlgorithmFactory; + } + return factoryInstance; + } + + void OptimizationAlgorithmFactory::registerSolver(AbstractOptimizationAlgorithmCreator* c) + { + const string& name = c->property().name; + CreatorList::iterator foundIt = findSolver(name); + if (foundIt != _creator.end()) { + _creator.erase(foundIt); + cerr << "SOLVER FACTORY WARNING: Overwriting Solver creator " << name << endl; + assert(0); + } + _creator.push_back(c); + } + + void OptimizationAlgorithmFactory::unregisterSolver(AbstractOptimizationAlgorithmCreator* c) + { + const string& name = c->property().name; + CreatorList::iterator foundIt = findSolver(name); + if (foundIt != _creator.end()) { + delete *foundIt; + _creator.erase(foundIt); + } + } + + OptimizationAlgorithm* OptimizationAlgorithmFactory::construct(const std::string& name, OptimizationAlgorithmProperty& solverProperty) const + { + CreatorList::const_iterator foundIt = findSolver(name); + if (foundIt != _creator.end()) { + solverProperty = (*foundIt)->property(); + return (*foundIt)->construct(); + } + cerr << "SOLVER FACTORY WARNING: Unable to create solver " << name << endl; + return 0; + } + + void OptimizationAlgorithmFactory::destroy() + { + delete factoryInstance; + factoryInstance = 0; + } + + void OptimizationAlgorithmFactory::listSolvers(std::ostream& os) const + { + size_t solverNameColumnLength = 0; + for (CreatorList::const_iterator it = _creator.begin(); it != _creator.end(); ++it) + solverNameColumnLength = std::max(solverNameColumnLength, (*it)->property().name.size()); + solverNameColumnLength += 4; + + for (CreatorList::const_iterator it = _creator.begin(); it != _creator.end(); ++it) { + const OptimizationAlgorithmProperty& sp = (*it)->property(); + os << sp.name; + for (size_t i = sp.name.size(); i < solverNameColumnLength; ++i) + os << ' '; + os << sp.desc << endl; + } + } + + OptimizationAlgorithmFactory::CreatorList::const_iterator OptimizationAlgorithmFactory::findSolver(const std::string& name) const + { + for (CreatorList::const_iterator it = _creator.begin(); it != _creator.end(); ++it) { + const OptimizationAlgorithmProperty& sp = (*it)->property(); + if (sp.name == name) + return it; + } + return _creator.end(); + } + + OptimizationAlgorithmFactory::CreatorList::iterator OptimizationAlgorithmFactory::findSolver(const std::string& name) + { + for (CreatorList::iterator it = _creator.begin(); it != _creator.end(); ++it) { + const OptimizationAlgorithmProperty& sp = (*it)->property(); + if (sp.name == name) + return it; + } + return _creator.end(); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h b/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h new file mode 100644 index 0000000000..b8bf26e78e --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_factory.h @@ -0,0 +1,167 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPTMIZATION_ALGORITHM_PROPERTY_H +#define G2O_OPTMIZATION_ALGORITHM_PROPERTY_H + +#include "../../config.h" +#include "../stuff/misc.h" +#include "optimization_algorithm_property.h" + +#include +#include +#include + + +// define to get some verbose output +//#define G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY + +namespace g2o { + + // forward decl + class OptimizationAlgorithm; + class SparseOptimizer; + + /** + * \brief base for allocating an optimization algorithm + * + * Allocating a solver for a given optimizer. The method construct() has to be + * implemented in your derived class to allocate the desired solver. + */ + class AbstractOptimizationAlgorithmCreator + { + public: + AbstractOptimizationAlgorithmCreator(const OptimizationAlgorithmProperty& p); + virtual ~AbstractOptimizationAlgorithmCreator() { } + //! allocate a solver operating on optimizer, re-implement for your creator + virtual OptimizationAlgorithm* construct() = 0; + //! return the properties of the solver + const OptimizationAlgorithmProperty& property() const { return _property;} + protected: + OptimizationAlgorithmProperty _property; + }; + + /** + * \brief create solvers based on their short name + * + * Factory to allocate solvers based on their short name. + * The Factory is implemented as a sigleton and the single + * instance can be accessed via the instance() function. + */ + class OptimizationAlgorithmFactory + { + public: + typedef std::list CreatorList; + + //! return the instance + static OptimizationAlgorithmFactory* instance(); + + //! free the instance + static void destroy(); + + /** + * register a specific creator for allocating a solver + */ + void registerSolver(AbstractOptimizationAlgorithmCreator* c); + + /** + * unregister a specific creator for allocating a solver + */ + void unregisterSolver(AbstractOptimizationAlgorithmCreator* c); + + /** + * construct a solver based on its name, e.g., var, fix3_2_cholmod + */ + OptimizationAlgorithm* construct(const std::string& tag, OptimizationAlgorithmProperty& solverProperty) const; + + //! list the known solvers into a stream + void listSolvers(std::ostream& os) const; + + //! return the underlying list of creators + const CreatorList& creatorList() const { return _creator;} + + protected: + OptimizationAlgorithmFactory(); + ~OptimizationAlgorithmFactory(); + + CreatorList _creator; + + CreatorList::const_iterator findSolver(const std::string& name) const; + CreatorList::iterator findSolver(const std::string& name); + + private: + static OptimizationAlgorithmFactory* factoryInstance; + }; + + class RegisterOptimizationAlgorithmProxy + { + public: + RegisterOptimizationAlgorithmProxy(AbstractOptimizationAlgorithmCreator* c) + { + _creator = c; +#ifdef G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY + std::cout << __FUNCTION__ << ": Registering " << _creator->property().name << " of type " << typeid(*_creator).name() << std::endl; +#endif + OptimizationAlgorithmFactory::instance()->registerSolver(c); + } + + ~RegisterOptimizationAlgorithmProxy() + { +#ifdef G2O_DEBUG_OPTIMIZATION_ALGORITHM_FACTORY + std::cout << __FUNCTION__ << ": Unregistering " << _creator->property().name << std::endl; +#endif + OptimizationAlgorithmFactory::instance()->unregisterSolver(_creator); + } + private: + AbstractOptimizationAlgorithmCreator* _creator; + }; + +} + +#if defined _MSC_VER && defined G2O_SHARED_LIBS +# define G2O_OAF_EXPORT __declspec(dllexport) +# define G2O_OAF_IMPORT __declspec(dllimport) +#else +# define G2O_OAF_EXPORT +# define G2O_OAF_IMPORT +#endif + +#define G2O_REGISTER_OPTIMIZATION_LIBRARY(libraryname) \ + extern "C" void G2O_OAF_EXPORT g2o_optimization_library_##libraryname(void) {} + +#define G2O_USE_OPTIMIZATION_LIBRARY(libraryname) \ + extern "C" void G2O_OAF_IMPORT g2o_optimization_library_##libraryname(void); \ + static g2o::ForceLinker g2o_force_optimization_algorithm_library_##libraryname(g2o_optimization_library_##libraryname); + +#define G2O_REGISTER_OPTIMIZATION_ALGORITHM(optimizername, instance) \ + extern "C" void G2O_OAF_EXPORT g2o_optimization_algorithm_##optimizername(void) {} \ + static g2o::RegisterOptimizationAlgorithmProxy g_optimization_algorithm_proxy_##optimizername(instance); + +#define G2O_USE_OPTIMIZATION_ALGORITHM(optimizername) \ + extern "C" void G2O_OAF_IMPORT g2o_optimization_algorithm_##optimizername(void); \ + static g2o::ForceLinker g2o_force_optimization_algorithm_link_##optimizername(g2o_optimization_algorithm_##optimizername); + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.cpp b/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.cpp new file mode 100644 index 0000000000..04ca44540b --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.cpp @@ -0,0 +1,101 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "optimization_algorithm_gauss_newton.h" + +#include + +#include "../stuff/timeutil.h" +#include "../stuff/macros.h" + +#include "solver.h" +#include "batch_stats.h" +#include "sparse_optimizer.h" +using namespace std; + +namespace g2o { + + OptimizationAlgorithmGaussNewton::OptimizationAlgorithmGaussNewton(Solver* solver) : + OptimizationAlgorithmWithHessian(solver) + { + } + + OptimizationAlgorithmGaussNewton::~OptimizationAlgorithmGaussNewton() + { + } + + OptimizationAlgorithm::SolverResult OptimizationAlgorithmGaussNewton::solve(int iteration, bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph"); + bool ok = true; + + //here so that correct component for max-mixtures can be computed before the build structure + double t=get_monotonic_time(); + _optimizer->computeActiveErrors(); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeResiduals = get_monotonic_time()-t; + } + + if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure + ok = _solver->buildStructure(); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl; + return OptimizationAlgorithm::Fail; + } + } + + t=get_monotonic_time(); + _solver->buildSystem(); + if (globalStats) { + globalStats->timeQuadraticForm = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + ok = _solver->solve(); + if (globalStats) { + globalStats->timeLinearSolution = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + _optimizer->update(_solver->x()); + if (globalStats) { + globalStats->timeUpdate = get_monotonic_time()-t; + } + if (ok) + return OK; + else + return Fail; + } + + void OptimizationAlgorithmGaussNewton::printVerbose(std::ostream& os) const + { + os + << "\t schur= " << _solver->schur(); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h b/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h new file mode 100644 index 0000000000..409aa27c7a --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_gauss_newton.h @@ -0,0 +1,54 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_GAUSS_NEWTON_H +#define G2O_OPTIMIZATION_ALGORITHM_GAUSS_NEWTON_H + +#include "optimization_algorithm_with_hessian.h" + +namespace g2o { + + /** + * \brief Implementation of the Gauss Newton Algorithm + */ + class OptimizationAlgorithmGaussNewton : public OptimizationAlgorithmWithHessian + { + public: + /** + * construct the Gauss Newton algorithm, which use the given Solver for solving the + * linearized system. + */ + explicit OptimizationAlgorithmGaussNewton(Solver* solver); + virtual ~OptimizationAlgorithmGaussNewton(); + + virtual SolverResult solve(int iteration, bool online = false); + + virtual void printVerbose(std::ostream& os) const; + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp b/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp new file mode 100644 index 0000000000..b24718f549 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.cpp @@ -0,0 +1,209 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +// Modified Raul Mur Artal (2014) +// - Stop criterium (solve function) + +#include "optimization_algorithm_levenberg.h" + +#include + +#include "../stuff/timeutil.h" + +#include "sparse_optimizer.h" +#include "solver.h" +#include "batch_stats.h" +using namespace std; + +namespace g2o { + + OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(Solver* solver) : + OptimizationAlgorithmWithHessian(solver) + { + _currentLambda = -1.; + _tau = 1e-5; + _goodStepUpperScale = 2./3.; + _goodStepLowerScale = 1./3.; + _userLambdaInit = _properties.makeProperty >("initialLambda", 0.); + _maxTrialsAfterFailure = _properties.makeProperty >("maxTrialsAfterFailure", 10); + _ni=2.; + _levenbergIterations = 0; + _nBad = 0; + } + + OptimizationAlgorithmLevenberg::~OptimizationAlgorithmLevenberg() + { + } + + OptimizationAlgorithm::SolverResult OptimizationAlgorithmLevenberg::solve(int iteration, bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph"); + + if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure + bool ok = _solver->buildStructure(); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl; + return OptimizationAlgorithm::Fail; + } + } + + double t=get_monotonic_time(); + _optimizer->computeActiveErrors(); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeResiduals = get_monotonic_time()-t; + t=get_monotonic_time(); + } + + double currentChi = _optimizer->activeRobustChi2(); + double tempChi=currentChi; + + double iniChi = currentChi; + + _solver->buildSystem(); + if (globalStats) { + globalStats->timeQuadraticForm = get_monotonic_time()-t; + } + + // core part of the Levenbarg algorithm + if (iteration == 0) { + _currentLambda = computeLambdaInit(); + _ni = 2; + _nBad = 0; + } + + double rho=0; + int& qmax = _levenbergIterations; + qmax = 0; + do { + _optimizer->push(); + if (globalStats) { + globalStats->levenbergIterations++; + t=get_monotonic_time(); + } + // update the diagonal of the system matrix + _solver->setLambda(_currentLambda, true); + bool ok2 = _solver->solve(); + if (globalStats) { + globalStats->timeLinearSolution+=get_monotonic_time()-t; + t=get_monotonic_time(); + } + _optimizer->update(_solver->x()); + if (globalStats) { + globalStats->timeUpdate = get_monotonic_time()-t; + } + + // restore the diagonal + _solver->restoreDiagonal(); + + _optimizer->computeActiveErrors(); + tempChi = _optimizer->activeRobustChi2(); + + if (! ok2) + tempChi=std::numeric_limits::max(); + + rho = (currentChi-tempChi); + double scale = computeScale(); + scale += 1e-3; // make sure it's non-zero :) + rho /= scale; + + if (rho>0 && g2o_isfinite(tempChi)){ // last step was good + double alpha = 1.-pow((2*rho-1),3); + // crop lambda between minimum and maximum factors + alpha = (std::min)(alpha, _goodStepUpperScale); + double scaleFactor = (std::max)(_goodStepLowerScale, alpha); + _currentLambda *= scaleFactor; + _ni = 2; + currentChi=tempChi; + _optimizer->discardTop(); + } else { + _currentLambda*=_ni; + _ni*=2; + _optimizer->pop(); // restore the last state before trying to optimize + } + qmax++; + } while (rho<0 && qmax < _maxTrialsAfterFailure->value() && ! _optimizer->terminate()); + + if (qmax == _maxTrialsAfterFailure->value() || rho==0) + return Terminate; + + //Stop criterium (Raul) + if((iniChi-currentChi)*1e3=3) + return Terminate; + + return OK; + } + + double OptimizationAlgorithmLevenberg::computeLambdaInit() const + { + if (_userLambdaInit->value() > 0) + return _userLambdaInit->value(); + double maxDiagonal=0.; + for (size_t k = 0; k < _optimizer->indexMapping().size(); k++) { + OptimizableGraph::Vertex* v = _optimizer->indexMapping()[k]; + assert(v); + int dim = v->dimension(); + for (int j = 0; j < dim; ++j){ + maxDiagonal = std::max(fabs(v->hessian(j,j)),maxDiagonal); + } + } + return _tau*maxDiagonal; + } + + double OptimizationAlgorithmLevenberg::computeScale() const + { + double scale = 0.; + for (size_t j=0; j < _solver->vectorSize(); j++){ + scale += _solver->x()[j] * (_currentLambda * _solver->x()[j] + _solver->b()[j]); + } + return scale; + } + + void OptimizationAlgorithmLevenberg::setMaxTrialsAfterFailure(int max_trials) + { + _maxTrialsAfterFailure->setValue(max_trials); + } + + void OptimizationAlgorithmLevenberg::setUserLambdaInit(double lambda) + { + _userLambdaInit->setValue(lambda); + } + + void OptimizationAlgorithmLevenberg::printVerbose(std::ostream& os) const + { + os + << "\t schur= " << _solver->schur() + << "\t lambda= " << FIXED(_currentLambda) + << "\t levenbergIter= " << _levenbergIterations; + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h b/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h new file mode 100644 index 0000000000..bc4a4a0660 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h @@ -0,0 +1,92 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SOLVER_LEVENBERG_H +#define G2O_SOLVER_LEVENBERG_H + +#include "optimization_algorithm_with_hessian.h" + +namespace g2o { + + /** + * \brief Implementation of the Levenberg Algorithm + */ + class OptimizationAlgorithmLevenberg : public OptimizationAlgorithmWithHessian + { + public: + /** + * construct the Levenberg algorithm, which will use the given Solver for solving the + * linearized system. + */ + explicit OptimizationAlgorithmLevenberg(Solver* solver); + virtual ~OptimizationAlgorithmLevenberg(); + + virtual SolverResult solve(int iteration, bool online = false); + + virtual void printVerbose(std::ostream& os) const; + + //! return the currently used damping factor + double currentLambda() const { return _currentLambda;} + + //! the number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt + void setMaxTrialsAfterFailure(int max_trials); + + //! get the number of inner iterations for Levenberg-Marquardt + int maxTrialsAfterFailure() const { return _maxTrialsAfterFailure->value();} + + //! return the lambda set by the user, if < 0 the SparseOptimizer will compute the initial lambda + double userLambdaInit() {return _userLambdaInit->value();} + //! specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to compute a suitable value + void setUserLambdaInit(double lambda); + + //! return the number of levenberg iterations performed in the last round + int levenbergIteration() { return _levenbergIterations;} + + protected: + // Levenberg parameters + Property* _maxTrialsAfterFailure; + Property* _userLambdaInit; + double _currentLambda; + double _tau; + double _goodStepLowerScale; ///< lower bound for lambda decrease if a good LM step + double _goodStepUpperScale; ///< upper bound for lambda decrease if a good LM step + double _ni; + int _levenbergIterations; ///< the numer of levenberg iterations performed to accept the last step + //RAUL + int _nBad; + + /** + * helper for Levenberg, this function computes the initial damping factor, if the user did not + * specify an own value, see setUserLambdaInit() + */ + double computeLambdaInit() const; + double computeScale() const; + + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h b/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h new file mode 100644 index 0000000000..62abb0eccf --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_property.h @@ -0,0 +1,57 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_PROPERTY_H +#define G2O_OPTIMIZATION_ALGORITHM_PROPERTY_H + +#include + +namespace g2o { + +/** + * \brief describe the properties of a solver + */ +struct OptimizationAlgorithmProperty +{ + std::string name; ///< name of the solver, e.g., var + std::string desc; ///< short description of the solver + std::string type; ///< type of solver, e.g., "CSparse Cholesky", "PCG" + bool requiresMarginalize; ///< whether the solver requires marginalization of landmarks + int poseDim; ///< dimension of the pose vertices (-1 if variable) + int landmarkDim; ///< dimension of the landmar vertices (-1 if variable) + OptimizationAlgorithmProperty() : + name(), desc(), type(), requiresMarginalize(false), poseDim(-1), landmarkDim(-1) + { + } + OptimizationAlgorithmProperty(const std::string& name_, const std::string& desc_, const std::string& type_, bool requiresMarginalize_, int poseDim_, int landmarkDim_) : + name(name_), desc(desc_), type(type_), requiresMarginalize(requiresMarginalize_), poseDim(poseDim_), landmarkDim(landmarkDim_) + { + } +}; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp b/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp new file mode 100644 index 0000000000..5c23a78b60 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.cpp @@ -0,0 +1,101 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "optimization_algorithm_with_hessian.h" + +#include "solver.h" +#include "optimizable_graph.h" +#include "sparse_optimizer.h" + +#include +using namespace std; + +namespace g2o { + + OptimizationAlgorithmWithHessian::OptimizationAlgorithmWithHessian(Solver* solver) : + OptimizationAlgorithm(), + _solver(solver) + { + _writeDebug = _properties.makeProperty >("writeDebug", true); + } + + OptimizationAlgorithmWithHessian::~OptimizationAlgorithmWithHessian() + { + delete _solver; + } + + bool OptimizationAlgorithmWithHessian::init(bool online) + { + assert(_optimizer && "_optimizer not set"); + assert(_solver && "Solver not set"); + _solver->setWriteDebug(_writeDebug->value()); + bool useSchur=false; + for (OptimizableGraph::VertexContainer::const_iterator it=_optimizer->activeVertices().begin(); it!=_optimizer->activeVertices().end(); ++it) { + OptimizableGraph::Vertex* v= *it; + if (v->marginalized()){ + useSchur=true; + break; + } + } + if (useSchur){ + if (_solver->supportsSchur()) + _solver->setSchur(true); + } else { + if (_solver->supportsSchur()) + _solver->setSchur(false); + } + + bool initState = _solver->init(_optimizer, online); + return initState; + } + + bool OptimizationAlgorithmWithHessian::computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) + { + return _solver ? _solver->computeMarginals(spinv, blockIndices) : false; + } + + bool OptimizationAlgorithmWithHessian::buildLinearStructure() + { + return _solver ? _solver->buildStructure() : false; + } + + void OptimizationAlgorithmWithHessian::updateLinearSystem() + { + if (_solver) + _solver->buildSystem(); + } + + bool OptimizationAlgorithmWithHessian::updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) + { + return _solver ? _solver->updateStructure(vset, edges) : false; + } + + void OptimizationAlgorithmWithHessian::setWriteDebug(bool writeDebug) + { + _writeDebug->setValue(writeDebug); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h b/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h new file mode 100644 index 0000000000..cf5da58ccf --- /dev/null +++ b/Thirdparty/g2o/g2o/core/optimization_algorithm_with_hessian.h @@ -0,0 +1,72 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OPTIMIZATION_ALGORITHM_WITH_HESSIAN_H +#define G2O_OPTIMIZATION_ALGORITHM_WITH_HESSIAN_H + +#include "optimization_algorithm.h" + +namespace g2o { + + class Solver; + + /** + * \brief Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg + */ + class OptimizationAlgorithmWithHessian : public OptimizationAlgorithm + { + public: + explicit OptimizationAlgorithmWithHessian(Solver* solver); + virtual ~OptimizationAlgorithmWithHessian(); + + virtual bool init(bool online = false); + + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); + + virtual bool buildLinearStructure(); + + virtual void updateLinearSystem(); + + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges); + + //! return the underlying solver used to solve the linear system + Solver* solver() { return _solver;} + + /** + * write debug output of the Hessian if system is not positive definite + */ + virtual void setWriteDebug(bool writeDebug); + virtual bool writeDebug() const { return _writeDebug->value();} + + protected: + Solver* _solver; + Property* _writeDebug; + + }; + +}// end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/parameter.cpp b/Thirdparty/g2o/g2o/core/parameter.cpp new file mode 100644 index 0000000000..345f9c026b --- /dev/null +++ b/Thirdparty/g2o/g2o/core/parameter.cpp @@ -0,0 +1,40 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "parameter.h" + +namespace g2o { + + Parameter::Parameter() : _id(-1) + { + } + + void Parameter::setId(int id_) + { + _id = id_; + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/parameter.h b/Thirdparty/g2o/g2o/core/parameter.h new file mode 100644 index 0000000000..6def66446c --- /dev/null +++ b/Thirdparty/g2o/g2o/core/parameter.h @@ -0,0 +1,56 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_GRAPH_PARAMETER_HH_ +#define G2O_GRAPH_PARAMETER_HH_ + +#include + +#include "hyper_graph.h" + +namespace g2o { + + class Parameter : public HyperGraph::HyperGraphElement + { + public: + Parameter(); + virtual ~Parameter() {}; + //! read the data from a stream + virtual bool read(std::istream& is) = 0; + //! write the data to a stream + virtual bool write(std::ostream& os) const = 0; + int id() const {return _id;} + void setId(int id_); + virtual HyperGraph::HyperGraphElementType elementType() const { return HyperGraph::HGET_PARAMETER;} + protected: + int _id; + }; + + typedef std::vector ParameterVector; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/parameter_container.cpp b/Thirdparty/g2o/g2o/core/parameter_container.cpp new file mode 100644 index 0000000000..d0123310de --- /dev/null +++ b/Thirdparty/g2o/g2o/core/parameter_container.cpp @@ -0,0 +1,142 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "parameter_container.h" + +#include + +#include "factory.h" +#include "parameter.h" + +#include "../stuff/macros.h" +#include "../stuff/color_macros.h" +#include "../stuff/string_tools.h" + +namespace g2o { + + using namespace std; + + ParameterContainer::ParameterContainer(bool isMainStorage_) : + _isMainStorage(isMainStorage_) + { + } + + void ParameterContainer::clear() { + if (!_isMainStorage) + return; + for (iterator it = begin(); it!=end(); it++){ + delete it->second; + } + BaseClass::clear(); + } + + ParameterContainer::~ParameterContainer(){ + clear(); + } + + bool ParameterContainer::addParameter(Parameter* p){ + if (p->id()<0) + return false; + iterator it=find(p->id()); + if (it!=end()) + return false; + insert(make_pair(p->id(), p)); + return true; + } + + Parameter* ParameterContainer::getParameter(int id) { + iterator it=find(id); + if (it==end()) + return 0; + return it->second; + } + + Parameter* ParameterContainer::detachParameter(int id){ + iterator it=find(id); + if (it==end()) + return 0; + Parameter* p=it->second; + erase(it); + return p; + } + + bool ParameterContainer::write(std::ostream& os) const{ + Factory* factory = Factory::instance(); + for (const_iterator it=begin(); it!=end(); it++){ + os << factory->tag(it->second) << " "; + os << it->second->id() << " "; + it->second->write(os); + os << endl; + } + return true; + } + + bool ParameterContainer::read(std::istream& is, const std::map* _renamedTypesLookup){ + stringstream currentLine; + string token; + + Factory* factory = Factory::instance(); + HyperGraph::GraphElemBitset elemBitset; + elemBitset[HyperGraph::HGET_PARAMETER] = 1; + + while (1) { + int bytesRead = readLine(is, currentLine); + if (bytesRead == -1) + break; + currentLine >> token; + if (bytesRead == 0 || token.size() == 0 || token[0] == '#') + continue; + if (_renamedTypesLookup && _renamedTypesLookup->size()>0){ + map::const_iterator foundIt = _renamedTypesLookup->find(token); + if (foundIt != _renamedTypesLookup->end()) { + token = foundIt->second; + } + } + + HyperGraph::HyperGraphElement* element = factory->construct(token, elemBitset); + if (! element) // not a parameter or otherwise unknown tag + continue; + assert(element->elementType() == HyperGraph::HGET_PARAMETER && "Should be a param"); + + Parameter* p = static_cast(element); + int pid; + currentLine >> pid; + p->setId(pid); + bool r = p->read(currentLine); + if (! r) { + cerr << __PRETTY_FUNCTION__ << ": Error reading data " << token << " for parameter " << pid << endl; + delete p; + } else { + if (! addParameter(p) ){ + cerr << __PRETTY_FUNCTION__ << ": Parameter of type:" << token << " id:" << pid << " already defined" << endl; + } + } + } // while read line + + return true; + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/parameter_container.h b/Thirdparty/g2o/g2o/core/parameter_container.h new file mode 100644 index 0000000000..eef6c2ff68 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/parameter_container.h @@ -0,0 +1,74 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_GRAPH_PARAMETER_CONTAINER_HH_ +#define G2O_GRAPH_PARAMETER_CONTAINER_HH_ + +#include +#include +#include + +namespace g2o { + + class Parameter; + + /** + * \brief map id to parameters + */ + class ParameterContainer : protected std::map + { + public: + typedef std::map BaseClass; + + /** + * create a container for the parameters. + * @param isMainStorage_ pointers to the parameters are owned by this container, i.e., freed in its constructor + */ + ParameterContainer(bool isMainStorage_=true); + virtual ~ParameterContainer(); + //! add parameter to the container + bool addParameter(Parameter* p); + //! return a parameter based on its ID + Parameter* getParameter(int id); + //! remove a parameter from the container, i.e., the user now owns the pointer + Parameter* detachParameter(int id); + //! read parameters from a stream + virtual bool read(std::istream& is, const std::map* renamedMap =0); + //! write the data to a stream + virtual bool write(std::ostream& os) const; + bool isMainStorage() const {return _isMainStorage;} + void clear(); + + // stuff of the base class that should re-appear + using BaseClass::size; + + protected: + bool _isMainStorage; + }; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/robust_kernel.cpp b/Thirdparty/g2o/g2o/core/robust_kernel.cpp new file mode 100644 index 0000000000..ac6776d8a1 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/robust_kernel.cpp @@ -0,0 +1,46 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "robust_kernel.h" + +namespace g2o { + +RobustKernel::RobustKernel() : + _delta(1.) +{ +} + +RobustKernel::RobustKernel(double delta) : + _delta(delta) +{ +} + +void RobustKernel::setDelta(double delta) +{ + _delta = delta; +} + +} // end namespace g2o diff --git a/Thirdparty/g2o/g2o/core/robust_kernel.h b/Thirdparty/g2o/g2o/core/robust_kernel.h new file mode 100644 index 0000000000..29e1394a0d --- /dev/null +++ b/Thirdparty/g2o/g2o/core/robust_kernel.h @@ -0,0 +1,81 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_ROBUST_KERNEL_H +#define G2O_ROBUST_KERNEL_H + +#ifdef _MSC_VER +#include +#else +#include +#endif +#include + + +namespace g2o { + + /** + * \brief base for all robust cost functions + * + * Note in all the implementations for the other cost functions the e in the + * funtions corresponds to the sqaured errors, i.e., the robustification + * functions gets passed the squared error. + * + * e.g. the robustified least squares function is + * + * chi^2 = sum_{e} rho( e^T Omega e ) + */ + class RobustKernel + { + public: + RobustKernel(); + explicit RobustKernel(double delta); + virtual ~RobustKernel() {} + /** + * compute the scaling factor for a error: + * The error is e^T Omega e + * The output rho is + * rho[0]: The actual scaled error value + * rho[1]: First derivative of the scaling function + * rho[2]: Second derivative of the scaling function + */ + virtual void robustify(double squaredError, Eigen::Vector3d& rho) const = 0; + + /** + * set the window size of the error. A squared error above delta^2 is considered + * as outlier in the data. + */ + virtual void setDelta(double delta); + double delta() const { return _delta;} + + protected: + double _delta; + }; + typedef std::tr1::shared_ptr RobustKernelPtr; + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp b/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp new file mode 100644 index 0000000000..1d028cf3c3 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/robust_kernel_factory.cpp @@ -0,0 +1,111 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "robust_kernel_factory.h" +#include "robust_kernel.h" + +#include + +using namespace std; + +namespace g2o { + +RobustKernelFactory* RobustKernelFactory::factoryInstance = 0; + +RobustKernelFactory::RobustKernelFactory() +{ +} + +RobustKernelFactory::~RobustKernelFactory() +{ + for (CreatorMap::iterator it = _creator.begin(); it != _creator.end(); ++it) { + delete it->second; + } + _creator.clear(); +} + +RobustKernelFactory* RobustKernelFactory::instance() +{ + if (factoryInstance == 0) { + factoryInstance = new RobustKernelFactory; + } + + return factoryInstance; +} + +void RobustKernelFactory::registerRobustKernel(const std::string& tag, AbstractRobustKernelCreator* c) +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + cerr << "RobustKernelFactory WARNING: Overwriting robust kernel tag " << tag << endl; + assert(0); + } + + _creator[tag] = c; +} + +void RobustKernelFactory::unregisterType(const std::string& tag) +{ + CreatorMap::iterator tagPosition = _creator.find(tag); + if (tagPosition != _creator.end()) { + AbstractRobustKernelCreator* c = tagPosition->second; + delete c; + _creator.erase(tagPosition); + } +} + +RobustKernel* RobustKernelFactory::construct(const std::string& tag) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + return foundIt->second->construct(); + } + return 0; +} + +AbstractRobustKernelCreator* RobustKernelFactory::creator(const std::string& tag) const +{ + CreatorMap::const_iterator foundIt = _creator.find(tag); + if (foundIt != _creator.end()) { + return foundIt->second; + } + return 0; +} + +void RobustKernelFactory::fillKnownKernels(std::vector& types) const +{ + types.clear(); + for (CreatorMap::const_iterator it = _creator.begin(); it != _creator.end(); ++it) + types.push_back(it->first); +} + +void RobustKernelFactory::destroy() +{ + delete factoryInstance; + factoryInstance = 0; +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/robust_kernel_factory.h b/Thirdparty/g2o/g2o/core/robust_kernel_factory.h new file mode 100644 index 0000000000..bcdec07f47 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/robust_kernel_factory.h @@ -0,0 +1,151 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_ROBUST_KERNEL_FACTORY_H +#define G2O_ROBUST_KERNEL_FACTORY_H + +#include "../stuff/misc.h" + +#include +#include +#include +#include + +namespace g2o { + + class RobustKernel; + + /** + * \brief Abstract interface for allocating a robust kernel + */ + class AbstractRobustKernelCreator + { + public: + /** + * create a hyper graph element. Has to implemented in derived class. + */ + virtual RobustKernel* construct() = 0; + virtual ~AbstractRobustKernelCreator() { } + }; + + /** + * \brief templatized creator class which creates graph elements + */ + template + class RobustKernelCreator : public AbstractRobustKernelCreator + { + public: + RobustKernel* construct() { return new T;} + }; + + /** + * \brief create robust kernels based on their human readable name + */ + class RobustKernelFactory + { + public: + + //! return the instance + static RobustKernelFactory* instance(); + + //! free the instance + static void destroy(); + + /** + * register a tag for a specific creator + */ + void registerRobustKernel(const std::string& tag, AbstractRobustKernelCreator* c); + + /** + * unregister a tag for a specific creator + */ + void unregisterType(const std::string& tag); + + /** + * construct a robust kernel based on its tag + */ + RobustKernel* construct(const std::string& tag) const; + + /** + * return the creator for a specific tag + */ + AbstractRobustKernelCreator* creator(const std::string& tag) const; + + /** + * get a list of all known robust kernels + */ + void fillKnownKernels(std::vector& types) const; + + protected: + + typedef std::map CreatorMap; + RobustKernelFactory(); + ~RobustKernelFactory(); + + CreatorMap _creator; ///< look-up map for the existing creators + + private: + static RobustKernelFactory* factoryInstance; + }; + + template + class RegisterRobustKernelProxy + { + public: + RegisterRobustKernelProxy(const std::string& name) : _name(name) + { + RobustKernelFactory::instance()->registerRobustKernel(_name, new RobustKernelCreator()); + } + + ~RegisterRobustKernelProxy() + { + RobustKernelFactory::instance()->unregisterType(_name); + } + + private: + std::string _name; + }; + +#if defined _MSC_VER && defined G2O_SHARED_LIBS +# define G2O_ROBUST_KERNEL_FACTORY_EXPORT __declspec(dllexport) +# define G2O_ROBUST_KERNEL_FACTORY_IMPORT __declspec(dllimport) +#else +# define G2O_ROBUST_KERNEL_FACTORY_EXPORT +# define G2O_ROBUST_KERNEL_FACTORY_IMPORT +#endif + + // These macros are used to automate registering of robust kernels and forcing linkage +#define G2O_REGISTER_ROBUST_KERNEL(name, classname) \ + extern "C" void G2O_ROBUST_KERNEL_FACTORY_EXPORT g2o_robust_kernel_##classname(void) {} \ + static g2o::RegisterRobustKernelProxy g_robust_kernel_proxy_##classname(#name); + +#define G2O_USE_ROBUST_KERNEL(classname) \ + extern "C" void G2O_ROBUST_KERNEL_FACTORY_IMPORT g2o_robust_kernel_##classname(void); \ + static g2o::TypeFunctionProxy proxy_##classname(g2o_robust_kernel_##classname); + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp b/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp new file mode 100644 index 0000000000..e446efcd87 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/robust_kernel_impl.cpp @@ -0,0 +1,173 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "robust_kernel_impl.h" +#include "robust_kernel_factory.h" + +#include + +namespace g2o { + +RobustKernelScaleDelta::RobustKernelScaleDelta(const RobustKernelPtr& kernel, double delta) : + RobustKernel(delta), + _kernel(kernel) +{ +} + +RobustKernelScaleDelta::RobustKernelScaleDelta(double delta) : + RobustKernel(delta) +{ +} + +void RobustKernelScaleDelta::setKernel(const RobustKernelPtr& ptr) +{ + _kernel = ptr; +} + +void RobustKernelScaleDelta::robustify(double error, Eigen::Vector3d& rho) const +{ + if (_kernel.get()) { + double dsqr = _delta * _delta; + double dsqrReci = 1. / dsqr; + _kernel->robustify(dsqrReci * error, rho); + rho[0] *= dsqr; + rho[2] *= dsqrReci; + } else { // no robustification + rho[0] = error; + rho[1] = 1.; + rho[2] = 0.; + } +} + +void RobustKernelHuber::setDelta(double delta) +{ + dsqr = delta*delta; + _delta = delta; +} + + +void RobustKernelHuber::setDeltaSqr(const double &delta, const double &deltaSqr) +{ + dsqr = deltaSqr; + _delta = delta; +} + +void RobustKernelHuber::robustify(double e, Eigen::Vector3d& rho) const +{ + //dsqr = _delta * _delta; + if (e <= dsqr) { // inlier + rho[0] = e; + rho[1] = 1.; + rho[2] = 0.; + } else { // outlier + double sqrte = sqrt(e); // absolut value of the error + rho[0] = 2*sqrte*_delta - dsqr; // rho(e) = 2 * delta * e^(1/2) - delta^2 + rho[1] = _delta / sqrte; // rho'(e) = delta / sqrt(e) + rho[2] = - 0.5 * rho[1] / e; // rho''(e) = -1 / (2*e^(3/2)) = -1/2 * (delta/e) / e + } +} + +void RobustKernelTukey::setDeltaSqr(const double &deltaSqr, const double &inv) +{ + _deltaSqr = deltaSqr; + _invDeltaSqr = inv; + +} + +void RobustKernelTukey::robustify(double e, Eigen::Vector3d& rho) const +{ + if (e <= _deltaSqr) { // inlier + double factor = e*_invDeltaSqr; + double d = 1-factor; + double dd = d*d; + rho[0] = _deltaSqr*(1-dd*d); + rho[1] = 3*dd; + rho[2] = -6*_invDeltaSqr*d; + } else { // outlier + rho[0] = _deltaSqr; // rho(e) = delta^2 + rho[1] = 0.; + rho[2] = 0.; + } +} + +void RobustKernelPseudoHuber::robustify(double e2, Eigen::Vector3d& rho) const +{ + double dsqr = _delta * _delta; + double dsqrReci = 1. / dsqr; + double aux1 = dsqrReci * e2 + 1.0; + double aux2 = sqrt(aux1); + rho[0] = 2 * dsqr * (aux2 - 1); + rho[1] = 1. / aux2; + rho[2] = -0.5 * dsqrReci * rho[1] / aux1; +} + +void RobustKernelCauchy::robustify(double e2, Eigen::Vector3d& rho) const +{ + double dsqr = _delta * _delta; + double dsqrReci = 1. / dsqr; + double aux = dsqrReci * e2 + 1.0; + rho[0] = dsqr * log(aux); + rho[1] = 1. / aux; + rho[2] = -dsqrReci * std::pow(rho[1], 2); +} + +void RobustKernelSaturated::robustify(double e2, Eigen::Vector3d& rho) const +{ + double dsqr = _delta * _delta; + if (e2 <= dsqr) { // inlier + rho[0] = e2; + rho[1] = 1.; + rho[2] = 0.; + } else { // outlier + rho[0] = dsqr; + rho[1] = 0.; + rho[2] = 0.; + } +} + +//delta is used as $phi$ +void RobustKernelDCS::robustify(double e2, Eigen::Vector3d& rho) const +{ + const double& phi = _delta; + double scale = (2.0*phi)/(phi+e2); + if(scale>=1.0) + scale = 1.0; + + rho[0] = scale*e2*scale; + rho[1] = (scale*scale); + rho[2] = 0; +} + + +// register the kernel to their factory +G2O_REGISTER_ROBUST_KERNEL(Huber, RobustKernelHuber) +G2O_REGISTER_ROBUST_KERNEL(Tukey, RobustKernelTukey) +G2O_REGISTER_ROBUST_KERNEL(PseudoHuber, RobustKernelPseudoHuber) +G2O_REGISTER_ROBUST_KERNEL(Cauchy, RobustKernelCauchy) +G2O_REGISTER_ROBUST_KERNEL(Saturated, RobustKernelSaturated) +G2O_REGISTER_ROBUST_KERNEL(DCS, RobustKernelDCS) + +} // end namespace g2o diff --git a/Thirdparty/g2o/g2o/core/robust_kernel_impl.h b/Thirdparty/g2o/g2o/core/robust_kernel_impl.h new file mode 100644 index 0000000000..066cc37f38 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/robust_kernel_impl.h @@ -0,0 +1,167 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_ROBUST_KERNEL_IMPL_H +#define G2O_ROBUST_KERNEL_IMPL_H + +#include "robust_kernel.h" + +namespace g2o { + + /** + * \brief scale a robust kernel to another delta (window size) + * + * Scales a robust kernel to another window size. Useful, in case if + * one implements a kernel which only is designed for a fixed window + * size. + */ + class RobustKernelScaleDelta : public RobustKernel + { + public: + /** + * construct the scaled kernel ontop of another kernel which might be shared accross + * several scaled kernels + */ + explicit RobustKernelScaleDelta(const RobustKernelPtr& kernel, double delta = 1.); + explicit RobustKernelScaleDelta(double delta = 1.); + + //! return the underlying kernel + const RobustKernelPtr kernel() const { return _kernel;} + //! use another kernel for the underlying operation + void setKernel(const RobustKernelPtr& ptr); + + void robustify(double error, Eigen::Vector3d& rho) const; + + protected: + RobustKernelPtr _kernel; + }; + + /** + * \brief Huber Cost Function + * + * Loss function as described by Huber + * See http://en.wikipedia.org/wiki/Huber_loss_function + * + * If e^(1/2) < d + * rho(e) = e + * + * else + * + * 1/2 2 + * rho(e) = 2 d e - d + */ + class RobustKernelHuber : public RobustKernel + { + public: + virtual void setDelta(double delta); + virtual void setDeltaSqr(const double &delta, const double &deltaSqr); + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + + private: + float dsqr; + }; + + /** + * \brief Tukey Cost Function + * + * + * If e^(1/2) < d + * rho(e) = delta2(1-(1-e/delta2)^3) + * + * else + * + * rho(e) = delta2 + */ + class RobustKernelTukey : public RobustKernel + { + public: + + virtual void setDeltaSqr(const double &deltaSqr, const double &inv); + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + private: + float _deltaSqr; + float _invDeltaSqr; + }; + + + /** + * \brief Pseudo Huber Cost Function + * + * The smooth pseudo huber cost function: + * See http://en.wikipedia.org/wiki/Huber_loss_function + * + * 2 e + * 2 d (sqrt(-- + 1) - 1) + * 2 + * d + */ + class RobustKernelPseudoHuber : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + + /** + * \brief Cauchy cost function + * + * 2 e + * d log(-- + 1) + * 2 + * d + */ + class RobustKernelCauchy : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + + /** + * \brief Saturated cost function. + * + * The error is at most delta^2 + */ + class RobustKernelSaturated : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + + /** + * \brief Dynamic covariance scaling - DCS + * + * See paper Robust Map Optimization from Agarwal et al. ICRA 2013 + * + * delta is used as $phi$ + */ + class RobustKernelDCS : public RobustKernel + { + public: + virtual void robustify(double e2, Eigen::Vector3d& rho) const; + }; + +} // end namespace g2o + +#endif diff --git a/Thirdparty/g2o/g2o/core/solver.cpp b/Thirdparty/g2o/g2o/core/solver.cpp new file mode 100644 index 0000000000..cdddfac0e5 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/solver.cpp @@ -0,0 +1,87 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "solver.h" + +#include +#include + +namespace g2o { + +Solver::Solver() : + _optimizer(0), _x(0), _b(0), _xSize(0), _maxXSize(0), + _isLevenberg(false), _additionalVectorSpace(0) +{ +} + +Solver::~Solver() +{ + delete[] _x; + delete[] _b; +} + +void Solver::resizeVector(size_t sx) +{ + size_t oldSize = _xSize; + _xSize = sx; + sx += _additionalVectorSpace; // allocate some additional space if requested + if (_maxXSize < sx) { + _maxXSize = 2*sx; + delete[] _x; + _x = new double[_maxXSize]; +#ifndef NDEBUG + memset(_x, 0, _maxXSize * sizeof(double)); +#endif + if (_b) { // backup the former b, might still be needed for online processing + memcpy(_x, _b, oldSize * sizeof(double)); + delete[] _b; + _b = new double[_maxXSize]; + std::swap(_b, _x); + } else { + _b = new double[_maxXSize]; +#ifndef NDEBUG + memset(_b, 0, _maxXSize * sizeof(double)); +#endif + } + } +} + +void Solver::setOptimizer(SparseOptimizer* optimizer) +{ + _optimizer = optimizer; +} + +void Solver::setLevenberg(bool levenberg) +{ + _isLevenberg = levenberg; +} + +void Solver::setAdditionalVectorSpace(size_t s) +{ + _additionalVectorSpace = s; +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/solver.h b/Thirdparty/g2o/g2o/core/solver.h new file mode 100644 index 0000000000..a801d319c4 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/solver.h @@ -0,0 +1,151 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SOLVER_H +#define G2O_SOLVER_H + +#include "hyper_graph.h" +#include "batch_stats.h" +#include "sparse_block_matrix.h" +#include + +namespace g2o { + + + class SparseOptimizer; + + /** + * \brief Generic interface for a sparse solver operating on a graph which solves one iteration of the linearized objective function + */ + class Solver + { + public: + Solver(); + virtual ~Solver(); + + public: + /** + * initialize the solver, called once before the first iteration + */ + virtual bool init(SparseOptimizer* optimizer, bool online = false) = 0; + + /** + * build the structure of the system + */ + virtual bool buildStructure(bool zeroBlocks = false) = 0; + /** + * update the structures for online processing + */ + virtual bool updateStructure(const std::vector& vset, const HyperGraph::EdgeSet& edges) = 0; + /** + * build the current system + */ + virtual bool buildSystem() = 0; + + /** + * solve Ax = b + */ + virtual bool solve() = 0; + + /** + * computes the block diagonal elements of the pattern specified in the input + * and stores them in given SparseBlockMatrix + */ + virtual bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices) = 0; + + /** + * update the system while performing Levenberg, i.e., modifying the diagonal + * components of A by doing += lambda along the main diagonal of the Matrix. + * Note that this function may be called with a positive and a negative lambda. + * The latter is used to undo a former modification. + * If backup is true, then the solver should store a backup of the diagonal, which + * can be restored by restoreDiagonal() + */ + virtual bool setLambda(double lambda, bool backup = false) = 0; + + /** + * restore a previosly made backup of the diagonal + */ + virtual void restoreDiagonal() = 0; + + //! return x, the solution vector + double* x() { return _x;} + const double* x() const { return _x;} + //! return b, the right hand side of the system + double* b() { return _b;} + const double* b() const { return _b;} + + //! return the size of the solution vector (x) and b + size_t vectorSize() const { return _xSize;} + + //! the optimizer (graph) on which the solver works + SparseOptimizer* optimizer() const { return _optimizer;} + void setOptimizer(SparseOptimizer* optimizer); + + //! the system is Levenberg-Marquardt + bool levenberg() const { return _isLevenberg;} + void setLevenberg(bool levenberg); + + /** + * does this solver support the Schur complement for solving a system consisting of poses and + * landmarks. Re-implemement in a derived solver, if your solver supports it. + */ + virtual bool supportsSchur() {return false;} + + //! should the solver perform the schur complement or not + virtual bool schur()=0; + virtual void setSchur(bool s)=0; + + size_t additionalVectorSpace() const { return _additionalVectorSpace;} + void setAdditionalVectorSpace(size_t s); + + /** + * write debug output of the Hessian if system is not positive definite + */ + virtual void setWriteDebug(bool) = 0; + virtual bool writeDebug() const = 0; + + //! write the hessian to disk using the specified file name + virtual bool saveHessian(const std::string& /*fileName*/) const = 0; + + protected: + SparseOptimizer* _optimizer; + double* _x; + double* _b; + size_t _xSize, _maxXSize; + bool _isLevenberg; ///< the system we gonna solve is a Levenberg-Marquardt system + size_t _additionalVectorSpace; + + void resizeVector(size_t sx); + + private: + // Disable the copy constructor and assignment operator + Solver(const Solver&) { } + Solver& operator= (const Solver&) { return *this; } + }; +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/sparse_block_matrix.h b/Thirdparty/g2o/g2o/core/sparse_block_matrix.h new file mode 100644 index 0000000000..8e9b5efdf4 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_block_matrix.h @@ -0,0 +1,231 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SPARSE_BLOCK_MATRIX_ +#define G2O_SPARSE_BLOCK_MATRIX_ + +#include +#include +#include +#include +#include +#include +#include + +#include "sparse_block_matrix_ccs.h" +#include "matrix_structure.h" +#include "matrix_operations.h" +#include "../../config.h" + +namespace g2o { + using namespace Eigen; +/** + * \brief Sparse matrix which uses blocks + * + * Template class that specifies a sparse block matrix. A block + * matrix is a sparse matrix made of dense blocks. These blocks + * cannot have a random pattern, but follow a (variable) grid + * structure. This structure is specified by a partition of the rows + * and the columns of the matrix. The blocks are represented by the + * Eigen::Matrix structure, thus they can be statically or dynamically + * allocated. For efficiency reasons it is convenient to allocate them + * statically, when possible. A static block matrix has all blocks of + * the same size, and the size of the block is specified by the + * template argument. If this is not the case, and you have different + * block sizes than you have to use a dynamic-block matrix (default + * template argument). + */ +template +class SparseBlockMatrix { + + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + inline int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;} + //! rows of the matrix + inline int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;} + + typedef std::map IntBlockMap; + + /** + * constructs a sparse block matrix having a specific layout + * @param rbi: array of int containing the row layout of the blocks. + * the component i of the array should contain the index of the first row of the block i+1. + * @param rbi: array of int containing the column layout of the blocks. + * the component i of the array should contain the index of the first col of the block i+1. + * @param rb: number of row blocks + * @param cb: number of col blocks + * @param hasStorage: set it to true if the matrix "owns" the blocks, thus it deletes it on destruction. + * if false the matrix is only a "view" over an existing structure. + */ + SparseBlockMatrix( const int * rbi, const int* cbi, int rb, int cb, bool hasStorage=true); + + SparseBlockMatrix(); + + ~SparseBlockMatrix(); + + + //! this zeroes all the blocks. If dealloc=true the blocks are removed from memory + void clear(bool dealloc=false) ; + + //! returns the block at location r,c. if alloc=true he block is created if it does not exist + SparseMatrixBlock* block(int r, int c, bool alloc=false); + //! returns the block at location r,c + const SparseMatrixBlock* block(int r, int c) const; + + //! how many rows does the block at block-row r has? + inline int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; } + + //! how many cols does the block at block-col c has? + inline int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; } + + //! where does the row at block-row r starts? + inline int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; } + + //! where does the col at block-col r starts? + inline int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; } + + //! number of non-zero elements + size_t nonZeros() const; + //! number of allocated blocks + size_t nonZeroBlocks() const; + + //! deep copy of a sparse-block-matrix; + SparseBlockMatrix* clone() const ; + + /** + * returns a view or a copy of the block matrix + * @param rmin: starting block row + * @param rmax: ending block row + * @param cmin: starting block col + * @param cmax: ending block col + * @param alloc: if true it makes a deep copy, if false it creates a view. + */ + SparseBlockMatrix* slice(int rmin, int rmax, int cmin, int cmax, bool alloc=true) const; + + //! transposes a block matrix, The transposed type should match the argument false on failure + template + bool transpose(SparseBlockMatrix*& dest) const; + + //! adds the current matrix to the destination + bool add(SparseBlockMatrix*& dest) const ; + + //! dest = (*this) * M + template + bool multiply(SparseBlockMatrix *& dest, const SparseBlockMatrix* M) const; + + //! dest = (*this) * src + void multiply(double*& dest, const double* src) const; + + /** + * compute dest = (*this) * src + * However, assuming that this is a symmetric matrix where only the upper triangle is stored + */ + void multiplySymmetricUpperTriangle(double*& dest, const double* src) const; + + //! dest = M * (*this) + void rightMultiply(double*& dest, const double* src) const; + + //! *this *= a + void scale( double a); + + /** + * writes in dest a block permutaton specified by pinv. + * @param pinv: array such that new_block[i] = old_block[pinv[i]] + */ + bool symmPermutation(SparseBlockMatrix*& dest, const int* pinv, bool onlyUpper=false) const; + + /** + * fill the CCS arrays of a matrix, arrays have to be allocated beforehand + */ + int fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle = false) const; + + /** + * fill the CCS arrays of a matrix, arrays have to be allocated beforehand. This function only writes + * the values and assumes that column and row structures have already been written. + */ + int fillCCS(double* Cx, bool upperTriangle = false) const; + + //! exports the non zero blocks in the structure matrix ms + void fillBlockStructure(MatrixStructure& ms) const; + + //! the block matrices per block-column + const std::vector& blockCols() const { return _blockCols;} + std::vector& blockCols() { return _blockCols;} + + //! indices of the row blocks + const std::vector& rowBlockIndices() const { return _rowBlockIndices;} + std::vector& rowBlockIndices() { return _rowBlockIndices;} + + //! indices of the column blocks + const std::vector& colBlockIndices() const { return _colBlockIndices;} + std::vector& colBlockIndices() { return _colBlockIndices;} + + /** + * write the content of this matrix to a stream loadable by Octave + * @param upperTriangle does this matrix store only the upper triangular blocks + */ + bool writeOctave(const char* filename, bool upperTriangle = true) const; + + /** + * copy into CCS structure + * @return number of processed blocks, -1 on error + */ + int fillSparseBlockMatrixCCS(SparseBlockMatrixCCS& blockCCS) const; + + /** + * copy as transposed into a CCS structure + * @return number of processed blocks, -1 on error + */ + int fillSparseBlockMatrixCCSTransposed(SparseBlockMatrixCCS& blockCCS) const; + + /** + * take over the memory and matrix pattern from a hash matrix. + * The structure of the hash matrix will be cleared. + */ + void takePatternFromHash(SparseBlockMatrixHashMap& hashMatrix); + + protected: + std::vector _rowBlockIndices; ///< vector of the indices of the blocks along the rows. + std::vector _colBlockIndices; ///< vector of the indices of the blocks along the cols + //! array of maps of blocks. The index of the array represent a block column of the matrix + //! and the block column is stored as a map row_block -> matrix_block_ptr. + std::vector _blockCols; + bool _hasStorage; +}; + +template < class MatrixType > +std::ostream& operator << (std::ostream&, const SparseBlockMatrix& m); + + typedef SparseBlockMatrix SparseBlockMatrixXd; + +} //end namespace + +#include "sparse_block_matrix.hpp" + +#endif diff --git a/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp b/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp new file mode 100644 index 0000000000..8dfa99c1b7 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_block_matrix.hpp @@ -0,0 +1,657 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +namespace g2o { + using namespace Eigen; + + namespace { + struct TripletEntry + { + int r, c; + double x; + TripletEntry(int r_, int c_, double x_) : r(r_), c(c_), x(x_) {} + }; + struct TripletColSort + { + bool operator()(const TripletEntry& e1, const TripletEntry& e2) const + { + return e1.c < e2.c || (e1.c == e2.c && e1.r < e2.r); + } + }; + /** Helper class to sort pair based on first elem */ + template > + struct CmpPairFirst { + bool operator()(const std::pair& left, const std::pair& right) { + return Pred()(left.first, right.first); + } + }; + } + + template + SparseBlockMatrix::SparseBlockMatrix( const int * rbi, const int* cbi, int rb, int cb, bool hasStorage): + _rowBlockIndices(rbi,rbi+rb), + _colBlockIndices(cbi,cbi+cb), + _blockCols(cb), _hasStorage(hasStorage) + { + } + + template + SparseBlockMatrix::SparseBlockMatrix( ): + _blockCols(0), _hasStorage(true) + { + } + + template + void SparseBlockMatrix::clear(bool dealloc) { +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_blockCols.size() > 100) +# endif + for (int i=0; i < static_cast(_blockCols.size()); ++i) { + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + if (_hasStorage && dealloc) + delete b; + else + b->setZero(); + } + if (_hasStorage && dealloc) + _blockCols[i].clear(); + } + } + + template + SparseBlockMatrix::~SparseBlockMatrix(){ + if (_hasStorage) + clear(true); + } + + template + typename SparseBlockMatrix::SparseMatrixBlock* SparseBlockMatrix::block(int r, int c, bool alloc) { + typename SparseBlockMatrix::IntBlockMap::iterator it =_blockCols[c].find(r); + typename SparseBlockMatrix::SparseMatrixBlock* _block=0; + if (it==_blockCols[c].end()){ + if (!_hasStorage && ! alloc ) + return 0; + else { + int rb=rowsOfBlock(r); + int cb=colsOfBlock(c); + _block=new typename SparseBlockMatrix::SparseMatrixBlock(rb,cb); + _block->setZero(); + std::pair < typename SparseBlockMatrix::IntBlockMap::iterator, bool> result + =_blockCols[c].insert(std::make_pair(r,_block)); (void) result; + assert (result.second); + } + } else { + _block=it->second; + } + return _block; + } + + template + const typename SparseBlockMatrix::SparseMatrixBlock* SparseBlockMatrix::block(int r, int c) const { + typename SparseBlockMatrix::IntBlockMap::const_iterator it =_blockCols[c].find(r); + if (it==_blockCols[c].end()) + return 0; + return it->second; + } + + + template + SparseBlockMatrix* SparseBlockMatrix::clone() const { + SparseBlockMatrix* ret= new SparseBlockMatrix(&_rowBlockIndices[0], &_colBlockIndices[0], _rowBlockIndices.size(), _colBlockIndices.size()); + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* b=new typename SparseBlockMatrix::SparseMatrixBlock(*it->second); + ret->_blockCols[i].insert(std::make_pair(it->first, b)); + } + } + ret->_hasStorage=true; + return ret; + } + + + template + template + bool SparseBlockMatrix::transpose(SparseBlockMatrix*& dest) const { + if (! dest){ + dest=new SparseBlockMatrix(&_colBlockIndices[0], &_rowBlockIndices[0], _colBlockIndices.size(), _rowBlockIndices.size()); + } else { + if (! dest->_hasStorage) + return false; + if(_rowBlockIndices.size()!=dest->_colBlockIndices.size()) + return false; + if (_colBlockIndices.size()!=dest->_rowBlockIndices.size()) + return false; + for (size_t i=0; i<_rowBlockIndices.size(); ++i){ + if(_rowBlockIndices[i]!=dest->_colBlockIndices[i]) + return false; + } + for (size_t i=0; i<_colBlockIndices.size(); ++i){ + if(_colBlockIndices[i]!=dest->_rowBlockIndices[i]) + return false; + } + } + + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* s=it->second; + typename SparseBlockMatrix::SparseMatrixBlock* d=dest->block(i,it->first,true); + *d = s->transpose(); + } + } + return true; + } + + template + bool SparseBlockMatrix::add(SparseBlockMatrix*& dest) const { + if (! dest){ + dest=new SparseBlockMatrix(&_rowBlockIndices[0], &_colBlockIndices[0], _rowBlockIndices.size(), _colBlockIndices.size()); + } else { + if (! dest->_hasStorage) + return false; + if(_rowBlockIndices.size()!=dest->_rowBlockIndices.size()) + return false; + if (_colBlockIndices.size()!=dest->_colBlockIndices.size()) + return false; + for (size_t i=0; i<_rowBlockIndices.size(); ++i){ + if(_rowBlockIndices[i]!=dest->_rowBlockIndices[i]) + return false; + } + for (size_t i=0; i<_colBlockIndices.size(); ++i){ + if(_colBlockIndices[i]!=dest->_colBlockIndices[i]) + return false; + } + } + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* s=it->second; + typename SparseBlockMatrix::SparseMatrixBlock* d=dest->block(it->first,i,true); + (*d)+=*s; + } + } + return true; + } + + template + template < class MatrixResultType, class MatrixFactorType > + bool SparseBlockMatrix::multiply(SparseBlockMatrix*& dest, const SparseBlockMatrix * M) const { + // sanity check + if (_colBlockIndices.size()!=M->_rowBlockIndices.size()) + return false; + for (size_t i=0; i<_colBlockIndices.size(); ++i){ + if (_colBlockIndices[i]!=M->_rowBlockIndices[i]) + return false; + } + if (! dest) { + dest=new SparseBlockMatrix(&_rowBlockIndices[0],&(M->_colBlockIndices[0]), _rowBlockIndices.size(), M->_colBlockIndices.size() ); + } + if (! dest->_hasStorage) + return false; + for (size_t i=0; i_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=M->_blockCols[i].begin(); it!=M->_blockCols[i].end(); ++it){ + // look for a non-zero block in a row of column it + int colM=i; + const typename SparseBlockMatrix::SparseMatrixBlock *b=it->second; + typename SparseBlockMatrix::IntBlockMap::const_iterator rbt=_blockCols[it->first].begin(); + while(rbt!=_blockCols[it->first].end()){ + //int colA=it->first; + int rowA=rbt->first; + typename SparseBlockMatrix::SparseMatrixBlock *a=rbt->second; + typename SparseBlockMatrix::SparseMatrixBlock *c=dest->block(rowA,colM,true); + assert (c->rows()==a->rows()); + assert (c->cols()==b->cols()); + ++rbt; + (*c)+=(*a)*(*b); + } + } + } + return false; + } + + template + void SparseBlockMatrix::multiply(double*& dest, const double* src) const { + if (! dest){ + dest=new double [_rowBlockIndices[_rowBlockIndices.size()-1] ]; + memset(dest,0, _rowBlockIndices[_rowBlockIndices.size()-1]*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, rows()); + const Eigen::Map srcVec(src, cols()); + + for (size_t i=0; i<_blockCols.size(); ++i){ + int srcOffset = i ? _colBlockIndices[i-1] : 0; + + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + int destOffset = it->first ? _rowBlockIndices[it->first - 1] : 0; + // destVec += *a * srcVec (according to the sub-vector parts) + internal::axpy(*a, srcVec, srcOffset, destVec, destOffset); + } + } + } + + template + void SparseBlockMatrix::multiplySymmetricUpperTriangle(double*& dest, const double* src) const + { + if (! dest){ + dest=new double [_rowBlockIndices[_rowBlockIndices.size()-1] ]; + memset(dest,0, _rowBlockIndices[_rowBlockIndices.size()-1]*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, rows()); + const Eigen::Map srcVec(src, cols()); + + for (size_t i=0; i<_blockCols.size(); ++i){ + int srcOffset = colBaseOfBlock(i); + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + int destOffset = rowBaseOfBlock(it->first); + if (destOffset > srcOffset) // only upper triangle + break; + // destVec += *a * srcVec (according to the sub-vector parts) + internal::axpy(*a, srcVec, srcOffset, destVec, destOffset); + if (destOffset < srcOffset) + internal::atxpy(*a, srcVec, destOffset, destVec, srcOffset); + } + } + } + + template + void SparseBlockMatrix::rightMultiply(double*& dest, const double* src) const { + int destSize=cols(); + + if (! dest){ + dest=new double [ destSize ]; + memset(dest,0, destSize*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, destSize); + Eigen::Map srcVec(src, rows()); + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int i=0; i < static_cast(_blockCols.size()); ++i){ + int destOffset = colBaseOfBlock(i); + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); + it!=_blockCols[i].end(); + ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + int srcOffset = rowBaseOfBlock(it->first); + // destVec += *a.transpose() * srcVec (according to the sub-vector parts) + internal::atxpy(*a, srcVec, srcOffset, destVec, destOffset); + } + } + + } + + template + void SparseBlockMatrix::scale(double a_) { + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + *a *= a_; + } + } + } + + template + SparseBlockMatrix* SparseBlockMatrix::slice(int rmin, int rmax, int cmin, int cmax, bool alloc) const { + int m=rmax-rmin; + int n=cmax-cmin; + int rowIdx [m]; + rowIdx[0] = rowsOfBlock(rmin); + for (int i=1; i::SparseBlockMatrix* s=new SparseBlockMatrix(rowIdx, colIdx, m, n, true); + for (int i=0; i::IntBlockMap::const_iterator it=_blockCols[mc].begin(); it!=_blockCols[mc].end(); ++it){ + if (it->first >= rmin && it->first < rmax){ + typename SparseBlockMatrix::SparseMatrixBlock* b = alloc ? new typename SparseBlockMatrix::SparseMatrixBlock (* (it->second) ) : it->second; + s->_blockCols[i].insert(std::make_pair(it->first-rmin, b)); + } + } + } + s->_hasStorage=alloc; + return s; + } + + template + size_t SparseBlockMatrix::nonZeroBlocks() const { + size_t count=0; + for (size_t i=0; i<_blockCols.size(); ++i) + count+=_blockCols[i].size(); + return count; + } + + template + size_t SparseBlockMatrix::nonZeros() const{ + if (MatrixType::SizeAtCompileTime != Eigen::Dynamic) { + size_t nnz = nonZeroBlocks() * MatrixType::SizeAtCompileTime; + return nnz; + } else { + size_t count=0; + for (size_t i=0; i<_blockCols.size(); ++i){ + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* a=it->second; + count += a->cols()*a->rows(); + } + } + return count; + } + } + + template + std::ostream& operator << (std::ostream& os, const SparseBlockMatrix& m){ + os << "RBI: " << m.rowBlockIndices().size(); + for (size_t i=0; i::IntBlockMap::const_iterator it=m.blockCols()[i].begin(); it!=m.blockCols()[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + os << "BLOCK: " << it->first << " " << i << std::endl; + os << *b << std::endl; + } + } + return os; + } + + template + bool SparseBlockMatrix::symmPermutation(SparseBlockMatrix*& dest, const int* pinv, bool upperTriangle) const{ + // compute the permuted version of the new row/column layout + size_t n=_rowBlockIndices.size(); + // computed the block sizes + int blockSizes[_rowBlockIndices.size()]; + blockSizes[0]=_rowBlockIndices[0]; + for (size_t i=1; i_rowBlockIndices.size()!=n) + return false; + if (dest->_colBlockIndices.size()!=n) + return false; + for (size_t i=0; i_rowBlockIndices[i]!=pBlockIndices[i]) + return false; + if (dest->_colBlockIndices[i]!=pBlockIndices[i]) + return false; + } + dest->clear(); + } + // now ready to permute the columns + for (size_t i=0; i::IntBlockMap::const_iterator it=_blockCols[i].begin(); + it!=_blockCols[i].end(); ++it){ + int pj=pinv[it->first]; + + const typename SparseBlockMatrix::SparseMatrixBlock* s=it->second; + + typename SparseBlockMatrix::SparseMatrixBlock* b=0; + if (! upperTriangle || pj<=pi) { + b=dest->block(pj,pi,true); + assert(b->cols()==s->cols()); + assert(b->rows()==s->rows()); + *b=*s; + } else { + b=dest->block(pi,pj,true); + assert(b); + assert(b->rows()==s->cols()); + assert(b->cols()==s->rows()); + *b=s->transpose(); + } + } + //cerr << endl; + // within each row, + } + return true; + + } + + template + int SparseBlockMatrix::fillCCS(double* Cx, bool upperTriangle) const + { + assert(Cx && "Target destination is NULL"); + double* CxStart = Cx; + for (size_t i=0; i<_blockCols.size(); ++i){ + int cstart=i ? _colBlockIndices[i-1] : 0; + int csize=colsOfBlock(i); + for (int c=0; c::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + int rstart=it->first ? _rowBlockIndices[it->first-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + memcpy(Cx, b->data() + c*b->rows(), elemsToCopy * sizeof(double)); + Cx += elemsToCopy; + + } + } + } + return Cx - CxStart; + } + + template + int SparseBlockMatrix::fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle) const + { + assert(Cp && Ci && Cx && "Target destination is NULL"); + int nz=0; + for (size_t i=0; i<_blockCols.size(); ++i){ + int cstart=i ? _colBlockIndices[i-1] : 0; + int csize=colsOfBlock(i); + for (int c=0; c::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it){ + const typename SparseBlockMatrix::SparseMatrixBlock* b=it->second; + int rstart=it->first ? _rowBlockIndices[it->first-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + for (int r=0; r + void SparseBlockMatrix::fillBlockStructure(MatrixStructure& ms) const + { + int n = _colBlockIndices.size(); + int nzMax = (int)nonZeroBlocks(); + + ms.alloc(n, nzMax); + ms.m = _rowBlockIndices.size(); + + int nz = 0; + int* Cp = ms.Ap; + int* Ci = ms.Aii; + for (int i = 0; i < static_cast(_blockCols.size()); ++i){ + *Cp = nz; + const int& c = i; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it) { + const int& r = it->first; + if (r <= c) { + *Ci++ = r; + ++nz; + } + } + Cp++; + } + *Cp=nz; + assert(nz <= nzMax); + } + + template + bool SparseBlockMatrix::writeOctave(const char* filename, bool upperTriangle) const + { + std::string name = filename; + std::string::size_type lastDot = name.find_last_of('.'); + if (lastDot != std::string::npos) + name = name.substr(0, lastDot); + + std::vector entries; + for (size_t i = 0; i<_blockCols.size(); ++i){ + const int& c = i; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it=_blockCols[i].begin(); it!=_blockCols[i].end(); ++it) { + const int& r = it->first; + const MatrixType& m = *(it->second); + for (int cc = 0; cc < m.cols(); ++cc) + for (int rr = 0; rr < m.rows(); ++rr) { + int aux_r = rowBaseOfBlock(r) + rr; + int aux_c = colBaseOfBlock(c) + cc; + entries.push_back(TripletEntry(aux_r, aux_c, m(rr, cc))); + if (upperTriangle && r != c) { + entries.push_back(TripletEntry(aux_c, aux_r, m(rr, cc))); + } + } + } + } + + int nz = entries.size(); + std::sort(entries.begin(), entries.end(), TripletColSort()); + + std::ofstream fout(filename); + fout << "# name: " << name << std::endl; + fout << "# type: sparse matrix" << std::endl; + fout << "# nnz: " << nz << std::endl; + fout << "# rows: " << rows() << std::endl; + fout << "# columns: " << cols() << std::endl; + fout << std::setprecision(9) << std::fixed << std::endl; + + for (std::vector::const_iterator it = entries.begin(); it != entries.end(); ++it) { + const TripletEntry& entry = *it; + fout << entry.r+1 << " " << entry.c+1 << " " << entry.x << std::endl; + } + return fout.good(); + } + + template + int SparseBlockMatrix::fillSparseBlockMatrixCCS(SparseBlockMatrixCCS& blockCCS) const + { + blockCCS.blockCols().resize(blockCols().size()); + int numblocks = 0; + for (size_t i = 0; i < blockCols().size(); ++i) { + const IntBlockMap& row = blockCols()[i]; + typename SparseBlockMatrixCCS::SparseColumn& dest = blockCCS.blockCols()[i]; + dest.clear(); + dest.reserve(row.size()); + for (typename IntBlockMap::const_iterator it = row.begin(); it != row.end(); ++it) { + dest.push_back(typename SparseBlockMatrixCCS::RowBlock(it->first, it->second)); + ++numblocks; + } + } + return numblocks; + } + + template + int SparseBlockMatrix::fillSparseBlockMatrixCCSTransposed(SparseBlockMatrixCCS& blockCCS) const + { + blockCCS.blockCols().clear(); + blockCCS.blockCols().resize(_rowBlockIndices.size()); + int numblocks = 0; + for (size_t i = 0; i < blockCols().size(); ++i) { + const IntBlockMap& row = blockCols()[i]; + for (typename IntBlockMap::const_iterator it = row.begin(); it != row.end(); ++it) { + typename SparseBlockMatrixCCS::SparseColumn& dest = blockCCS.blockCols()[it->first]; + dest.push_back(typename SparseBlockMatrixCCS::RowBlock(i, it->second)); + ++numblocks; + } + } + return numblocks; + } + + template + void SparseBlockMatrix::takePatternFromHash(SparseBlockMatrixHashMap& hashMatrix) + { + // sort the sparse columns and add them to the map structures by + // exploiting that we are inserting a sorted structure + typedef std::pair SparseColumnPair; + typedef typename SparseBlockMatrixHashMap::SparseColumn HashSparseColumn; + for (size_t i = 0; i < hashMatrix.blockCols().size(); ++i) { + // prepare a temporary vector for sorting + HashSparseColumn& column = hashMatrix.blockCols()[i]; + if (column.size() == 0) + continue; + std::vector sparseRowSorted; // temporary structure + sparseRowSorted.reserve(column.size()); + for (typename HashSparseColumn::const_iterator it = column.begin(); it != column.end(); ++it) + sparseRowSorted.push_back(*it); + std::sort(sparseRowSorted.begin(), sparseRowSorted.end(), CmpPairFirst()); + // try to free some memory early + HashSparseColumn aux; + swap(aux, column); + // now insert sorted vector to the std::map structure + IntBlockMap& destColumnMap = blockCols()[i]; + destColumnMap.insert(sparseRowSorted[0]); + for (size_t j = 1; j < sparseRowSorted.size(); ++j) { + typename SparseBlockMatrix::IntBlockMap::iterator hint = destColumnMap.end(); + --hint; // cppreference says the element goes after the hint (until C++11) + destColumnMap.insert(hint, sparseRowSorted[j]); + } + } + } + +}// end namespace diff --git a/Thirdparty/g2o/g2o/core/sparse_block_matrix_ccs.h b/Thirdparty/g2o/g2o/core/sparse_block_matrix_ccs.h new file mode 100644 index 0000000000..eb9042c218 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_block_matrix_ccs.h @@ -0,0 +1,282 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SPARSE_BLOCK_MATRIX_CCS_H +#define G2O_SPARSE_BLOCK_MATRIX_CCS_H + +#include +#include +#include + +#include "../../config.h" +#include "matrix_operations.h" + +#ifdef _MSC_VER +#include +#else +#include +#endif + +namespace g2o { + + /** + * \brief Sparse matrix which uses blocks + * + * This class is used as a const view on a SparseBlockMatrix + * which allows a faster iteration over the elements of the + * matrix. + */ + template + class SparseBlockMatrixCCS + { + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;} + //! rows of the matrix + int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;} + + /** + * \brief A block within a column + */ + struct RowBlock + { + int row; ///< row of the block + MatrixType* block; ///< matrix pointer for the block + RowBlock() : row(-1), block(0) {} + RowBlock(int r, MatrixType* b) : row(r), block(b) {} + bool operator<(const RowBlock& other) const { return row < other.row;} + }; + typedef std::vector SparseColumn; + + SparseBlockMatrixCCS(const std::vector& rowIndices, const std::vector& colIndices) : + _rowBlockIndices(rowIndices), _colBlockIndices(colIndices) + {} + + //! how many rows does the block at block-row r has? + int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; } + + //! how many cols does the block at block-col c has? + int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; } + + //! where does the row at block-row r start? + int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; } + + //! where does the col at block-col r start? + int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; } + + //! the block matrices per block-column + const std::vector& blockCols() const { return _blockCols;} + std::vector& blockCols() { return _blockCols;} + + //! indices of the row blocks + const std::vector& rowBlockIndices() const { return _rowBlockIndices;} + + //! indices of the column blocks + const std::vector& colBlockIndices() const { return _colBlockIndices;} + + void rightMultiply(double*& dest, const double* src) const + { + int destSize=cols(); + + if (! dest){ + dest=new double [ destSize ]; + memset(dest,0, destSize*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, destSize); + Eigen::Map srcVec(src, rows()); + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int i=0; i < static_cast(_blockCols.size()); ++i){ + int destOffset = colBaseOfBlock(i); + for (typename SparseColumn::const_iterator it = _blockCols[i].begin(); it!=_blockCols[i].end(); ++it) { + const SparseMatrixBlock* a = it->block; + int srcOffset = rowBaseOfBlock(it->row); + // destVec += *a.transpose() * srcVec (according to the sub-vector parts) + internal::atxpy(*a, srcVec, srcOffset, destVec, destOffset); + } + } + } + + /** + * sort the blocks in each column + */ + void sortColumns() + { + for (int i=0; i < static_cast(_blockCols.size()); ++i){ + std::sort(_blockCols[i].begin(), _blockCols[i].end()); + } + } + + /** + * fill the CCS arrays of a matrix, arrays have to be allocated beforehand + */ + int fillCCS(int* Cp, int* Ci, double* Cx, bool upperTriangle = false) const + { + assert(Cp && Ci && Cx && "Target destination is NULL"); + int nz=0; + for (size_t i=0; i<_blockCols.size(); ++i){ + int cstart=i ? _colBlockIndices[i-1] : 0; + int csize=colsOfBlock(i); + for (int c=0; cblock; + int rstart=it->row ? _rowBlockIndices[it->row-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + for (int r=0; rblock; + int rstart = it->row ? _rowBlockIndices[it->row-1] : 0; + + int elemsToCopy = b->rows(); + if (upperTriangle && rstart == cstart) + elemsToCopy = c + 1; + memcpy(Cx, b->data() + c*b->rows(), elemsToCopy * sizeof(double)); + Cx += elemsToCopy; + + } + } + cstart = _colBlockIndices[i]; + } + return Cx - CxStart; + } + + protected: + const std::vector& _rowBlockIndices; ///< vector of the indices of the blocks along the rows. + const std::vector& _colBlockIndices; ///< vector of the indices of the blocks along the cols + std::vector _blockCols; ///< the matrices stored in CCS order + }; + + + + /** + * \brief Sparse matrix which uses blocks based on hash structures + * + * This class is used to construct the pattern of a sparse block matrix + */ + template + class SparseBlockMatrixHashMap + { + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + int cols() const {return _colBlockIndices.size() ? _colBlockIndices.back() : 0;} + //! rows of the matrix + int rows() const {return _rowBlockIndices.size() ? _rowBlockIndices.back() : 0;} + + typedef std::tr1::unordered_map SparseColumn; + + SparseBlockMatrixHashMap(const std::vector& rowIndices, const std::vector& colIndices) : + _rowBlockIndices(rowIndices), _colBlockIndices(colIndices) + {} + + //! how many rows does the block at block-row r has? + int rowsOfBlock(int r) const { return r ? _rowBlockIndices[r] - _rowBlockIndices[r-1] : _rowBlockIndices[0] ; } + + //! how many cols does the block at block-col c has? + int colsOfBlock(int c) const { return c ? _colBlockIndices[c] - _colBlockIndices[c-1] : _colBlockIndices[0]; } + + //! where does the row at block-row r start? + int rowBaseOfBlock(int r) const { return r ? _rowBlockIndices[r-1] : 0 ; } + + //! where does the col at block-col r start? + int colBaseOfBlock(int c) const { return c ? _colBlockIndices[c-1] : 0 ; } + + //! the block matrices per block-column + const std::vector& blockCols() const { return _blockCols;} + std::vector& blockCols() { return _blockCols;} + + //! indices of the row blocks + const std::vector& rowBlockIndices() const { return _rowBlockIndices;} + + //! indices of the column blocks + const std::vector& colBlockIndices() const { return _colBlockIndices;} + + /** + * add a block to the pattern, return a pointer to the added block + */ + MatrixType* addBlock(int r, int c, bool zeroBlock = false) + { + assert(c <(int)_blockCols.size() && "accessing column which is not available"); + SparseColumn& sparseColumn = _blockCols[c]; + typename SparseColumn::iterator foundIt = sparseColumn.find(r); + if (foundIt == sparseColumn.end()) { + int rb = rowsOfBlock(r); + int cb = colsOfBlock(c); + MatrixType* m = new MatrixType(rb, cb); + if (zeroBlock) + m->setZero(); + sparseColumn[r] = m; + return m; + } + return foundIt->second; + } + + protected: + const std::vector& _rowBlockIndices; ///< vector of the indices of the blocks along the rows. + const std::vector& _colBlockIndices; ///< vector of the indices of the blocks along the cols + std::vector _blockCols; ///< the matrices stored in CCS order + }; + +} //end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/sparse_block_matrix_diagonal.h b/Thirdparty/g2o/g2o/core/sparse_block_matrix_diagonal.h new file mode 100644 index 0000000000..7b13b9f2f3 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_block_matrix_diagonal.h @@ -0,0 +1,108 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SPARSE_BLOCK_MATRIX_DIAGONAL_H +#define G2O_SPARSE_BLOCK_MATRIX_DIAGONAL_H + +#include +#include +#include + +#include "../../config.h" +#include "matrix_operations.h" + +namespace g2o { + + /** + * \brief Sparse matrix which uses blocks on the diagonal + * + * This class is used as a const view on a SparseBlockMatrix + * which allows a faster iteration over the elements of the + * matrix. + */ + template + class SparseBlockMatrixDiagonal + { + public: + //! this is the type of the elementary block, it is an Eigen::Matrix. + typedef MatrixType SparseMatrixBlock; + + //! columns of the matrix + int cols() const {return _blockIndices.size() ? _blockIndices.back() : 0;} + //! rows of the matrix + int rows() const {return _blockIndices.size() ? _blockIndices.back() : 0;} + + typedef std::vector > DiagonalVector; + + SparseBlockMatrixDiagonal(const std::vector& blockIndices) : + _blockIndices(blockIndices) + {} + + //! how many rows/cols does the block at block-row / block-column r has? + inline int dimOfBlock(int r) const { return r ? _blockIndices[r] - _blockIndices[r-1] : _blockIndices[0] ; } + + //! where does the row /col at block-row / block-column r starts? + inline int baseOfBlock(int r) const { return r ? _blockIndices[r-1] : 0 ; } + + //! the block matrices per block-column + const DiagonalVector& diagonal() const { return _diagonal;} + DiagonalVector& diagonal() { return _diagonal;} + + //! indices of the row blocks + const std::vector& blockIndices() const { return _blockIndices;} + + void multiply(double*& dest, const double* src) const + { + int destSize=cols(); + if (! dest) { + dest=new double[destSize]; + memset(dest,0, destSize*sizeof(double)); + } + + // map the memory by Eigen + Eigen::Map destVec(dest, destSize); + Eigen::Map srcVec(src, rows()); + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) schedule(dynamic, 10) +# endif + for (int i=0; i < static_cast(_diagonal.size()); ++i){ + int destOffset = baseOfBlock(i); + int srcOffset = destOffset; + const SparseMatrixBlock& A = _diagonal[i]; + // destVec += *A.transpose() * srcVec (according to the sub-vector parts) + internal::axpy(A, srcVec, srcOffset, destVec, destOffset); + } + } + + protected: + const std::vector& _blockIndices; ///< vector of the indices of the blocks along the diagonal + DiagonalVector _diagonal; + }; + +} //end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/core/sparse_block_matrix_test.cpp b/Thirdparty/g2o/g2o/core/sparse_block_matrix_test.cpp new file mode 100644 index 0000000000..42a4560824 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_block_matrix_test.cpp @@ -0,0 +1,107 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "sparse_block_matrix.h" +#include + +using namespace std; +using namespace g2o; +using namespace Eigen; + +typedef SparseBlockMatrix< MatrixXd > +SparseBlockMatrixX; + +std::ostream& operator << (std::ostream& os, const SparseBlockMatrixX::SparseMatrixBlock& m) { + for (int i=0; iblock(0,0, true); + cerr << b->rows() << " " << b->cols() << endl; + for (int i=0; irows(); ++i) + for (int j=0; jcols(); ++j){ + (*b)(i,j)=i*b->cols()+j; + } + + + cerr << "block access 2" << endl; + b=M->block(0,2, true); + cerr << b->rows() << " " << b->cols() << endl; + for (int i=0; irows(); ++i) + for (int j=0; jcols(); ++j){ + (*b)(i,j)=i*b->cols()+j; + } + + b=M->block(3,2, true); + cerr << b->rows() << " " << b->cols() << endl; + for (int i=0; irows(); ++i) + for (int j=0; jcols(); ++j){ + (*b)(i,j)=i*b->cols()+j; + } + + cerr << *M << endl; + + cerr << "SUM" << endl; + + SparseBlockMatrixX* Ms=0; + M->add(Ms); + M->add(Ms); + cerr << *Ms; + + SparseBlockMatrixX* Mt=0; + M->transpose(Mt); + cerr << *Mt << endl; + + SparseBlockMatrixX* Mp=0; + M->multiply(Mp, Mt); + cerr << *Mp << endl; + + int iperm[]={3,2,1,0}; + SparseBlockMatrixX* PMp=0; + + Mp->symmPermutation(PMp,iperm, false); + cerr << *PMp << endl; + + PMp->clear(true); + Mp->block(3,0)->fill(0.); + Mp->symmPermutation(PMp,iperm, true); + cerr << *PMp << endl; + + + +} diff --git a/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp b/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp new file mode 100644 index 0000000000..7c316e656a --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_optimizer.cpp @@ -0,0 +1,615 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "sparse_optimizer.h" + +#include +#include +#include +#include +#include +#include + +#include "estimate_propagator.h" +#include "optimization_algorithm.h" +#include "batch_stats.h" +#include "hyper_graph_action.h" +#include "robust_kernel.h" +#include "../stuff/timeutil.h" +#include "../stuff/macros.h" +#include "../stuff/misc.h" +#include "../../config.h" + +namespace g2o{ + using namespace std; + + + SparseOptimizer::SparseOptimizer() : + _forceStopFlag(0), _verbose(false), _algorithm(0), _computeBatchStatistics(false) + { + _graphActions.resize(AT_NUM_ELEMENTS); + } + + SparseOptimizer::~SparseOptimizer(){ + delete _algorithm; + G2OBatchStatistics::setGlobalStats(0); + } + + void SparseOptimizer::computeActiveErrors() + { + // call the callbacks in case there is something registered + HyperGraphActionSet& actions = _graphActions[AT_COMPUTEACTIVERROR]; + if (actions.size() > 0) { + for (HyperGraphActionSet::iterator it = actions.begin(); it != actions.end(); ++it) + (*(*it))(this); + } + +# ifdef G2O_OPENMP +# pragma omp parallel for default (shared) if (_activeEdges.size() > 50) +# endif + for (int k = 0; k < static_cast(_activeEdges.size()); ++k) { + OptimizableGraph::Edge* e = _activeEdges[k]; + e->computeError(); + } + +# ifndef NDEBUG + for (int k = 0; k < static_cast(_activeEdges.size()); ++k) { + OptimizableGraph::Edge* e = _activeEdges[k]; + bool hasNan = arrayHasNaN(e->errorData(), e->dimension()); + if (hasNan) { + cerr << "computeActiveErrors(): found NaN in error for edge " << e << endl; + } + } +# endif + + } + + double SparseOptimizer::activeChi2( ) const + { + double chi = 0.0; + for (EdgeContainer::const_iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) { + const OptimizableGraph::Edge* e = *it; + chi += e->chi2(); + } + return chi; + } + + double SparseOptimizer::activeRobustChi2() const + { + Eigen::Vector3d rho; + double chi = 0.0; + for (EdgeContainer::const_iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) { + const OptimizableGraph::Edge* e = *it; + if (e->robustKernel()) { + e->robustKernel()->robustify(e->chi2(), rho); + chi += rho[0]; + } + else + chi += e->chi2(); + } + return chi; + } + + OptimizableGraph::Vertex* SparseOptimizer::findGauge(){ + if (vertices().empty()) + return 0; + + int maxDim=0; + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + maxDim=std::max(maxDim,v->dimension()); + } + + OptimizableGraph::Vertex* rut=0; + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + if (v->dimension()==maxDim){ + rut=v; + break; + } + } + return rut; + } + + bool SparseOptimizer::gaugeFreedom() + { + if (vertices().empty()) + return false; + + int maxDim=0; + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + maxDim = std::max(maxDim,v->dimension()); + } + + for (HyperGraph::VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it){ + OptimizableGraph::Vertex* v=static_cast(it->second); + if (v->dimension() == maxDim) { + // test for fixed vertex + if (v->fixed()) { + return false; + } + // test for full dimension prior + for (HyperGraph::EdgeSet::const_iterator eit = v->edges().begin(); eit != v->edges().end(); ++eit) { + OptimizableGraph::Edge* e = static_cast(*eit); + if (e->vertices().size() == 1 && e->dimension() == maxDim) + return false; + } + } + } + return true; + } + + bool SparseOptimizer::buildIndexMapping(SparseOptimizer::VertexContainer& vlist){ + if (! vlist.size()){ + _ivMap.clear(); + return false; + } + + _ivMap.resize(vlist.size()); + size_t i = 0; + for (int k=0; k<2; k++) + for (VertexContainer::iterator it=vlist.begin(); it!=vlist.end(); ++it){ + OptimizableGraph::Vertex* v = *it; + if (! v->fixed()){ + if (static_cast(v->marginalized()) == k){ + v->setHessianIndex(i); + _ivMap[i]=v; + i++; + } + } + else { + v->setHessianIndex(-1); + } + } + _ivMap.resize(i); + return true; + } + + void SparseOptimizer::clearIndexMapping(){ + for (size_t i=0; i<_ivMap.size(); ++i){ + _ivMap[i]->setHessianIndex(-1); + _ivMap[i]=0; + } + } + + bool SparseOptimizer::initializeOptimization(int level){ + HyperGraph::VertexSet vset; + for (VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it) + vset.insert(it->second); + return initializeOptimization(vset,level); + } + + bool SparseOptimizer::initializeOptimization(HyperGraph::VertexSet& vset, int level){ + if (edges().size() == 0) { + cerr << __PRETTY_FUNCTION__ << ": Attempt to initialize an empty graph" << endl; + return false; + } + bool workspaceAllocated = _jacobianWorkspace.allocate(); (void) workspaceAllocated; + assert(workspaceAllocated && "Error while allocating memory for the Jacobians"); + clearIndexMapping(); + _activeVertices.clear(); + _activeVertices.reserve(vset.size()); + _activeEdges.clear(); + set auxEdgeSet; // temporary structure to avoid duplicates + for (HyperGraph::VertexSet::iterator it=vset.begin(); it!=vset.end(); ++it){ + OptimizableGraph::Vertex* v= (OptimizableGraph::Vertex*) *it; + const OptimizableGraph::EdgeSet& vEdges=v->edges(); + // count if there are edges in that level. If not remove from the pool + int levelEdges=0; + for (OptimizableGraph::EdgeSet::const_iterator it=vEdges.begin(); it!=vEdges.end(); ++it){ + OptimizableGraph::Edge* e=reinterpret_cast(*it); + if (level < 0 || e->level() == level) { + + bool allVerticesOK = true; + for (vector::const_iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) { + if (vset.find(*vit) == vset.end()) { + allVerticesOK = false; + break; + } + } + if (allVerticesOK && !e->allVerticesFixed()) { + auxEdgeSet.insert(e); + levelEdges++; + } + + } + } + if (levelEdges){ + _activeVertices.push_back(v); + + // test for NANs in the current estimate if we are debugging +# ifndef NDEBUG + int estimateDim = v->estimateDimension(); + if (estimateDim > 0) { + Eigen::VectorXd estimateData(estimateDim); + if (v->getEstimateData(estimateData.data()) == true) { + int k; + bool hasNan = arrayHasNaN(estimateData.data(), estimateDim, &k); + if (hasNan) + cerr << __PRETTY_FUNCTION__ << ": Vertex " << v->id() << " contains a nan entry at index " << k << endl; + } + } +# endif + + } + } + + _activeEdges.reserve(auxEdgeSet.size()); + for (set::iterator it = auxEdgeSet.begin(); it != auxEdgeSet.end(); ++it) + _activeEdges.push_back(*it); + + sortVectorContainers(); + return buildIndexMapping(_activeVertices); + } + + bool SparseOptimizer::initializeOptimization(HyperGraph::EdgeSet& eset){ + bool workspaceAllocated = _jacobianWorkspace.allocate(); (void) workspaceAllocated; + assert(workspaceAllocated && "Error while allocating memory for the Jacobians"); + clearIndexMapping(); + _activeVertices.clear(); + _activeEdges.clear(); + _activeEdges.reserve(eset.size()); + set auxVertexSet; // temporary structure to avoid duplicates + for (HyperGraph::EdgeSet::iterator it=eset.begin(); it!=eset.end(); ++it){ + OptimizableGraph::Edge* e=(OptimizableGraph::Edge*)(*it); + for (vector::const_iterator vit = e->vertices().begin(); vit != e->vertices().end(); ++vit) { + auxVertexSet.insert(static_cast(*vit)); + } + _activeEdges.push_back(reinterpret_cast(*it)); + } + + _activeVertices.reserve(auxVertexSet.size()); + for (set::iterator it = auxVertexSet.begin(); it != auxVertexSet.end(); ++it) + _activeVertices.push_back(*it); + + sortVectorContainers(); + return buildIndexMapping(_activeVertices); + } + + void SparseOptimizer::setToOrigin(){ + for (VertexIDMap::iterator it=vertices().begin(); it!=vertices().end(); ++it) { + OptimizableGraph::Vertex* v = static_cast(it->second); + v->setToOrigin(); + } + } + + void SparseOptimizer::computeInitialGuess() + { + EstimatePropagator::PropagateCost costFunction(this); + computeInitialGuess(costFunction); + } + + void SparseOptimizer::computeInitialGuess(EstimatePropagatorCost& costFunction) + { + OptimizableGraph::VertexSet emptySet; + std::set backupVertices; + HyperGraph::VertexSet fixedVertices; // these are the root nodes where to start the initialization + for (EdgeContainer::iterator it = _activeEdges.begin(); it != _activeEdges.end(); ++it) { + OptimizableGraph::Edge* e = *it; + for (size_t i = 0; i < e->vertices().size(); ++i) { + OptimizableGraph::Vertex* v = static_cast(e->vertex(i)); + if (v->fixed()) + fixedVertices.insert(v); + else { // check for having a prior which is able to fully initialize a vertex + for (EdgeSet::const_iterator vedgeIt = v->edges().begin(); vedgeIt != v->edges().end(); ++vedgeIt) { + OptimizableGraph::Edge* vedge = static_cast(*vedgeIt); + if (vedge->vertices().size() == 1 && vedge->initialEstimatePossible(emptySet, v) > 0.) { + //cerr << "Initialize with prior for " << v->id() << endl; + vedge->initialEstimate(emptySet, v); + fixedVertices.insert(v); + } + } + } + if (v->hessianIndex() == -1) { + std::set::const_iterator foundIt = backupVertices.find(v); + if (foundIt == backupVertices.end()) { + v->push(); + backupVertices.insert(v); + } + } + } + } + + EstimatePropagator estimatePropagator(this); + estimatePropagator.propagate(fixedVertices, costFunction); + + // restoring the vertices that should not be initialized + for (std::set::iterator it = backupVertices.begin(); it != backupVertices.end(); ++it) { + Vertex* v = *it; + v->pop(); + } + if (verbose()) { + computeActiveErrors(); + cerr << "iteration= -1\t chi2= " << activeChi2() + << "\t time= 0.0" + << "\t cumTime= 0.0" + << "\t (using initial guess from " << costFunction.name() << ")" << endl; + } + } + + int SparseOptimizer::optimize(int iterations, bool online) + { + if (_ivMap.size() == 0) { + cerr << __PRETTY_FUNCTION__ << ": 0 vertices to optimize, maybe forgot to call initializeOptimization()" << endl; + return -1; + } + + int cjIterations=0; + double cumTime=0; + bool ok=true; + + ok = _algorithm->init(online); + if (! ok) { + cerr << __PRETTY_FUNCTION__ << " Error while initializing" << endl; + return -1; + } + + _batchStatistics.clear(); + if (_computeBatchStatistics) + _batchStatistics.resize(iterations); + + OptimizationAlgorithm::SolverResult result = OptimizationAlgorithm::OK; + for (int i=0; isolve(i, online); + ok = ( result == OptimizationAlgorithm::OK ); + + bool errorComputed = false; + if (_computeBatchStatistics) { + computeActiveErrors(); + errorComputed = true; + _batchStatistics[i].chi2 = activeRobustChi2(); + _batchStatistics[i].timeIteration = get_monotonic_time()-ts; + } + + if (verbose()){ + double dts = get_monotonic_time()-ts; + cumTime += dts; + if (! errorComputed) + computeActiveErrors(); + cerr << "iteration= " << i + << "\t chi2= " << FIXED(activeRobustChi2()) + << "\t time= " << dts + << "\t cumTime= " << cumTime + << "\t edges= " << _activeEdges.size(); + _algorithm->printVerbose(cerr); + cerr << endl; + } + ++cjIterations; + postIteration(i); + } + if (result == OptimizationAlgorithm::Fail) { + return 0; + } + return cjIterations; + } + + + void SparseOptimizer::update(const double* update) + { + // update the graph by calling oplus on the vertices + for (size_t i=0; i < _ivMap.size(); ++i) { + OptimizableGraph::Vertex* v= _ivMap[i]; +#ifndef NDEBUG + bool hasNan = arrayHasNaN(update, v->dimension()); + if (hasNan) + cerr << __PRETTY_FUNCTION__ << ": Update contains a nan for vertex " << v->id() << endl; +#endif + v->oplus(update); + update += v->dimension(); + } + } + + void SparseOptimizer::setComputeBatchStatistics(bool computeBatchStatistics) + { + if ((_computeBatchStatistics == true) && (computeBatchStatistics == false)) { + G2OBatchStatistics::setGlobalStats(0); + _batchStatistics.clear(); + } + _computeBatchStatistics = computeBatchStatistics; + } + + bool SparseOptimizer::updateInitialization(HyperGraph::VertexSet& vset, HyperGraph::EdgeSet& eset) + { + std::vector newVertices; + newVertices.reserve(vset.size()); + _activeVertices.reserve(_activeVertices.size() + vset.size()); + _activeEdges.reserve(_activeEdges.size() + eset.size()); + for (HyperGraph::EdgeSet::iterator it = eset.begin(); it != eset.end(); ++it) { + OptimizableGraph::Edge* e = static_cast(*it); + if (!e->allVerticesFixed()) _activeEdges.push_back(e); + } + + // update the index mapping + size_t next = _ivMap.size(); + for (HyperGraph::VertexSet::iterator it = vset.begin(); it != vset.end(); ++it) { + OptimizableGraph::Vertex* v=static_cast(*it); + if (! v->fixed()){ + if (! v->marginalized()){ + v->setHessianIndex(next); + _ivMap.push_back(v); + newVertices.push_back(v); + _activeVertices.push_back(v); + next++; + } + else // not supported right now + abort(); + } + else { + v->setHessianIndex(-1); + } + } + + //if (newVertices.size() != vset.size()) + //cerr << __PRETTY_FUNCTION__ << ": something went wrong " << PVAR(vset.size()) << " " << PVAR(newVertices.size()) << endl; + return _algorithm->updateStructure(newVertices, eset); + } + + void SparseOptimizer::sortVectorContainers() + { + // sort vector structures to get deterministic ordering based on IDs + sort(_activeVertices.begin(), _activeVertices.end(), VertexIDCompare()); + sort(_activeEdges.begin(), _activeEdges.end(), EdgeIDCompare()); + } + + void SparseOptimizer::clear() { + _ivMap.clear(); + _activeVertices.clear(); + _activeEdges.clear(); + OptimizableGraph::clear(); + } + + SparseOptimizer::VertexContainer::const_iterator SparseOptimizer::findActiveVertex(const OptimizableGraph::Vertex* v) const + { + VertexContainer::const_iterator lower = lower_bound(_activeVertices.begin(), _activeVertices.end(), v, VertexIDCompare()); + if (lower == _activeVertices.end()) + return _activeVertices.end(); + if ((*lower) == v) + return lower; + return _activeVertices.end(); + } + + SparseOptimizer::EdgeContainer::const_iterator SparseOptimizer::findActiveEdge(const OptimizableGraph::Edge* e) const + { + EdgeContainer::const_iterator lower = lower_bound(_activeEdges.begin(), _activeEdges.end(), e, EdgeIDCompare()); + if (lower == _activeEdges.end()) + return _activeEdges.end(); + if ((*lower) == e) + return lower; + return _activeEdges.end(); + } + + void SparseOptimizer::push(SparseOptimizer::VertexContainer& vlist) + { + for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it) + (*it)->push(); + } + + void SparseOptimizer::pop(SparseOptimizer::VertexContainer& vlist) + { + for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it) + (*it)->pop(); + } + + void SparseOptimizer::push(HyperGraph::VertexSet& vlist) + { + for (HyperGraph::VertexSet::iterator it = vlist.begin(); it != vlist.end(); ++it) { + OptimizableGraph::Vertex* v = dynamic_cast(*it); + if (v) + v->push(); + else + cerr << __FUNCTION__ << ": FATAL PUSH SET" << endl; + } + } + + void SparseOptimizer::pop(HyperGraph::VertexSet& vlist) + { + for (HyperGraph::VertexSet::iterator it = vlist.begin(); it != vlist.end(); ++it){ + OptimizableGraph::Vertex* v = dynamic_cast (*it); + if (v) + v->pop(); + else + cerr << __FUNCTION__ << ": FATAL POP SET" << endl; + } + } + + void SparseOptimizer::discardTop(SparseOptimizer::VertexContainer& vlist) + { + for (VertexContainer::iterator it = vlist.begin(); it != vlist.end(); ++it) + (*it)->discardTop(); + } + + void SparseOptimizer::setVerbose(bool verbose) + { + _verbose = verbose; + } + + void SparseOptimizer::setAlgorithm(OptimizationAlgorithm* algorithm) + { + if (_algorithm) // reset the optimizer for the formerly used solver + _algorithm->setOptimizer(0); + _algorithm = algorithm; + if (_algorithm) + _algorithm->setOptimizer(this); + } + + bool SparseOptimizer::computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices){ + return _algorithm->computeMarginals(spinv, blockIndices); + } + + void SparseOptimizer::setForceStopFlag(bool* flag) + { + _forceStopFlag=flag; + } + + bool SparseOptimizer::removeVertex(HyperGraph::Vertex* v) + { + OptimizableGraph::Vertex* vv = static_cast(v); + if (vv->hessianIndex() >= 0) { + clearIndexMapping(); + _ivMap.clear(); + } + return HyperGraph::removeVertex(v); + } + + bool SparseOptimizer::addComputeErrorAction(HyperGraphAction* action) + { + std::pair insertResult = _graphActions[AT_COMPUTEACTIVERROR].insert(action); + return insertResult.second; + } + + bool SparseOptimizer::removeComputeErrorAction(HyperGraphAction* action) + { + return _graphActions[AT_COMPUTEACTIVERROR].erase(action) > 0; + } + + void SparseOptimizer::push() + { + push(_activeVertices); + } + + void SparseOptimizer::pop() + { + pop(_activeVertices); + } + + void SparseOptimizer::discardTop() + { + discardTop(_activeVertices); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/core/sparse_optimizer.h b/Thirdparty/g2o/g2o/core/sparse_optimizer.h new file mode 100644 index 0000000000..3b09f5a3d5 --- /dev/null +++ b/Thirdparty/g2o/g2o/core/sparse_optimizer.h @@ -0,0 +1,312 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_GRAPH_OPTIMIZER_CHOL_H_ +#define G2O_GRAPH_OPTIMIZER_CHOL_H_ + +#include "../stuff/macros.h" + +#include "optimizable_graph.h" +#include "sparse_block_matrix.h" +#include "batch_stats.h" + +#include + +namespace g2o { + + // forward declaration + class ActivePathCostFunction; + class OptimizationAlgorithm; + class EstimatePropagatorCost; + + class SparseOptimizer : public OptimizableGraph { + + public: + enum { + AT_COMPUTEACTIVERROR = OptimizableGraph::AT_NUM_ELEMENTS, + AT_NUM_ELEMENTS, // keep as last element + }; + + friend class ActivePathCostFunction; + + // Attention: _solver & _statistics is own by SparseOptimizer and will be + // deleted in its destructor. + SparseOptimizer(); + virtual ~SparseOptimizer(); + + // new interface for the optimizer + // the old functions will be dropped + /** + * Initializes the structures for optimizing a portion of the graph specified by a subset of edges. + * Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the + * schur complement or to set as fixed during the optimization. + * @param eset: the subgraph to be optimized. + * @returns false if somethings goes wrong + */ + virtual bool initializeOptimization(HyperGraph::EdgeSet& eset); + + /** + * Initializes the structures for optimizing a portion of the graph specified by a subset of vertices. + * Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the + * schur complement or to set as fixed during the optimization. + * @param vset: the subgraph to be optimized. + * @param level: is the level (in multilevel optimization) + * @returns false if somethings goes wrong + */ + virtual bool initializeOptimization(HyperGraph::VertexSet& vset, int level=0); + + /** + * Initializes the structures for optimizing the whole graph. + * Before calling it be sure to invoke marginalized() and fixed() to the vertices you want to include in the + * schur complement or to set as fixed during the optimization. + * @param level: is the level (in multilevel optimization) + * @returns false if somethings goes wrong + */ + virtual bool initializeOptimization(int level=0); + + /** + * HACK updating the internal structures for online processing + */ + virtual bool updateInitialization(HyperGraph::VertexSet& vset, HyperGraph::EdgeSet& eset); + + /** + * Propagates an initial guess from the vertex specified as origin. + * It should be called after initializeOptimization(...), as it relies on the _activeVertices/_edges structures. + * It constructs a set of trees starting from the nodes in the graph which are fixed and eligible for preforming optimization. + * The trees are constructed by utlizing a cost-function specified. + * @param costFunction: the cost function used + * @patam maxDistance: the distance where to stop the search + */ + virtual void computeInitialGuess(); + + /** + * Same as above but using a specific propagator + */ + virtual void computeInitialGuess(EstimatePropagatorCost& propagator); + + /** + * sets all vertices to their origin. + */ + virtual void setToOrigin(); + + + /** + * starts one optimization run given the current configuration of the graph, + * and the current settings stored in the class instance. + * It can be called only after initializeOptimization + */ + int optimize(int iterations, bool online = false); + + /** + * computes the blocks of the inverse of the specified pattern. + * the pattern is given via pairs of the blocks in the hessian + * @param blockIndices: the pattern + * @param spinv: the sparse block matrix with the result + * @returns false if the operation is not supported by the solver + */ + bool computeMarginals(SparseBlockMatrix& spinv, const std::vector >& blockIndices); + + /** + * computes the inverse of the specified vertex. + * @param vertex: the vertex whose state is to be marginalised + * @param spinv: the sparse block matrix with the result + * @returns false if the operation is not supported by the solver + */ + bool computeMarginals(SparseBlockMatrix& spinv, const Vertex* vertex) { + if (vertex->hessianIndex() < 0) { + return false; + } + std::vector > index; + index.push_back(std::pair(vertex->hessianIndex(), vertex->hessianIndex())); + return computeMarginals(spinv, index); + } + + /** + * computes the inverse of the set specified vertices, assembled into a single covariance matrix. + * @param vertex: the pattern + * @param spinv: the sparse block matrix with the result + * @returns false if the operation is not supported by the solver + */ + bool computeMarginals(SparseBlockMatrix& spinv, const VertexContainer& vertices) { + std::vector > indices; + for (VertexContainer::const_iterator it = vertices.begin(); it != vertices.end(); ++it) { + indices.push_back(std::pair((*it)->hessianIndex(),(*it)->hessianIndex())); + } + return computeMarginals(spinv, indices); + } + + //! finds a gauge in the graph to remove the undefined dof. + // The gauge should be fixed() and then the optimization can work (if no additional dof are in + // the system. The default implementation returns a node with maximum dimension. + virtual Vertex* findGauge(); + + bool gaugeFreedom(); + + /**returns the cached chi2 of the active portion of the graph*/ + double activeChi2() const; + /** + * returns the cached chi2 of the active portion of the graph. + * In contrast to activeChi2() this functions considers the weighting + * of the error according to the robustification of the error functions. + */ + double activeRobustChi2() const; + + //! verbose information during optimization + bool verbose() const {return _verbose;} + void setVerbose(bool verbose); + + /** + * sets a variable checked at every iteration to force a user stop. The iteration exits when the variable is true; + */ + void setForceStopFlag(bool* flag); + bool* forceStopFlag() const { return _forceStopFlag;}; + + //! if external stop flag is given, return its state. False otherwise + bool terminate() {return _forceStopFlag ? (*_forceStopFlag) : false; } + + //! the index mapping of the vertices + const VertexContainer& indexMapping() const {return _ivMap;} + //! the vertices active in the current optimization + const VertexContainer& activeVertices() const { return _activeVertices;} + //! the edges active in the current optimization + const EdgeContainer& activeEdges() const { return _activeEdges;} + + /** + * Remove a vertex. If the vertex is contained in the currently active set + * of vertices, then the internal temporary structures are cleaned, e.g., the index + * mapping is erased. In case you need the index mapping for manipulating the + * graph, you have to store it in your own copy. + */ + virtual bool removeVertex(HyperGraph::Vertex* v); + + /** + * search for an edge in _activeVertices and return the iterator pointing to it + * getActiveVertices().end() if not found + */ + VertexContainer::const_iterator findActiveVertex(const OptimizableGraph::Vertex* v) const; + /** + * search for an edge in _activeEdges and return the iterator pointing to it + * getActiveEdges().end() if not found + */ + EdgeContainer::const_iterator findActiveEdge(const OptimizableGraph::Edge* e) const; + + //! the solver used by the optimizer + const OptimizationAlgorithm* algorithm() const { return _algorithm;} + OptimizationAlgorithm* solver() { return _algorithm;} + void setAlgorithm(OptimizationAlgorithm* algorithm); + + //! push the estimate of a subset of the variables onto a stack + void push(SparseOptimizer::VertexContainer& vlist); + //! push the estimate of a subset of the variables onto a stack + void push(HyperGraph::VertexSet& vlist); + //! push all the active vertices onto a stack + void push(); + //! pop (restore) the estimate a subset of the variables from the stack + void pop(SparseOptimizer::VertexContainer& vlist); + //! pop (restore) the estimate a subset of the variables from the stack + void pop(HyperGraph::VertexSet& vlist); + //! pop (restore) the estimate of the active vertices from the stack + void pop(); + + //! ignore the latest stored element on the stack, remove it from the stack but do not restore the estimate + void discardTop(SparseOptimizer::VertexContainer& vlist); + //! same as above, but for the active vertices + void discardTop(); + using OptimizableGraph::discardTop; + + /** + * clears the graph, and polishes some intermediate structures + * Note that this only removes nodes / edges. Parameters can be removed + * with clearParameters(). + */ + virtual void clear(); + + /** + * computes the error vectors of all edges in the activeSet, and caches them + */ + void computeActiveErrors(); + + /** + * Linearizes the system by computing the Jacobians for the nodes + * and edges in the graph + */ + G2O_ATTRIBUTE_DEPRECATED(void linearizeSystem()) + { + // nothing needed, linearization is now done inside the solver + } + + /** + * update the estimate of the active vertices + * @param update: the double vector containing the stacked + * elements of the increments on the vertices. + */ + void update(const double* update); + + /** + returns the set of batch statistics about the optimisation + */ + const BatchStatisticsContainer& batchStatistics() const { return _batchStatistics;} + /** + returns the set of batch statistics about the optimisation + */ + BatchStatisticsContainer& batchStatistics() { return _batchStatistics;} + + void setComputeBatchStatistics(bool computeBatchStatistics); + + bool computeBatchStatistics() const { return _computeBatchStatistics;} + + /**** callbacks ****/ + //! add an action to be executed before the error vectors are computed + bool addComputeErrorAction(HyperGraphAction* action); + //! remove an action that should no longer be execured before computing the error vectors + bool removeComputeErrorAction(HyperGraphAction* action); + + + + protected: + bool* _forceStopFlag; + bool _verbose; + + VertexContainer _ivMap; + VertexContainer _activeVertices; ///< sorted according to VertexIDCompare + EdgeContainer _activeEdges; ///< sorted according to EdgeIDCompare + + void sortVectorContainers(); + + OptimizationAlgorithm* _algorithm; + + /** + * builds the mapping of the active vertices to the (block) row / column in the Hessian + */ + bool buildIndexMapping(SparseOptimizer::VertexContainer& vlist); + void clearIndexMapping(); + + BatchStatisticsContainer _batchStatistics; ///< global statistics of the optimizer, e.g., timing, num-non-zeros + bool _computeBatchStatistics; + }; +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/solvers/linear_solver_dense.h b/Thirdparty/g2o/g2o/solvers/linear_solver_dense.h new file mode 100644 index 0000000000..b34674c89c --- /dev/null +++ b/Thirdparty/g2o/g2o/solvers/linear_solver_dense.h @@ -0,0 +1,125 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// Copyright (C) 2012 R. Kümmerle +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_LINEAR_SOLVER_DENSE_H +#define G2O_LINEAR_SOLVER_DENSE_H + +#include "../core/linear_solver.h" +#include "../core/batch_stats.h" + +#include +#include +#include +#include + + +namespace g2o { + + /** + * \brief linear solver using dense cholesky decomposition + */ + template + class LinearSolverDense : public LinearSolver + { + public: + LinearSolverDense() : + LinearSolver(), + _reset(true) + { + } + + virtual ~LinearSolverDense() + { + } + + virtual bool init() + { + _reset = true; + return true; + } + + bool solve(const SparseBlockMatrix& A, double* x, double* b) + { + int n = A.cols(); + int m = A.cols(); + + Eigen::MatrixXd& H = _H; + if (H.cols() != n) { + H.resize(n, m); + _reset = true; + } + if (_reset) { + _reset = false; + H.setZero(); + } + + // copy the sparse block matrix into a dense matrix + int c_idx = 0; + for (size_t i = 0; i < A.blockCols().size(); ++i) { + int c_size = A.colsOfBlock(i); + assert(c_idx == A.colBaseOfBlock(i) && "mismatch in block indices"); + + const typename SparseBlockMatrix::IntBlockMap& col = A.blockCols()[i]; + if (col.size() > 0) { + typename SparseBlockMatrix::IntBlockMap::const_iterator it; + for (it = col.begin(); it != col.end(); ++it) { + int r_idx = A.rowBaseOfBlock(it->first); + // only the upper triangular block is processed + if (it->first <= (int)i) { + int r_size = A.rowsOfBlock(it->first); + H.block(r_idx, c_idx, r_size, c_size) = *(it->second); + if (r_idx != c_idx) // write the lower triangular block + H.block(c_idx, r_idx, c_size, r_size) = it->second->transpose(); + } + } + } + + c_idx += c_size; + } + + // solving via Cholesky decomposition + Eigen::VectorXd::MapType xvec(x, m); + Eigen::VectorXd::ConstMapType bvec(b, n); + _cholesky.compute(H); + if (_cholesky.isPositive()) { + xvec = _cholesky.solve(bvec); + return true; + } + return false; + } + + protected: + bool _reset; + Eigen::MatrixXd _H; + Eigen::LDLT _cholesky; + + }; + + +}// end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h b/Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h new file mode 100644 index 0000000000..d61c633c71 --- /dev/null +++ b/Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h @@ -0,0 +1,237 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_LINEAR_SOLVER_EIGEN_H +#define G2O_LINEAR_SOLVER_EIGEN_H + +#include +#include + +#include "../core/linear_solver.h" +#include "../core/batch_stats.h" +#include "../stuff/timeutil.h" + +#include "../core/eigen_types.h" + +#include +#include + +namespace g2o { + +/** + * \brief linear solver which uses the sparse Cholesky solver from Eigen + * + * Has no dependencies except Eigen. Hence, should compile almost everywhere + * without to much issues. Performance should be similar to CSparse, I guess. + */ +template +class LinearSolverEigen: public LinearSolver +{ + public: + typedef Eigen::SparseMatrix SparseMatrix; + typedef Eigen::Triplet Triplet; + typedef Eigen::PermutationMatrix PermutationMatrix; + /** + * \brief Sub-classing Eigen's SimplicialLDLT to perform ordering with a given ordering + */ + class CholeskyDecomposition : public Eigen::SimplicialLDLT + { + public: + CholeskyDecomposition() : Eigen::SimplicialLDLT() {} + using Eigen::SimplicialLDLT< SparseMatrix, Eigen::Upper>::analyzePattern_preordered; + + void analyzePatternWithPermutation(SparseMatrix& a, const PermutationMatrix& permutation) + { + m_Pinv = permutation; + m_P = permutation.inverse(); + int size = a.cols(); + SparseMatrix ap(size, size); + ap.selfadjointView() = a.selfadjointView().twistedBy(m_P); + analyzePattern_preordered(ap, true); + } + }; + + public: + LinearSolverEigen() : + LinearSolver(), + _init(true), _blockOrdering(false), _writeDebug(false) + { + } + + virtual ~LinearSolverEigen() + { + } + + virtual bool init() + { + _init = true; + return true; + } + + bool solve(const SparseBlockMatrix& A, double* x, double* b) + { + if (_init) + _sparseMatrix.resize(A.rows(), A.cols()); + fillSparseMatrix(A, !_init); + if (_init) // compute the symbolic composition once + computeSymbolicDecomposition(A); + _init = false; + + double t=get_monotonic_time(); + _cholesky.factorize(_sparseMatrix); + if (_cholesky.info() != Eigen::Success) { // the matrix is not positive definite + if (_writeDebug) { + std::cerr << "Cholesky failure, writing debug.txt (Hessian loadable by Octave)" << std::endl; + A.writeOctave("debug.txt"); + } + return false; + } + + // Solving the system + VectorXD::MapType xx(x, _sparseMatrix.cols()); + VectorXD::ConstMapType bb(b, _sparseMatrix.cols()); + xx = _cholesky.solve(bb); + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) { + globalStats->timeNumericDecomposition = get_monotonic_time() - t; + globalStats->choleskyNNZ = _cholesky.matrixL().nestedExpression().nonZeros() + _sparseMatrix.cols(); // the elements of D + } + + return true; + } + + //! do the AMD ordering on the blocks or on the scalar matrix + bool blockOrdering() const { return _blockOrdering;} + void setBlockOrdering(bool blockOrdering) { _blockOrdering = blockOrdering;} + + //! write a debug dump of the system matrix if it is not SPD in solve + virtual bool writeDebug() const { return _writeDebug;} + virtual void setWriteDebug(bool b) { _writeDebug = b;} + + protected: + bool _init; + bool _blockOrdering; + bool _writeDebug; + SparseMatrix _sparseMatrix; + CholeskyDecomposition _cholesky; + + /** + * compute the symbolic decompostion of the matrix only once. + * Since A has the same pattern in all the iterations, we only + * compute the fill-in reducing ordering once and re-use for all + * the following iterations. + */ + void computeSymbolicDecomposition(const SparseBlockMatrix& A) + { + double t=get_monotonic_time(); + if (! _blockOrdering) { + _cholesky.analyzePattern(_sparseMatrix); + } else { + // block ordering with the Eigen Interface + // This is really ugly currently, as it calls internal functions from Eigen + // and modifies the SparseMatrix class + Eigen::PermutationMatrix blockP; + { + // prepare a block structure matrix for calling AMD + std::vector triplets; + for (size_t c = 0; c < A.blockCols().size(); ++c){ + const typename SparseBlockMatrix::IntBlockMap& column = A.blockCols()[c]; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it = column.begin(); it != column.end(); ++it) { + const int& r = it->first; + if (r > static_cast(c)) // only upper triangle + break; + triplets.push_back(Triplet(r, c, 0.)); + } + } + + // call the AMD ordering on the block matrix. + // Relies on Eigen's internal stuff, probably bad idea + SparseMatrix auxBlockMatrix(A.blockCols().size(), A.blockCols().size()); + auxBlockMatrix.setFromTriplets(triplets.begin(), triplets.end()); + typename CholeskyDecomposition::CholMatrixType C; + C = auxBlockMatrix.selfadjointView(); + Eigen::internal::minimum_degree_ordering(C, blockP); + } + + int rows = A.rows(); + assert(rows == A.cols() && "Matrix A is not square"); + + // Adapt the block permutation to the scalar matrix + PermutationMatrix scalarP; + scalarP.resize(rows); + int scalarIdx = 0; + for (int i = 0; i < blockP.size(); ++i) { + const int& p = blockP.indices()(i); + int base = A.colBaseOfBlock(p); + int nCols = A.colsOfBlock(p); + for (int j = 0; j < nCols; ++j) + scalarP.indices()(scalarIdx++) = base++; + } + assert(scalarIdx == rows && "did not completely fill the permutation matrix"); + // analyze with the scalar permutation + _cholesky.analyzePatternWithPermutation(_sparseMatrix, scalarP); + + } + G2OBatchStatistics* globalStats = G2OBatchStatistics::globalStats(); + if (globalStats) + globalStats->timeSymbolicDecomposition = get_monotonic_time() - t; + } + + void fillSparseMatrix(const SparseBlockMatrix& A, bool onlyValues) + { + if (onlyValues) { + A.fillCCS(_sparseMatrix.valuePtr(), true); + } else { + + // create from triplet structure + std::vector triplets; + triplets.reserve(A.nonZeros()); + for (size_t c = 0; c < A.blockCols().size(); ++c) { + int colBaseOfBlock = A.colBaseOfBlock(c); + const typename SparseBlockMatrix::IntBlockMap& column = A.blockCols()[c]; + for (typename SparseBlockMatrix::IntBlockMap::const_iterator it = column.begin(); it != column.end(); ++it) { + int rowBaseOfBlock = A.rowBaseOfBlock(it->first); + const MatrixType& m = *(it->second); + for (int cc = 0; cc < m.cols(); ++cc) { + int aux_c = colBaseOfBlock + cc; + for (int rr = 0; rr < m.rows(); ++rr) { + int aux_r = rowBaseOfBlock + rr; + if (aux_r > aux_c) + break; + triplets.push_back(Triplet(aux_r, aux_c, m(rr, cc))); + } + } + } + } + _sparseMatrix.setFromTriplets(triplets.begin(), triplets.end()); + + } + } +}; + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/color_macros.h b/Thirdparty/g2o/g2o/stuff/color_macros.h new file mode 100644 index 0000000000..7115bbeacc --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/color_macros.h @@ -0,0 +1,65 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_COLOR_MACROS_H +#define G2O_COLOR_MACROS_H + +// font attributes +#define FT_BOLD "\033[1m" +#define FT_UNDERLINE "\033[4m" + +//background color +#define BG_BLACK "\033[40m" +#define BG_RED "\033[41m" +#define BG_GREEN "\033[42m" +#define BG_YELLOW "\033[43m" +#define BG_LIGHTBLUE "\033[44m" +#define BG_MAGENTA "\033[45m" +#define BG_BLUE "\033[46m" +#define BG_WHITE "\033[47m" + +// font color +#define CL_BLACK(s) "\033[30m" << s << "\033[0m" +#define CL_RED(s) "\033[31m" << s << "\033[0m" +#define CL_GREEN(s) "\033[32m" << s << "\033[0m" +#define CL_YELLOW(s) "\033[33m" << s << "\033[0m" +#define CL_LIGHTBLUE(s) "\033[34m" << s << "\033[0m" +#define CL_MAGENTA(s) "\033[35m" << s << "\033[0m" +#define CL_BLUE(s) "\033[36m" << s << "\033[0m" +#define CL_WHITE(s) "\033[37m" << s << "\033[0m" + +#define FG_BLACK "\033[30m" +#define FG_RED "\033[31m" +#define FG_GREEN "\033[32m" +#define FG_YELLOW "\033[33m" +#define FG_LIGHTBLUE "\033[34m" +#define FG_MAGENTA "\033[35m" +#define FG_BLUE "\033[36m" +#define FG_WHITE "\033[37m" + +#define FG_NORM "\033[0m" + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/macros.h b/Thirdparty/g2o/g2o/stuff/macros.h new file mode 100644 index 0000000000..be4a24518f --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/macros.h @@ -0,0 +1,134 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_MACROS_H +#define G2O_MACROS_H + +#ifndef DEG2RAD +#define DEG2RAD(x) ((x) * 0.01745329251994329575) +#endif + +#ifndef RAD2DEG +#define RAD2DEG(x) ((x) * 57.29577951308232087721) +#endif + +// GCC the one and only +#if defined(__GNUC__) +# define G2O_ATTRIBUTE_CONSTRUCTOR(func) \ + static void func(void)__attribute__ ((constructor)); \ + static void func(void) + +# define G2O_ATTRIBUTE_UNUSED __attribute__((unused)) +# define G2O_ATTRIBUTE_FORMAT12 __attribute__ ((format (printf, 1, 2))) +# define G2O_ATTRIBUTE_FORMAT23 __attribute__ ((format (printf, 2, 3))) +# define G2O_ATTRIBUTE_WARNING(func) func __attribute__((warning)) +# define G2O_ATTRIBUTE_DEPRECATED(func) func __attribute__((deprecated)) + +#ifdef ANDROID +# define g2o_isnan(x) isnan(x) +# define g2o_isinf(x) isinf(x) +# define g2o_isfinite(x) isfinite(x) +#else +# define g2o_isnan(x) std::isnan(x) +# define g2o_isinf(x) std::isinf(x) +# define g2o_isfinite(x) std::isfinite(x) +#endif + +// MSVC on Windows +#elif defined _MSC_VER +# define __PRETTY_FUNCTION__ __FUNCTION__ + +/** +Modified by Mark Pupilli from: + + "Initializer/finalizer sample for MSVC and GCC. + 2010 Joe Lowe. Released into the public domain." + + "For MSVC, places a ptr to the function in the user initializer section (.CRT$XCU), basically the same thing the compiler does for the constructor calls for static C++ objects. For GCC, uses a constructor attribute." + + (As posted on Stack OVerflow) +*/ +# define G2O_ATTRIBUTE_CONSTRUCTOR(f) \ + __pragma(section(".CRT$XCU",read)) \ + static void __cdecl f(void); \ + __declspec(allocate(".CRT$XCU")) void (__cdecl*f##_)(void) = f; \ + static void __cdecl f(void) + +# define G2O_ATTRIBUTE_UNUSED +# define G2O_ATTRIBUTE_FORMAT12 +# define G2O_ATTRIBUTE_FORMAT23 +# define G2O_ATTRIBUTE_WARNING(func) func +# define G2O_ATTRIBUTE_DEPRECATED(func) func + +#include + +# define g2o_isnan(x) _isnan(x) +# define g2o_isinf(x) (_finite(x) == 0) +# define g2o_isfinite(x) (_finite(x) != 0) + +// unknown compiler +#else +# ifndef __PRETTY_FUNCTION__ +# define __PRETTY_FUNCTION__ "" +# endif +# define G2O_ATTRIBUTE_CONSTRUCTOR(func) func +# define G2O_ATTRIBUTE_UNUSED +# define G2O_ATTRIBUTE_FORMAT12 +# define G2O_ATTRIBUTE_FORMAT23 +# define G2O_ATTRIBUTE_WARNING(func) func +# define G2O_ATTRIBUTE_DEPRECATED(func) func + +#include +#define g2o_isnan(x) isnan(x) +#define g2o_isinf(x) isinf(x) +#define g2o_isfinite(x) isfinite(x) + +#endif + +// some macros that are only useful for c++ +#ifdef __cplusplus + +#define G2O_FSKIP_LINE(f) \ + {char c=' ';while(c != '\n' && f.good() && !(f).eof()) (f).get(c);} + +#ifndef PVAR + #define PVAR(s) \ + #s << " = " << (s) << std::flush +#endif + +#ifndef PVARA +#define PVARA(s) \ + #s << " = " << RAD2DEG(s) << "deg" << std::flush +#endif + +#ifndef FIXED +#define FIXED(s) \ + std::fixed << s << std::resetiosflags(std::ios_base::fixed) +#endif + +#endif // __cplusplus + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/misc.h b/Thirdparty/g2o/g2o/stuff/misc.h new file mode 100644 index 0000000000..4fa4ff331f --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/misc.h @@ -0,0 +1,206 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_STUFF_MISC_H +#define G2O_STUFF_MISC_H + +#include "macros.h" +#include + +#ifndef M_PI +#define M_PI 3.14159265358979323846 +#endif + +/** @addtogroup utils **/ +// @{ + +/** \file misc.h + * \brief some general case utility functions + * + * This file specifies some general case utility functions + **/ + +namespace g2o { + +/** + * return the square value + */ +template +inline T square(T x) +{ + return x*x; +} + +/** + * return the hypot of x and y + */ +template +inline T hypot(T x, T y) +{ + return (T) (sqrt(x*x + y*y)); +} + +/** + * return the squared hypot of x and y + */ +template +inline T hypot_sqr(T x, T y) +{ + return x*x + y*y; +} + +/** + * convert from degree to radian + */ +inline double deg2rad(double degree) +{ + return degree * 0.01745329251994329576; +} + +/** + * convert from radian to degree + */ +inline double rad2deg(double rad) +{ + return rad * 57.29577951308232087721; +} + +/** + * normalize the angle + */ +inline double normalize_theta(double theta) +{ + if (theta >= -M_PI && theta < M_PI) + return theta; + + double multiplier = floor(theta / (2*M_PI)); + theta = theta - multiplier*2*M_PI; + if (theta >= M_PI) + theta -= 2*M_PI; + if (theta < -M_PI) + theta += 2*M_PI; + + return theta; +} + +/** + * inverse of an angle, i.e., +180 degree + */ +inline double inverse_theta(double th) +{ + return normalize_theta(th + M_PI); +} + +/** + * average two angles + */ +inline double average_angle(double theta1, double theta2) +{ + double x, y; + + x = cos(theta1) + cos(theta2); + y = sin(theta1) + sin(theta2); + if(x == 0 && y == 0) + return 0; + else + return std::atan2(y, x); +} + +/** + * sign function. + * @return the sign of x. +1 for x > 0, -1 for x < 0, 0 for x == 0 + */ +template +inline int sign(T x) +{ + if (x > 0) + return 1; + else if (x < 0) + return -1; + else + return 0; +} + +/** + * clamp x to the interval [l, u] + */ +template +inline T clamp(T l, T x, T u) +{ + if (x < l) + return l; + if (x > u) + return u; + return x; +} + +/** + * wrap x to be in the interval [l, u] + */ +template +inline T wrap(T l, T x, T u) +{ + T intervalWidth = u - l; + while (x < l) + x += intervalWidth; + while (x > u) + x -= intervalWidth; + return x; +} + +/** + * tests whether there is a NaN in the array + */ +inline bool arrayHasNaN(const double* array, int size, int* nanIndex = 0) +{ + for (int i = 0; i < size; ++i) + if (g2o_isnan(array[i])) { + if (nanIndex) + *nanIndex = i; + return true; + } + return false; +} + +/** + * The following two functions are used to force linkage with static libraries. + */ +extern "C" +{ + typedef void (* ForceLinkFunction) (void); +} + +struct ForceLinker +{ + ForceLinker(ForceLinkFunction function) { (function)(); } +}; + + +} // end namespace + +// @} + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/os_specific.c b/Thirdparty/g2o/g2o/stuff/os_specific.c new file mode 100644 index 0000000000..85f936897e --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/os_specific.c @@ -0,0 +1,64 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "os_specific.h" + +#ifdef WINDOWS + +int vasprintf(char** strp, const char* fmt, va_list ap) +{ + int n; + int size = 100; + char* p; + char* np; + + if ((p = (char*)malloc(size * sizeof(char))) == NULL) + return -1; + + while (1) { +#ifdef _MSC_VER + n = vsnprintf_s(p, size, size - 1, fmt, ap); +#else + n = vsnprintf(p, size, fmt, ap); +#endif + if (n > -1 && n < size) { + *strp = p; + return n; + } + if (n > -1) + size = n+1; + else + size *= 2; + if ((np = (char*)realloc (p, size * sizeof(char))) == NULL) { + free(p); + return -1; + } else + p = np; + } +} + + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/os_specific.h b/Thirdparty/g2o/g2o/stuff/os_specific.h new file mode 100644 index 0000000000..89dd0cccf9 --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/os_specific.h @@ -0,0 +1,56 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_OS_SPECIFIC_HH_ +#define G2O_OS_SPECIFIC_HH_ + +#ifdef WINDOWS +#include +#include +#include +#ifndef _WINDOWS +#include +#endif +#define drand48() ((double) rand()/(double)RAND_MAX) + +#ifdef __cplusplus +extern "C" { +#endif + +int vasprintf(char** strp, const char* fmt, va_list ap); + +#ifdef __cplusplus +} +#endif + +#endif + +#ifdef UNIX +#include +// nothing to do on real operating systems +#endif + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/property.cpp b/Thirdparty/g2o/g2o/stuff/property.cpp new file mode 100644 index 0000000000..f13016e1a9 --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/property.cpp @@ -0,0 +1,105 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "property.h" + +#include +#include + +#include "macros.h" + +#include "string_tools.h" +using namespace std; + +namespace g2o { + + BaseProperty::BaseProperty(const std::string name_) :_name(name_){ + } + + BaseProperty::~BaseProperty(){} + + bool PropertyMap::addProperty(BaseProperty* p) { + std::pair result = insert(make_pair(p->name(), p)); + return result.second; + } + + bool PropertyMap::eraseProperty(const std::string& name) { + PropertyMapIterator it=find(name); + if (it==end()) + return false; + delete it->second; + erase(it); + return true; + } + + PropertyMap::~PropertyMap() { + for (PropertyMapIterator it=begin(); it!=end(); it++){ + if (it->second) + delete it->second; + } + } + + bool PropertyMap::updatePropertyFromString(const std::string& name, const std::string& value) + { + PropertyMapIterator it = find(name); + if (it == end()) + return false; + it->second->fromString(value); + return true; + } + + void PropertyMap::writeToCSV(std::ostream& os) const + { + for (PropertyMapConstIterator it=begin(); it!=end(); it++){ + BaseProperty* p =it->second; + os << p->name() << ", "; + } + os << std::endl; + for (PropertyMapConstIterator it=begin(); it!=end(); it++){ + BaseProperty* p =it->second; + os << p->toString() << ", "; + } + os << std::endl; + } + + bool PropertyMap::updateMapFromString(const std::string& values) + { + bool status = true; + vector valuesMap = strSplit(values, ","); + for (size_t i = 0; i < valuesMap.size(); ++i) { + vector m = strSplit(valuesMap[i], "="); + if (m.size() != 2) { + cerr << __PRETTY_FUNCTION__ << ": unable to extract name=value pair from " << valuesMap[i] << endl; + continue; + } + string name = trim(m[0]); + string value = trim(m[1]); + status = status && updatePropertyFromString(name, value); + } + return status; + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/stuff/property.h b/Thirdparty/g2o/g2o/stuff/property.h new file mode 100644 index 0000000000..7b638780d5 --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/property.h @@ -0,0 +1,158 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_PROPERTY_H_ +#define G2O_PROPERTY_H_ + +#include +#include +#include + +#include "string_tools.h" + +namespace g2o { + + class BaseProperty { + public: + BaseProperty(const std::string name_); + virtual ~BaseProperty(); + const std::string& name() {return _name;} + virtual std::string toString() const = 0; + virtual bool fromString(const std::string& s) = 0; + protected: + std::string _name; + }; + + template + class Property: public BaseProperty { + public: + typedef T ValueType; + Property(const std::string& name_): BaseProperty(name_){} + Property(const std::string& name_, const T& v): BaseProperty(name_), _value(v){} + void setValue(const T& v) {_value = v; } + const T& value() const {return _value;} + virtual std::string toString() const + { + std::stringstream sstr; + sstr << _value; + return sstr.str(); + } + virtual bool fromString(const std::string& s) + { + bool status = convertString(s, _value); + return status; + } + protected: + T _value; + }; + + /** + * \brief a collection of properties mapping from name to the property itself + */ + class PropertyMap : protected std::map + { + public: + typedef std::map BaseClass; + typedef BaseClass::iterator PropertyMapIterator; + typedef BaseClass::const_iterator PropertyMapConstIterator; + + ~PropertyMap(); + + /** + * add a property to the map + */ + bool addProperty(BaseProperty* p); + + /** + * remove a property from the map + */ + bool eraseProperty(const std::string& name_); + + /** + * return a property by its name + */ + template + P* getProperty(const std::string& name_) + { + PropertyMapIterator it=find(name_); + if (it==end()) + return 0; + return dynamic_cast(it->second); + } + template + const P* getProperty(const std::string& name_) const + { + PropertyMapConstIterator it=find(name_); + if (it==end()) + return 0; + return dynamic_cast(it->second); + } + + /** + * create a property and insert it + */ + template + P* makeProperty(const std::string& name_, const typename P::ValueType& v) + { + PropertyMapIterator it=find(name_); + if (it==end()){ + P* p=new P(name_, v); + addProperty(p); + return p; + } else + return dynamic_cast(it->second); + } + + /** + * update a specfic property with a new value + * @return true if the params is stored and update was carried out + */ + bool updatePropertyFromString(const std::string& name, const std::string& value); + + /** + * update the map based on a name=value string, e.g., name1=val1,name2=val2 + * @return true, if it was possible to update all parameters + */ + bool updateMapFromString(const std::string& values); + + void writeToCSV(std::ostream& os) const; + + using BaseClass::size; + using BaseClass::begin; + using BaseClass::end; + using BaseClass::iterator; + using BaseClass::const_iterator; + + }; + + typedef Property IntProperty; + typedef Property BoolProperty; + typedef Property FloatProperty; + typedef Property DoubleProperty; + typedef Property StringProperty; + +} // end namespace +#endif diff --git a/Thirdparty/g2o/g2o/stuff/string_tools.cpp b/Thirdparty/g2o/g2o/stuff/string_tools.cpp new file mode 100644 index 0000000000..0a4f60a277 --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/string_tools.cpp @@ -0,0 +1,185 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "string_tools.h" +#include "os_specific.h" +#include "macros.h" + +#include +#include +#include +#include +#include +#include +#include +#include + +#if (defined (UNIX) || defined(CYGWIN)) && !defined(ANDROID) +#include +#endif + +namespace g2o { + +using namespace std; + +std::string trim(const std::string& s) +{ + if(s.length() == 0) + return s; + string::size_type b = s.find_first_not_of(" \t\n"); + string::size_type e = s.find_last_not_of(" \t\n"); + if(b == string::npos) + return ""; + return std::string(s, b, e - b + 1); +} + +std::string trimLeft(const std::string& s) +{ + if(s.length() == 0) + return s; + string::size_type b = s.find_first_not_of(" \t\n"); + string::size_type e = s.length() - 1; + if(b == string::npos) + return ""; + return std::string(s, b, e - b + 1); +} + +std::string trimRight(const std::string& s) +{ + if(s.length() == 0) + return s; + string::size_type b = 0; + string::size_type e = s.find_last_not_of(" \t\n"); + if(b == string::npos) + return ""; + return std::string(s, b, e - b + 1); +} + +std::string strToLower(const std::string& s) +{ + string ret; + std::transform(s.begin(), s.end(), back_inserter(ret), (int(*)(int)) std::tolower); + return ret; +} + +std::string strToUpper(const std::string& s) +{ + string ret; + std::transform(s.begin(), s.end(), back_inserter(ret), (int(*)(int)) std::toupper); + return ret; +} + +std::string formatString(const char* fmt, ...) +{ + char* auxPtr = NULL; + va_list arg_list; + va_start(arg_list, fmt); + int numChar = vasprintf(&auxPtr, fmt, arg_list); + va_end(arg_list); + string retString; + if (numChar != -1) + retString = auxPtr; + else { + cerr << __PRETTY_FUNCTION__ << ": Error while allocating memory" << endl; + } + free(auxPtr); + return retString; +} + +int strPrintf(std::string& str, const char* fmt, ...) +{ + char* auxPtr = NULL; + va_list arg_list; + va_start(arg_list, fmt); + int numChars = vasprintf(&auxPtr, fmt, arg_list); + va_end(arg_list); + str = auxPtr; + free(auxPtr); + return numChars; +} + +std::string strExpandFilename(const std::string& filename) +{ +#if (defined (UNIX) || defined(CYGWIN)) && !defined(ANDROID) + string result = filename; + wordexp_t p; + + wordexp(filename.c_str(), &p, 0); + if(p.we_wordc > 0) { + result = p.we_wordv[0]; + } + wordfree(&p); + return result; +#else + (void) filename; + std::cerr << "WARNING: " << __PRETTY_FUNCTION__ << " not implemented" << std::endl; + return std::string(); +#endif +} + +std::vector strSplit(const std::string& str, const std::string& delimiters) +{ + std::vector tokens; + string::size_type lastPos = 0; + string::size_type pos = 0; + + do { + pos = str.find_first_of(delimiters, lastPos); + tokens.push_back(str.substr(lastPos, pos - lastPos)); + lastPos = pos + 1; + } while (string::npos != pos); + + return tokens; +} + +bool strStartsWith(const std::string& s, const std::string& start) +{ + if (s.size() < start.size()) + return false; + return equal(start.begin(), start.end(), s.begin()); +} + +bool strEndsWith(const std::string& s, const std::string& end) +{ + if (s.size() < end.size()) + return false; + return equal(end.rbegin(), end.rend(), s.rbegin()); +} + +int readLine(std::istream& is, std::stringstream& currentLine) +{ + if (is.eof()) + return -1; + currentLine.str(""); + currentLine.clear(); + is.get(*currentLine.rdbuf()); + if (is.fail()) // fail is set on empty lines + is.clear(); + G2O_FSKIP_LINE(is); // read \n not read by get() + return static_cast(currentLine.str().size()); +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/stuff/string_tools.h b/Thirdparty/g2o/g2o/stuff/string_tools.h new file mode 100644 index 0000000000..226208ff30 --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/string_tools.h @@ -0,0 +1,176 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_STRING_TOOLS_H +#define G2O_STRING_TOOLS_H + +#include +#include +#include +#include + +#include "macros.h" + +namespace g2o { + +/** @addtogroup utils **/ +// @{ + +/** \file stringTools.h + * \brief utility functions for handling strings + */ + +/** + * remove whitespaces from the start/end of a string + */ + std::string trim(const std::string& s); + +/** + * remove whitespaces from the left side of the string + */ + std::string trimLeft(const std::string& s); + +/** + * remove whitespaced from the right side of the string + */ + std::string trimRight(const std::string& s); + +/** + * convert the string to lower case + */ + std::string strToLower(const std::string& s); + +/** + * convert a string to upper case + */ + std::string strToUpper(const std::string& s); + +/** + * read integer values (seperated by spaces) from a string and store + * them in the given OutputIterator. + */ +template +OutputIterator readInts(const char* str, OutputIterator out) +{ + char* cl = (char*)str; + char* cle = cl; + while (1) { + int id = strtol(cl, &cle, 10); + if (cl == cle) + break; + *out++ = id; + cl = cle; + } + return out; +} + +/** + * read float values (seperated by spaces) from a string and store + * them in the given OutputIterator. + */ +template +OutputIterator readFloats(const char* str, OutputIterator out) +{ + char* cl = (char*)str; + char* cle = cl; + while (1) { + double val = strtod(cl, &cle); + if (cl == cle) + break; + *out++ = val; + cl = cle; + } + return out; +} + +/** + * format a string and return a std::string. + * Format is just like printf, see man 3 printf + */ + std::string formatString(const char* fmt, ...) G2O_ATTRIBUTE_FORMAT12; + +/** + * replacement function for sprintf which fills a std::string instead of a char* + */ + int strPrintf(std::string& str, const char* fmt, ...) G2O_ATTRIBUTE_FORMAT23; + +/** + * convert a string into an other type. + */ +template +bool convertString(const std::string& s, T& x, bool failIfLeftoverChars = true) +{ + std::istringstream i(s); + char c; + if (!(i >> x) || (failIfLeftoverChars && i.get(c))) + return false; + return true; +} + +/** + * convert a string into an other type. + * Return the converted value. Throw error if parsing is wrong. + */ +template +T stringToType(const std::string& s, bool failIfLeftoverChars = true) +{ + T x; + convertString(s, x, failIfLeftoverChars); + return x; +} + +/** + * return true, if str starts with substr + */ + bool strStartsWith(const std::string & str, const std::string& substr); + +/** + * return true, if str ends with substr + */ + bool strEndsWith(const std::string & str, const std::string& substr); + +/** + * expand the given filename like a posix shell, e.g., ~ $CARMEN_HOME and other will get expanded. + * Also command substitution, e.g. `pwd` will give the current directory. + */ + std::string strExpandFilename(const std::string& filename); + +/** + * split a string into token based on the characters given in delim + */ + std::vector strSplit(const std::string& s, const std::string& delim); + +/** + * read a line from is into currentLine. + * @return the number of characters read into currentLine (excluding newline), -1 on eof() + */ + int readLine(std::istream& is, std::stringstream& currentLine); + +// @} + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/stuff/timeutil.cpp b/Thirdparty/g2o/g2o/stuff/timeutil.cpp new file mode 100644 index 0000000000..ec190519e6 --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/timeutil.cpp @@ -0,0 +1,124 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "timeutil.h" +#include + +#ifdef _WINDOWS +#include +#include +#endif + +#ifdef UNIX +#include +#endif + +namespace g2o { + +#ifdef _WINDOWS +#if defined(_MSC_VER) || defined(_MSC_EXTENSIONS) + #define DELTA_EPOCH_IN_MICROSECS 11644473600000000Ui64 +#else + #define DELTA_EPOCH_IN_MICROSECS 11644473600000000ULL +#endif + +struct timezone +{ + int tz_minuteswest; /* minutes W of Greenwich */ + int tz_dsttime; /* type of dst correction */ +}; + +int gettimeofday(struct timeval *tv, struct timezone *tz) +{ +// Define a structure to receive the current Windows filetime + FILETIME ft; + +// Initialize the present time to 0 and the timezone to UTC + unsigned __int64 tmpres = 0; + static int tzflag = 0; + + if (NULL != tv) + { + GetSystemTimeAsFileTime(&ft); + +// The GetSystemTimeAsFileTime returns the number of 100 nanosecond +// intervals since Jan 1, 1601 in a structure. Copy the high bits to +// the 64 bit tmpres, shift it left by 32 then or in the low 32 bits. + tmpres |= ft.dwHighDateTime; + tmpres <<= 32; + tmpres |= ft.dwLowDateTime; + +// Convert to microseconds by dividing by 10 + tmpres /= 10; + +// The Unix epoch starts on Jan 1 1970. Need to subtract the difference +// in seconds from Jan 1 1601. + tmpres -= DELTA_EPOCH_IN_MICROSECS; + +// Finally change microseconds to seconds and place in the seconds value. +// The modulus picks up the microseconds. + tv->tv_sec = (long)(tmpres / 1000000UL); + tv->tv_usec = (long)(tmpres % 1000000UL); + } + + if (NULL != tz) { + if (!tzflag) { + _tzset(); + tzflag++; + } + + long sec; + int hours; + _get_timezone(&sec); + _get_daylight(&hours); + +// Adjust for the timezone west of Greenwich + tz->tz_minuteswest = sec / 60; + tz->tz_dsttime = hours; + } + + return 0; +} +#endif + +ScopeTime::ScopeTime(const char* title) : _title(title), _startTime(get_monotonic_time()) {} + +ScopeTime::~ScopeTime() { + std::cerr << _title<<" took "<<1000*(get_monotonic_time()-_startTime)<<"ms.\n"; +} + +double get_monotonic_time() +{ +#if (defined(_POSIX_TIMERS) && (_POSIX_TIMERS+0 >= 0) && defined(_POSIX_MONOTONIC_CLOCK)) + struct timespec ts; + clock_gettime(CLOCK_MONOTONIC, &ts); + return ts.tv_sec + ts.tv_nsec*1e-9; +#else + return get_time(); +#endif +} + +} // end namespace diff --git a/Thirdparty/g2o/g2o/stuff/timeutil.h b/Thirdparty/g2o/g2o/stuff/timeutil.h new file mode 100644 index 0000000000..bde8e318ae --- /dev/null +++ b/Thirdparty/g2o/g2o/stuff/timeutil.h @@ -0,0 +1,132 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_TIMEUTIL_H +#define G2O_TIMEUTIL_H + +#ifdef _WINDOWS +#include +#else +#include +#endif + +#include + + +/** @addtogroup utils **/ +// @{ + +/** \file timeutil.h + * \brief utility functions for handling time related stuff + */ + +/// Executes code, only if secs are gone since last exec. +/// extended version, in which the current time is given, e.g., timestamp of IPC message +#ifndef DO_EVERY_TS +#define DO_EVERY_TS(secs, currentTime, code) \ +if (1) {\ + static double s_lastDone_ = (currentTime); \ + double s_now_ = (currentTime); \ + if (s_lastDone_ > s_now_) \ + s_lastDone_ = s_now_; \ + if (s_now_ - s_lastDone_ > (secs)) { \ + code; \ + s_lastDone_ = s_now_; \ + }\ +} else \ + (void)0 +#endif + +/// Executes code, only if secs are gone since last exec. +#ifndef DO_EVERY +#define DO_EVERY(secs, code) DO_EVERY_TS(secs, g2o::get_time(), code) +#endif + +#ifndef MEASURE_TIME +#define MEASURE_TIME(text, code) \ + if(1) { \ + double _start_time_ = g2o::get_time(); \ + code; \ + fprintf(stderr, "%s took %f sec\n", text, g2o::get_time() - _start_time_); \ + } else \ + (void) 0 +#endif + +namespace g2o { + +#ifdef _WINDOWS +typedef struct timeval { + long tv_sec; + long tv_usec; +} timeval; + int gettimeofday(struct timeval *tv, struct timezone *tz); +#endif + +/** + * return the current time in seconds since 1. Jan 1970 + */ +inline double get_time() +{ + struct timeval ts; + gettimeofday(&ts,0); + return ts.tv_sec + ts.tv_usec*1e-6; +} + +/** + * return a monotonic increasing time which basically does not need to + * have a reference point. Consider this for measuring how long some + * code fragments required to execute. + * + * On Linux we call clock_gettime() on other systems we currently + * call get_time(). + */ + double get_monotonic_time(); + +/** + * \brief Class to measure the time spent in a scope + * + * To use this class, e.g. to measure the time spent in a function, + * just create and instance at the beginning of the function. + */ +class ScopeTime { + public: + ScopeTime(const char* title); + ~ScopeTime(); + private: + std::string _title; + double _startTime; +}; + +} // end namespace + +#ifndef MEASURE_FUNCTION_TIME +#define MEASURE_FUNCTION_TIME \ + g2o::ScopeTime scopeTime(__PRETTY_FUNCTION__) +#endif + + +// @} +#endif diff --git a/Thirdparty/g2o/g2o/types/CMakeLists.txt b/Thirdparty/g2o/g2o/types/CMakeLists.txt new file mode 100644 index 0000000000..7c98825f9e --- /dev/null +++ b/Thirdparty/g2o/g2o/types/CMakeLists.txt @@ -0,0 +1,15 @@ +ADD_LIBRARY(types ${G2O_LIB_TYPE} + types_sba.h + types_six_dof_expmap.h + types_sba.cpp + types_six_dof_expmap.cpp + types_seven_dof_expmap.cpp + types_seven_dof_expmap.h + se3quat.h + se3_ops.h + se3_ops.hpp +) + +SET_TARGET_PROPERTIES(types PROPERTIES OUTPUT_NAME ${LIB_PREFIX}types) + +TARGET_LINK_LIBRARIES(types core) diff --git a/Thirdparty/g2o/g2o/types/se3_ops.h b/Thirdparty/g2o/g2o/types/se3_ops.h new file mode 100644 index 0000000000..b5c59d3ec0 --- /dev/null +++ b/Thirdparty/g2o/g2o/types/se3_ops.h @@ -0,0 +1,47 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_MATH_STUFF +#define G2O_MATH_STUFF + +#include +#include + +namespace g2o { + using namespace Eigen; + + inline Matrix3d skew(const Vector3d&v); + inline Vector3d deltaR(const Matrix3d& R); + inline Vector2d project(const Vector3d&); + inline Vector3d project(const Vector4d&); + inline Vector3d unproject(const Vector2d&); + inline Vector4d unproject(const Vector3d&); + +#include "se3_ops.hpp" + +} + +#endif //MATH_STUFF diff --git a/Thirdparty/g2o/g2o/types/se3_ops.hpp b/Thirdparty/g2o/g2o/types/se3_ops.hpp new file mode 100644 index 0000000000..c28860d49c --- /dev/null +++ b/Thirdparty/g2o/g2o/types/se3_ops.hpp @@ -0,0 +1,85 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + + Matrix3d skew(const Vector3d&v) + { + Matrix3d m; + m.fill(0.); + m(0,1) = -v(2); + m(0,2) = v(1); + m(1,2) = -v(0); + m(1,0) = v(2); + m(2,0) = -v(1); + m(2,1) = v(0); + return m; + } + + Vector3d deltaR(const Matrix3d& R) + { + Vector3d v; + v(0)=R(2,1)-R(1,2); + v(1)=R(0,2)-R(2,0); + v(2)=R(1,0)-R(0,1); + return v; + } + + Vector2d project(const Vector3d& v) + { + Vector2d res; + res(0) = v(0)/v(2); + res(1) = v(1)/v(2); + return res; + } + + Vector3d project(const Vector4d& v) + { + Vector3d res; + res(0) = v(0)/v(3); + res(1) = v(1)/v(3); + res(2) = v(2)/v(3); + return res; + } + + Vector3d unproject(const Vector2d& v) + { + Vector3d res; + res(0) = v(0); + res(1) = v(1); + res(2) = 1; + return res; + } + + Vector4d unproject(const Vector3d& v) + { + Vector4d res; + res(0) = v(0); + res(1) = v(1); + res(2) = v(2); + res(3) = 1; + return res; + } + + diff --git a/Thirdparty/g2o/g2o/types/se3quat.h b/Thirdparty/g2o/g2o/types/se3quat.h new file mode 100644 index 0000000000..ac5ec57cb6 --- /dev/null +++ b/Thirdparty/g2o/g2o/types/se3quat.h @@ -0,0 +1,306 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SE3QUAT_H_ +#define G2O_SE3QUAT_H_ + +#include "se3_ops.h" + +#include +#include + +namespace g2o { + using namespace Eigen; + + typedef Matrix Vector6d; + typedef Matrix Vector7d; + + class SE3Quat { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW; + + + protected: + + Quaterniond _r; + Vector3d _t; + + + public: + SE3Quat(){ + _r.setIdentity(); + _t.setZero(); + } + + SE3Quat(const Matrix3d& R, const Vector3d& t):_r(Quaterniond(R)),_t(t){ + normalizeRotation(); + } + + SE3Quat(const Quaterniond& q, const Vector3d& t):_r(q),_t(t){ + normalizeRotation(); + } + + /** + * templaized constructor which allows v to be an arbitrary Eigen Vector type, e.g., Vector6d or Map + */ + template + explicit SE3Quat(const MatrixBase& v) + { + assert((v.size() == 6 || v.size() == 7) && "Vector dimension does not match"); + if (v.size() == 6) { + for (int i=0; i<3; i++){ + _t[i]=v[i]; + _r.coeffs()(i)=v[i+3]; + } + _r.w() = 0.; // recover the positive w + if (_r.norm()>1.){ + _r.normalize(); + } else { + double w2=1.-_r.squaredNorm(); + _r.w()= (w2<0.) ? 0. : sqrt(w2); + } + } + else if (v.size() == 7) { + int idx = 0; + for (int i=0; i<3; ++i, ++idx) + _t(i) = v(idx); + for (int i=0; i<4; ++i, ++idx) + _r.coeffs()(i) = v(idx); + normalizeRotation(); + } + } + + inline const Vector3d& translation() const {return _t;} + + inline void setTranslation(const Vector3d& t_) {_t = t_;} + + inline const Quaterniond& rotation() const {return _r;} + + void setRotation(const Quaterniond& r_) {_r=r_;} + + inline SE3Quat operator* (const SE3Quat& tr2) const{ + SE3Quat result(*this); + result._t += _r*tr2._t; + result._r*=tr2._r; + result.normalizeRotation(); + return result; + } + + inline SE3Quat& operator*= (const SE3Quat& tr2){ + _t+=_r*tr2._t; + _r*=tr2._r; + normalizeRotation(); + return *this; + } + + inline Vector3d operator* (const Vector3d& v) const { + return _t+_r*v; + } + + inline SE3Quat inverse() const{ + SE3Quat ret; + ret._r=_r.conjugate(); + ret._t=ret._r*(_t*-1.); + return ret; + } + + inline double operator [](int i) const { + assert(i<7); + if (i<3) + return _t[i]; + return _r.coeffs()[i-3]; + } + + + inline Vector7d toVector() const{ + Vector7d v; + v[0]=_t(0); + v[1]=_t(1); + v[2]=_t(2); + v[3]=_r.x(); + v[4]=_r.y(); + v[5]=_r.z(); + v[6]=_r.w(); + return v; + } + + inline void fromVector(const Vector7d& v){ + _r=Quaterniond(v[6], v[3], v[4], v[5]); + _t=Vector3d(v[0], v[1], v[2]); + } + + inline Vector6d toMinimalVector() const{ + Vector6d v; + v[0]=_t(0); + v[1]=_t(1); + v[2]=_t(2); + v[3]=_r.x(); + v[4]=_r.y(); + v[5]=_r.z(); + return v; + } + + inline void fromMinimalVector(const Vector6d& v){ + double w = 1.-v[3]*v[3]-v[4]*v[4]-v[5]*v[5]; + if (w>0){ + _r=Quaterniond(sqrt(w), v[3], v[4], v[5]); + } else { + _r=Quaterniond(0, -v[3], -v[4], -v[5]); + } + _t=Vector3d(v[0], v[1], v[2]); + } + + + + Vector6d log() const { + Vector6d res; + Matrix3d _R = _r.toRotationMatrix(); + double d = 0.5*(_R(0,0)+_R(1,1)+_R(2,2)-1); + Vector3d omega; + Vector3d upsilon; + + + Vector3d dR = deltaR(_R); + Matrix3d V_inv; + + if (d>0.99999) + { + + omega=0.5*dR; + Matrix3d Omega = skew(omega); + V_inv = Matrix3d::Identity()- 0.5*Omega + (1./12.)*(Omega*Omega); + } + else + { + double theta = acos(d); + omega = theta/(2*sqrt(1-d*d))*dR; + Matrix3d Omega = skew(omega); + V_inv = ( Matrix3d::Identity() - 0.5*Omega + + ( 1-theta/(2*tan(theta/2)))/(theta*theta)*(Omega*Omega) ); + } + + upsilon = V_inv*_t; + for (int i=0; i<3;i++){ + res[i]=omega[i]; + } + for (int i=0; i<3;i++){ + res[i+3]=upsilon[i]; + } + + return res; + + } + + Vector3d map(const Vector3d & xyz) const + { + return _r*xyz + _t; + } + + + static SE3Quat exp(const Vector6d & update) + { + Vector3d omega; + for (int i=0; i<3; i++) + omega[i]=update[i]; + Vector3d upsilon; + for (int i=0; i<3; i++) + upsilon[i]=update[i+3]; + + double theta = omega.norm(); + Matrix3d Omega = skew(omega); + + Matrix3d R; + Matrix3d V; + if (theta<0.00001) + { + //TODO: CHECK WHETHER THIS IS CORRECT!!! + R = (Matrix3d::Identity() + Omega + Omega*Omega); + + V = R; + } + else + { + Matrix3d Omega2 = Omega*Omega; + + R = (Matrix3d::Identity() + + sin(theta)/theta *Omega + + (1-cos(theta))/(theta*theta)*Omega2); + + V = (Matrix3d::Identity() + + (1-cos(theta))/(theta*theta)*Omega + + (theta-sin(theta))/(pow(theta,3))*Omega2); + } + return SE3Quat(Quaterniond(R),V*upsilon); + } + + Matrix adj() const + { + Matrix3d R = _r.toRotationMatrix(); + Matrix res; + res.block(0,0,3,3) = R; + res.block(3,3,3,3) = R; + res.block(3,0,3,3) = skew(_t)*R; + res.block(0,3,3,3) = Matrix3d::Zero(3,3); + return res; + } + + Matrix to_homogeneous_matrix() const + { + Matrix homogeneous_matrix; + homogeneous_matrix.setIdentity(); + homogeneous_matrix.block(0,0,3,3) = _r.toRotationMatrix(); + homogeneous_matrix.col(3).head(3) = translation(); + + return homogeneous_matrix; + } + + void normalizeRotation(){ + if (_r.w()<0){ + _r.coeffs() *= -1; + } + _r.normalize(); + } + + /** + * cast SE3Quat into an Eigen::Isometry3d + */ + operator Eigen::Isometry3d() const + { + Eigen::Isometry3d result = (Eigen::Isometry3d) rotation(); + result.translation() = translation(); + return result; + } + }; + + inline std::ostream& operator <<(std::ostream& out_str, const SE3Quat& se3) + { + out_str << se3.to_homogeneous_matrix() << std::endl; + return out_str; + } + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/g2o/types/sim3.h b/Thirdparty/g2o/g2o/types/sim3.h new file mode 100644 index 0000000000..cfd6d5e9bd --- /dev/null +++ b/Thirdparty/g2o/g2o/types/sim3.h @@ -0,0 +1,307 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SIM_3 +#define G2O_SIM_3 + +#include "se3_ops.h" +#include + +namespace g2o +{ + using namespace Eigen; + + typedef Matrix Vector7d; + typedef Matrix Matrix7d; + + + struct Sim3 + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + protected: + Quaterniond r; + Vector3d t; + double s; + + +public: + Sim3() + { + r.setIdentity(); + t.fill(0.); + s=1.; + } + + Sim3(const Quaterniond & r, const Vector3d & t, double s) + : r(r),t(t),s(s) + { + } + + Sim3(const Matrix3d & R, const Vector3d & t, double s) + : r(Quaterniond(R)),t(t),s(s) + { + } + + + Sim3(const Vector7d & update) + { + + Vector3d omega; + for (int i=0; i<3; i++) + omega[i]=update[i]; + + Vector3d upsilon; + for (int i=0; i<3; i++) + upsilon[i]=update[i+3]; + + double sigma = update[6]; + double theta = omega.norm(); + Matrix3d Omega = skew(omega); + s = std::exp(sigma); + Matrix3d Omega2 = Omega*Omega; + Matrix3d I; + I.setIdentity(); + Matrix3d R; + + double eps = 0.00001; + double A,B,C; + if (fabs(sigma)1-eps) + { + omega=0.5*deltaR(R); + Omega = skew(omega); + A = 1./2.; + B = 1./6.; + } + else + { + double theta = acos(d); + double theta2 = theta*theta; + omega = theta/(2*sqrt(1-d*d))*deltaR(R); + Omega = skew(omega); + A = (1-cos(theta))/(theta2); + B = (theta-sin(theta))/(theta2*theta); + } + } + else + { + C=(s-1)/sigma; + if (d>1-eps) + { + + double sigma2 = sigma*sigma; + omega=0.5*deltaR(R); + Omega = skew(omega); + A = ((sigma-1)*s+1)/(sigma2); + B = ((0.5*sigma2-sigma+1)*s)/(sigma2*sigma); + } + else + { + double theta = acos(d); + omega = theta/(2*sqrt(1-d*d))*deltaR(R); + Omega = skew(omega); + double theta2 = theta*theta; + double a=s*sin(theta); + double b=s*cos(theta); + double c=theta2 + sigma*sigma; + A = (a*sigma+ (1-b)*theta)/(theta*c); + B = (C-((b-1)*sigma+a*theta)/(c))*1./(theta2); + } + } + + Matrix3d W = A*Omega + B*Omega*Omega + C*I; + + upsilon = W.lu().solve(t); + + + for (int i=0; i<3; i++) + res[i] = omega[i]; + + for (int i=0; i<3; i++) + res[i+3] = upsilon[i]; + + res[6] = sigma; + + return res; + + } + + + Sim3 inverse() const + { + return Sim3(r.conjugate(), r.conjugate()*((-1./s)*t), 1./s); + } + + + double operator[](int i) const + { + assert(i<8); + if (i<4){ + + return r.coeffs()[i]; + } + if (i<7){ + return t[i-4]; + } + return s; + } + + double& operator[](int i) + { + assert(i<8); + if (i<4){ + + return r.coeffs()[i]; + } + if (i<7) + { + return t[i-4]; + } + return s; + } + + Sim3 operator *(const Sim3& other) const { + Sim3 ret; + ret.r = r*other.r; + ret.t=s*(r*other.t)+t; + ret.s=s*other.s; + return ret; + } + + Sim3& operator *=(const Sim3& other){ + Sim3 ret=(*this)*other; + *this=ret; + return *this; + } + + inline const Vector3d& translation() const {return t;} + + inline Vector3d& translation() {return t;} + + inline const Quaterniond& rotation() const {return r;} + + inline Quaterniond& rotation() {return r;} + + inline const double& scale() const {return s;} + + inline double& scale() {return s;} + + }; + + inline std::ostream& operator <<(std::ostream& out_str, + const Sim3& sim3) + { + out_str << sim3.rotation().coeffs() << std::endl; + out_str << sim3.translation() << std::endl; + out_str << sim3.scale() << std::endl; + + return out_str; + } + +} // end namespace + + +#endif diff --git a/Thirdparty/g2o/g2o/types/types_sba.cpp b/Thirdparty/g2o/g2o/types/types_sba.cpp new file mode 100644 index 0000000000..d91b49829a --- /dev/null +++ b/Thirdparty/g2o/g2o/types/types_sba.cpp @@ -0,0 +1,56 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 Kurt Konolige +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "types_sba.h" +#include + +namespace g2o { + + using namespace std; + + + VertexSBAPointXYZ::VertexSBAPointXYZ() : BaseVertex<3, Vector3d>() + { + } + + bool VertexSBAPointXYZ::read(std::istream& is) + { + Vector3d lv; + for (int i=0; i<3; i++) + is >> _estimate[i]; + return true; + } + + bool VertexSBAPointXYZ::write(std::ostream& os) const + { + Vector3d lv=estimate(); + for (int i=0; i<3; i++){ + os << lv[i] << " "; + } + return os.good(); + } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/types/types_sba.h b/Thirdparty/g2o/g2o/types/types_sba.h new file mode 100644 index 0000000000..bb419dfaa7 --- /dev/null +++ b/Thirdparty/g2o/g2o/types/types_sba.h @@ -0,0 +1,61 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 Kurt Konolige +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#ifndef G2O_SBA_TYPES +#define G2O_SBA_TYPES + +#include "../core/base_vertex.h" + +#include +#include + +namespace g2o { + +/** + * \brief Point vertex, XYZ + */ + class VertexSBAPointXYZ : public BaseVertex<3, Vector3d> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexSBAPointXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate.fill(0.); + } + + virtual void oplusImpl(const double* update) + { + Eigen::Map v(update); + _estimate += v; + } +}; + +} // end namespace + +#endif // SBA_TYPES diff --git a/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp b/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp new file mode 100644 index 0000000000..abf1b1d8fb --- /dev/null +++ b/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.cpp @@ -0,0 +1,239 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "types_seven_dof_expmap.h" + +namespace g2o { + + VertexSim3Expmap::VertexSim3Expmap() : BaseVertex<7, Sim3>() + { + _marginalized=false; + _fix_scale = false; + } + + + EdgeSim3::EdgeSim3() : + BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap>() + { + } + + + bool VertexSim3Expmap::read(std::istream& is) + { + Vector7d cam2world; + for (int i=0; i<6; i++){ + is >> cam2world[i]; + } + is >> cam2world[6]; +// if (! is) { +// // if the scale is not specified we set it to 1; +// std::cerr << "!s"; +// cam2world[6]=0.; +// } + + for (int i=0; i<2; i++) + { + is >> _focal_length1[i]; + } + for (int i=0; i<2; i++) + { + is >> _principle_point1[i]; + } + + setEstimate(Sim3(cam2world).inverse()); + return true; + } + + bool VertexSim3Expmap::write(std::ostream& os) const + { + Sim3 cam2world(estimate().inverse()); + Vector7d lv=cam2world.log(); + for (int i=0; i<7; i++){ + os << lv[i] << " "; + } + for (int i=0; i<2; i++) + { + os << _focal_length1[i] << " "; + } + for (int i=0; i<2; i++) + { + os << _principle_point1[i] << " "; + } + return os.good(); + } + + bool EdgeSim3::read(std::istream& is) + { + Vector7d v7; + for (int i=0; i<7; i++){ + is >> v7[i]; + } + + Sim3 cam2world(v7); + setMeasurement(cam2world.inverse()); + + for (int i=0; i<7; i++) + for (int j=i; j<7; j++) + { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSim3::write(std::ostream& os) const + { + Sim3 cam2world(measurement().inverse()); + Vector7d v7 = cam2world.log(); + for (int i=0; i<7; i++) + { + os << v7[i] << " "; + } + for (int i=0; i<7; i++) + for (int j=i; j<7; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + /**Sim3ProjectXYZ*/ + + EdgeSim3ProjectXYZ::EdgeSim3ProjectXYZ() : + BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap>() + { + } + + bool EdgeSim3ProjectXYZ::read(std::istream& is) + { + for (int i=0; i<2; i++) + { + is >> _measurement[i]; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeSim3ProjectXYZ::write(std::ostream& os) const + { + for (int i=0; i<2; i++){ + os << _measurement[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + +/**InverseSim3ProjectXYZ*/ + + EdgeInverseSim3ProjectXYZ::EdgeInverseSim3ProjectXYZ() : + BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap>() + { + } + + bool EdgeInverseSim3ProjectXYZ::read(std::istream& is) + { + for (int i=0; i<2; i++) + { + is >> _measurement[i]; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; + } + + bool EdgeInverseSim3ProjectXYZ::write(std::ostream& os) const + { + for (int i=0; i<2; i++){ + os << _measurement[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); + } + + +// void EdgeSim3ProjectXYZ::linearizeOplus() +// { +// VertexSim3Expmap * vj = static_cast(_vertices[1]); +// Sim3 T = vj->estimate(); + +// VertexPointXYZ* vi = static_cast(_vertices[0]); +// Vector3d xyz = vi->estimate(); +// Vector3d xyz_trans = T.map(xyz); + +// double x = xyz_trans[0]; +// double y = xyz_trans[1]; +// double z = xyz_trans[2]; +// double z_2 = z*z; + +// Matrix tmp; +// tmp(0,0) = _focal_length(0); +// tmp(0,1) = 0; +// tmp(0,2) = -x/z*_focal_length(0); + +// tmp(1,0) = 0; +// tmp(1,1) = _focal_length(1); +// tmp(1,2) = -y/z*_focal_length(1); + +// _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix(); + +// _jacobianOplusXj(0,0) = x*y/z_2 * _focal_length(0); +// _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *_focal_length(0); +// _jacobianOplusXj(0,2) = y/z *_focal_length(0); +// _jacobianOplusXj(0,3) = -1./z *_focal_length(0); +// _jacobianOplusXj(0,4) = 0; +// _jacobianOplusXj(0,5) = x/z_2 *_focal_length(0); +// _jacobianOplusXj(0,6) = 0; // scale is ignored + + +// _jacobianOplusXj(1,0) = (1+y*y/z_2) *_focal_length(1); +// _jacobianOplusXj(1,1) = -x*y/z_2 *_focal_length(1); +// _jacobianOplusXj(1,2) = -x/z *_focal_length(1); +// _jacobianOplusXj(1,3) = 0; +// _jacobianOplusXj(1,4) = -1./z *_focal_length(1); +// _jacobianOplusXj(1,5) = y/z_2 *_focal_length(1); +// _jacobianOplusXj(1,6) = 0; // scale is ignored +// } + +} // end namespace diff --git a/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h b/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h new file mode 100644 index 0000000000..b63a585905 --- /dev/null +++ b/Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h @@ -0,0 +1,176 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +// Modified by Raúl Mur Artal (2014) +// - Added EdgeInverseSim3ProjectXYZ +// - Modified VertexSim3Expmap to represent relative transformation between two cameras. Includes calibration of both cameras. + +#ifndef G2O_SEVEN_DOF_EXPMAP_TYPES +#define G2O_SEVEN_DOF_EXPMAP_TYPES + +#include "../core/base_vertex.h" +#include "../core/base_binary_edge.h" +#include "types_six_dof_expmap.h" +#include "sim3.h" + +namespace g2o { + + using namespace Eigen; + + /** + * \brief Sim3 Vertex, (x,y,z,qw,qx,qy,qz) + * the parameterization for the increments constructed is a 7d vector + * (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion. + */ + class VertexSim3Expmap : public BaseVertex<7, Sim3> + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + VertexSim3Expmap(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate = Sim3(); + } + + virtual void oplusImpl(const double* update_) + { + Eigen::Map update(const_cast(update_)); + + if (_fix_scale) + update[6] = 0; + + Sim3 s(update); + setEstimate(s*estimate()); + } + + Vector2d _principle_point1, _principle_point2; + Vector2d _focal_length1, _focal_length2; + + Vector2d cam_map1(const Vector2d & v) const + { + Vector2d res; + res[0] = v[0]*_focal_length1[0] + _principle_point1[0]; + res[1] = v[1]*_focal_length1[1] + _principle_point1[1]; + return res; + } + + Vector2d cam_map2(const Vector2d & v) const + { + Vector2d res; + res[0] = v[0]*_focal_length2[0] + _principle_point2[0]; + res[1] = v[1]*_focal_length2[1] + _principle_point2[1]; + return res; + } + + bool _fix_scale; + + + protected: + }; + + /** + * \brief 7D edge between two Vertex7 + */ + class EdgeSim3 : public BaseBinaryEdge<7, Sim3, VertexSim3Expmap, VertexSim3Expmap> + { + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeSim3(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + void computeError() + { + const VertexSim3Expmap* v1 = static_cast(_vertices[0]); + const VertexSim3Expmap* v2 = static_cast(_vertices[1]); + + Sim3 C(_measurement); + Sim3 error_=C*v1->estimate()*v2->estimate().inverse(); + _error = error_.log(); + } + + virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& , OptimizableGraph::Vertex* ) { return 1.;} + virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* /*to*/) + { + VertexSim3Expmap* v1 = static_cast(_vertices[0]); + VertexSim3Expmap* v2 = static_cast(_vertices[1]); + if (from.count(v1) > 0) + v2->setEstimate(measurement()*v1->estimate()); + else + v1->setEstimate(measurement().inverse()*v2->estimate()); + } + }; + + +/**/ +class EdgeSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeSim3ProjectXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const VertexSim3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + + Vector2d obs(_measurement); + _error = obs-v1->cam_map1(project(v1->estimate().map(v2->estimate()))); + } + + // virtual void linearizeOplus(); + +}; + +/**/ +class EdgeInverseSim3ProjectXYZ : public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap> +{ + public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + EdgeInverseSim3ProjectXYZ(); + virtual bool read(std::istream& is); + virtual bool write(std::ostream& os) const; + + void computeError() + { + const VertexSim3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + + Vector2d obs(_measurement); + _error = obs-v1->cam_map2(project(v1->estimate().inverse().map(v2->estimate()))); + } + + // virtual void linearizeOplus(); + +}; + +} // end namespace + +#endif + diff --git a/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp b/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp new file mode 100644 index 0000000000..498508ccf3 --- /dev/null +++ b/Thirdparty/g2o/g2o/types/types_six_dof_expmap.cpp @@ -0,0 +1,367 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +#include "types_six_dof_expmap.h" + +#include "../core/factory.h" +#include "../stuff/macros.h" + +namespace g2o { + +using namespace std; + + +Vector2d project2d(const Vector3d& v) { + Vector2d res; + res(0) = v(0)/v(2); + res(1) = v(1)/v(2); + return res; +} + +Vector3d unproject2d(const Vector2d& v) { + Vector3d res; + res(0) = v(0); + res(1) = v(1); + res(2) = 1; + return res; +} + +VertexSE3Expmap::VertexSE3Expmap() : BaseVertex<6, SE3Quat>() { +} + +bool VertexSE3Expmap::read(std::istream& is) { + Vector7d est; + for (int i=0; i<7; i++) + is >> est[i]; + SE3Quat cam2world; + cam2world.fromVector(est); + setEstimate(cam2world.inverse()); + return true; +} + +bool VertexSE3Expmap::write(std::ostream& os) const { + SE3Quat cam2world(estimate().inverse()); + for (int i=0; i<7; i++) + os << cam2world[i] << " "; + return os.good(); +} + + +EdgeSE3ProjectXYZ::EdgeSE3ProjectXYZ() : BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSE3Expmap>() { +} + +bool EdgeSE3ProjectXYZ::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeSE3ProjectXYZ::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + + +void EdgeSE3ProjectXYZ::linearizeOplus() { + VertexSE3Expmap * vj = static_cast(_vertices[1]); + SE3Quat T(vj->estimate()); + VertexSBAPointXYZ* vi = static_cast(_vertices[0]); + Vector3d xyz = vi->estimate(); + Vector3d xyz_trans = T.map(xyz); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + double z_2 = z*z; + + Matrix tmp; + tmp(0,0) = fx; + tmp(0,1) = 0; + tmp(0,2) = -x/z*fx; + + tmp(1,0) = 0; + tmp(1,1) = fy; + tmp(1,2) = -y/z*fy; + + _jacobianOplusXi = -1./z * tmp * T.rotation().toRotationMatrix(); + + _jacobianOplusXj(0,0) = x*y/z_2 *fx; + _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *fx; + _jacobianOplusXj(0,2) = y/z *fx; + _jacobianOplusXj(0,3) = -1./z *fx; + _jacobianOplusXj(0,4) = 0; + _jacobianOplusXj(0,5) = x/z_2 *fx; + + _jacobianOplusXj(1,0) = (1+y*y/z_2) *fy; + _jacobianOplusXj(1,1) = -x*y/z_2 *fy; + _jacobianOplusXj(1,2) = -x/z *fy; + _jacobianOplusXj(1,3) = 0; + _jacobianOplusXj(1,4) = -1./z *fy; + _jacobianOplusXj(1,5) = y/z_2 *fy; +} + +Vector2d EdgeSE3ProjectXYZ::cam_project(const Vector3d & trans_xyz) const{ + Vector2d proj = project2d(trans_xyz); + Vector2d res; + res[0] = proj[0]*fx + cx; + res[1] = proj[1]*fy + cy; + return res; +} + + +Vector3d EdgeStereoSE3ProjectXYZ::cam_project(const Vector3d & trans_xyz, const float &bf) const{ + const float invz = 1.0f/trans_xyz[2]; + Vector3d res; + res[0] = trans_xyz[0]*invz*fx + cx; + res[1] = trans_xyz[1]*invz*fy + cy; + res[2] = res[0] - bf*invz; + return res; +} + +EdgeStereoSE3ProjectXYZ::EdgeStereoSE3ProjectXYZ() : BaseBinaryEdge<3, Vector3d, VertexSBAPointXYZ, VertexSE3Expmap>() { +} + +bool EdgeStereoSE3ProjectXYZ::read(std::istream& is){ + for (int i=0; i<=3; i++){ + is >> _measurement[i]; + } + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeStereoSE3ProjectXYZ::write(std::ostream& os) const { + + for (int i=0; i<=3; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + +void EdgeStereoSE3ProjectXYZ::linearizeOplus() { + VertexSE3Expmap * vj = static_cast(_vertices[1]); + SE3Quat T(vj->estimate()); + VertexSBAPointXYZ* vi = static_cast(_vertices[0]); + Vector3d xyz = vi->estimate(); + Vector3d xyz_trans = T.map(xyz); + + const Matrix3d R = T.rotation().toRotationMatrix(); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double z = xyz_trans[2]; + double z_2 = z*z; + + _jacobianOplusXi(0,0) = -fx*R(0,0)/z+fx*x*R(2,0)/z_2; + _jacobianOplusXi(0,1) = -fx*R(0,1)/z+fx*x*R(2,1)/z_2; + _jacobianOplusXi(0,2) = -fx*R(0,2)/z+fx*x*R(2,2)/z_2; + + _jacobianOplusXi(1,0) = -fy*R(1,0)/z+fy*y*R(2,0)/z_2; + _jacobianOplusXi(1,1) = -fy*R(1,1)/z+fy*y*R(2,1)/z_2; + _jacobianOplusXi(1,2) = -fy*R(1,2)/z+fy*y*R(2,2)/z_2; + + _jacobianOplusXi(2,0) = _jacobianOplusXi(0,0)-bf*R(2,0)/z_2; + _jacobianOplusXi(2,1) = _jacobianOplusXi(0,1)-bf*R(2,1)/z_2; + _jacobianOplusXi(2,2) = _jacobianOplusXi(0,2)-bf*R(2,2)/z_2; + + _jacobianOplusXj(0,0) = x*y/z_2 *fx; + _jacobianOplusXj(0,1) = -(1+(x*x/z_2)) *fx; + _jacobianOplusXj(0,2) = y/z *fx; + _jacobianOplusXj(0,3) = -1./z *fx; + _jacobianOplusXj(0,4) = 0; + _jacobianOplusXj(0,5) = x/z_2 *fx; + + _jacobianOplusXj(1,0) = (1+y*y/z_2) *fy; + _jacobianOplusXj(1,1) = -x*y/z_2 *fy; + _jacobianOplusXj(1,2) = -x/z *fy; + _jacobianOplusXj(1,3) = 0; + _jacobianOplusXj(1,4) = -1./z *fy; + _jacobianOplusXj(1,5) = y/z_2 *fy; + + _jacobianOplusXj(2,0) = _jacobianOplusXj(0,0)-bf*y/z_2; + _jacobianOplusXj(2,1) = _jacobianOplusXj(0,1)+bf*x/z_2; + _jacobianOplusXj(2,2) = _jacobianOplusXj(0,2); + _jacobianOplusXj(2,3) = _jacobianOplusXj(0,3); + _jacobianOplusXj(2,4) = 0; + _jacobianOplusXj(2,5) = _jacobianOplusXj(0,5)-bf/z_2; +} + + +//Only Pose + +bool EdgeSE3ProjectXYZOnlyPose::read(std::istream& is){ + for (int i=0; i<2; i++){ + is >> _measurement[i]; + } + for (int i=0; i<2; i++) + for (int j=i; j<2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeSE3ProjectXYZOnlyPose::write(std::ostream& os) const { + + for (int i=0; i<2; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<2; i++) + for (int j=i; j<2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + + +void EdgeSE3ProjectXYZOnlyPose::linearizeOplus() { + VertexSE3Expmap * vi = static_cast(_vertices[0]); + Vector3d xyz_trans = vi->estimate().map(Xw); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double invz = 1.0/xyz_trans[2]; + double invz_2 = invz*invz; + + _jacobianOplusXi(0,0) = x*y*invz_2 *fx; + _jacobianOplusXi(0,1) = -(1+(x*x*invz_2)) *fx; + _jacobianOplusXi(0,2) = y*invz *fx; + _jacobianOplusXi(0,3) = -invz *fx; + _jacobianOplusXi(0,4) = 0; + _jacobianOplusXi(0,5) = x*invz_2 *fx; + + _jacobianOplusXi(1,0) = (1+y*y*invz_2) *fy; + _jacobianOplusXi(1,1) = -x*y*invz_2 *fy; + _jacobianOplusXi(1,2) = -x*invz *fy; + _jacobianOplusXi(1,3) = 0; + _jacobianOplusXi(1,4) = -invz *fy; + _jacobianOplusXi(1,5) = y*invz_2 *fy; +} + +Vector2d EdgeSE3ProjectXYZOnlyPose::cam_project(const Vector3d & trans_xyz) const{ + Vector2d proj = project2d(trans_xyz); + Vector2d res; + res[0] = proj[0]*fx + cx; + res[1] = proj[1]*fy + cy; + return res; +} + + +Vector3d EdgeStereoSE3ProjectXYZOnlyPose::cam_project(const Vector3d & trans_xyz) const{ + const float invz = 1.0f/trans_xyz[2]; + Vector3d res; + res[0] = trans_xyz[0]*invz*fx + cx; + res[1] = trans_xyz[1]*invz*fy + cy; + res[2] = res[0] - bf*invz; + return res; +} + + +bool EdgeStereoSE3ProjectXYZOnlyPose::read(std::istream& is){ + for (int i=0; i<=3; i++){ + is >> _measurement[i]; + } + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++) { + is >> information()(i,j); + if (i!=j) + information()(j,i)=information()(i,j); + } + return true; +} + +bool EdgeStereoSE3ProjectXYZOnlyPose::write(std::ostream& os) const { + + for (int i=0; i<=3; i++){ + os << measurement()[i] << " "; + } + + for (int i=0; i<=2; i++) + for (int j=i; j<=2; j++){ + os << " " << information()(i,j); + } + return os.good(); +} + +void EdgeStereoSE3ProjectXYZOnlyPose::linearizeOplus() { + VertexSE3Expmap * vi = static_cast(_vertices[0]); + Vector3d xyz_trans = vi->estimate().map(Xw); + + double x = xyz_trans[0]; + double y = xyz_trans[1]; + double invz = 1.0/xyz_trans[2]; + double invz_2 = invz*invz; + + _jacobianOplusXi(0,0) = x*y*invz_2 *fx; + _jacobianOplusXi(0,1) = -(1+(x*x*invz_2)) *fx; + _jacobianOplusXi(0,2) = y*invz *fx; + _jacobianOplusXi(0,3) = -invz *fx; + _jacobianOplusXi(0,4) = 0; + _jacobianOplusXi(0,5) = x*invz_2 *fx; + + _jacobianOplusXi(1,0) = (1+y*y*invz_2) *fy; + _jacobianOplusXi(1,1) = -x*y*invz_2 *fy; + _jacobianOplusXi(1,2) = -x*invz *fy; + _jacobianOplusXi(1,3) = 0; + _jacobianOplusXi(1,4) = -invz *fy; + _jacobianOplusXi(1,5) = y*invz_2 *fy; + + _jacobianOplusXi(2,0) = _jacobianOplusXi(0,0)-bf*y*invz_2; + _jacobianOplusXi(2,1) = _jacobianOplusXi(0,1)+bf*x*invz_2; + _jacobianOplusXi(2,2) = _jacobianOplusXi(0,2); + _jacobianOplusXi(2,3) = _jacobianOplusXi(0,3); + _jacobianOplusXi(2,4) = 0; + _jacobianOplusXi(2,5) = _jacobianOplusXi(0,5)-bf*invz_2; +} + + +} // end namespace diff --git a/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h b/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h new file mode 100644 index 0000000000..be765f111d --- /dev/null +++ b/Thirdparty/g2o/g2o/types/types_six_dof_expmap.h @@ -0,0 +1,208 @@ +// g2o - General Graph Optimization +// Copyright (C) 2011 H. Strasdat +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +// IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +// TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +// PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// 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. + +// Modified by Raúl Mur Artal (2014) +// Added EdgeSE3ProjectXYZ (project using focal_length in x,y directions) +// Modified by Raúl Mur Artal (2016) +// Added EdgeStereoSE3ProjectXYZ (project using focal_length in x,y directions) +// Added EdgeSE3ProjectXYZOnlyPose (unary edge to optimize only the camera pose) +// Added EdgeStereoSE3ProjectXYZOnlyPose (unary edge to optimize only the camera pose) + +#ifndef G2O_SIX_DOF_TYPES_EXPMAP +#define G2O_SIX_DOF_TYPES_EXPMAP + +#include "../core/base_vertex.h" +#include "../core/base_binary_edge.h" +#include "../core/base_unary_edge.h" +#include "se3_ops.h" +#include "se3quat.h" +#include "types_sba.h" +#include + +namespace g2o { +namespace types_six_dof_expmap { +void init(); +} + +using namespace Eigen; + +typedef Matrix Matrix6d; + + +/** + * \brief SE3 Vertex parameterized internally with a transformation matrix + and externally with its exponential map + */ +class VertexSE3Expmap : public BaseVertex<6, SE3Quat>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + VertexSE3Expmap(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + virtual void setToOriginImpl() { + _estimate = SE3Quat(); + } + + virtual void oplusImpl(const double* update_) { + Eigen::Map update(update_); + setEstimate(SE3Quat::exp(update)*estimate()); + } +}; + + +class EdgeSE3ProjectXYZ: public BaseBinaryEdge<2, Vector2d, VertexSBAPointXYZ, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZ(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + Vector2d obs(_measurement); + _error = obs-cam_project(v1->estimate().map(v2->estimate())); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + return (v1->estimate().map(v2->estimate()))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector2d cam_project(const Vector3d & trans_xyz) const; + + double fx, fy, cx, cy; +}; + + +class EdgeStereoSE3ProjectXYZ: public BaseBinaryEdge<3, Vector3d, VertexSBAPointXYZ, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeStereoSE3ProjectXYZ(); + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + Vector3d obs(_measurement); + _error = obs - cam_project(v1->estimate().map(v2->estimate()),bf); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[1]); + const VertexSBAPointXYZ* v2 = static_cast(_vertices[0]); + return (v1->estimate().map(v2->estimate()))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector3d cam_project(const Vector3d & trans_xyz, const float &bf) const; + + double fx, fy, cx, cy, bf; +}; + +class EdgeSE3ProjectXYZOnlyPose: public BaseUnaryEdge<2, Vector2d, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeSE3ProjectXYZOnlyPose(){} + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + Vector2d obs(_measurement); + _error = obs-cam_project(v1->estimate().map(Xw)); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + return (v1->estimate().map(Xw))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector2d cam_project(const Vector3d & trans_xyz) const; + + Vector3d Xw; + double fx, fy, cx, cy; +}; + + +class EdgeStereoSE3ProjectXYZOnlyPose: public BaseUnaryEdge<3, Vector3d, VertexSE3Expmap>{ +public: + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + EdgeStereoSE3ProjectXYZOnlyPose(){} + + bool read(std::istream& is); + + bool write(std::ostream& os) const; + + void computeError() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + Vector3d obs(_measurement); + _error = obs - cam_project(v1->estimate().map(Xw)); + } + + bool isDepthPositive() { + const VertexSE3Expmap* v1 = static_cast(_vertices[0]); + return (v1->estimate().map(Xw))(2)>0.0; + } + + + virtual void linearizeOplus(); + + Vector3d cam_project(const Vector3d & trans_xyz) const; + + Vector3d Xw; + double fx, fy, cx, cy, bf; +}; + + + +} // end namespace + +#endif diff --git a/Thirdparty/g2o/license-bsd.txt b/Thirdparty/g2o/license-bsd.txt new file mode 100644 index 0000000000..b9b8846be4 --- /dev/null +++ b/Thirdparty/g2o/license-bsd.txt @@ -0,0 +1,27 @@ +g2o - General Graph Optimization +Copyright (C) 2011 Rainer Kuemmerle, Giorgio Grisetti, Hauke Strasdat, +Kurt Konolige, and Wolfram Burgard +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are +met: + +* Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +* Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +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. + diff --git a/Vocabulary/ORBvoc.txt.tar.gz b/Vocabulary/ORBvoc.txt.tar.gz new file mode 100644 index 0000000000..96f5a8184a Binary files /dev/null and b/Vocabulary/ORBvoc.txt.tar.gz differ diff --git a/build.sh b/build.sh new file mode 100755 index 0000000000..69d4ba228c --- /dev/null +++ b/build.sh @@ -0,0 +1,31 @@ +echo "Configuring and building Thirdparty/DBoW2 ..." + +cd Thirdparty/DBoW2 +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=Release +make -j + +cd ../../g2o + +echo "Configuring and building Thirdparty/g2o ..." + +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=Release +make -j + +cd ../../../ + +echo "Uncompress vocabulary ..." + +cd Vocabulary +tar -xf ORBvoc.txt.tar.gz +cd .. + +echo "Configuring and building ORB_SLAM2 ..." + +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=Release +make -j diff --git a/cmake_modules/FindEigen3.cmake b/cmake_modules/FindEigen3.cmake new file mode 100644 index 0000000000..8c2a734c3d --- /dev/null +++ b/cmake_modules/FindEigen3.cmake @@ -0,0 +1,87 @@ +# - Try to find Eigen3 lib +# +# This module supports requiring a minimum version, e.g. you can do +# find_package(Eigen3 3.1.2) +# to require version 3.1.2 or newer of Eigen3. +# +# Once done this will define +# +# EIGEN3_FOUND - system has eigen lib with correct version +# EIGEN3_INCLUDE_DIR - the eigen include directory +# EIGEN3_VERSION - eigen version + +# Copyright (c) 2006, 2007 Montel Laurent, +# Copyright (c) 2008, 2009 Gael Guennebaud, +# Copyright (c) 2009 Benoit Jacob +# Redistribution and use is allowed according to the terms of the 2-clause BSD license. + +if(NOT Eigen3_FIND_VERSION) + if(NOT Eigen3_FIND_VERSION_MAJOR) + set(Eigen3_FIND_VERSION_MAJOR 2) + endif(NOT Eigen3_FIND_VERSION_MAJOR) + if(NOT Eigen3_FIND_VERSION_MINOR) + set(Eigen3_FIND_VERSION_MINOR 91) + endif(NOT Eigen3_FIND_VERSION_MINOR) + if(NOT Eigen3_FIND_VERSION_PATCH) + set(Eigen3_FIND_VERSION_PATCH 0) + endif(NOT Eigen3_FIND_VERSION_PATCH) + + set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") +endif(NOT Eigen3_FIND_VERSION) + +macro(_eigen3_check_version) + file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) + + string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") + set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") + set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") + set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") + + set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) + if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK FALSE) + else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK TRUE) + endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + + if(NOT EIGEN3_VERSION_OK) + + message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " + "but at least version ${Eigen3_FIND_VERSION} is required") + endif(NOT EIGEN3_VERSION_OK) +endmacro(_eigen3_check_version) + +if (EIGEN3_INCLUDE_DIR) + + # in cache already + _eigen3_check_version() + set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) + +else (EIGEN3_INCLUDE_DIR) + + # specific additional paths for some OS + if (WIN32) + set(EIGEN_ADDITIONAL_SEARCH_PATHS ${EIGEN_ADDITIONAL_SEARCH_PATHS} "C:/Program Files/Eigen/include" "C:/Program Files (x86)/Eigen/include") + endif(WIN32) + + find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library + PATHS + ${CMAKE_INSTALL_PREFIX}/include + ${EIGEN_ADDITIONAL_SEARCH_PATHS} + ${KDE4_INCLUDE_DIR} + PATH_SUFFIXES eigen3 eigen + ) + + if(EIGEN3_INCLUDE_DIR) + _eigen3_check_version() + endif(EIGEN3_INCLUDE_DIR) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) + + mark_as_advanced(EIGEN3_INCLUDE_DIR) + +endif(EIGEN3_INCLUDE_DIR) + diff --git a/include/Converter.h b/include/Converter.h new file mode 100644 index 0000000000..0002ad62c2 --- /dev/null +++ b/include/Converter.h @@ -0,0 +1,57 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef CONVERTER_H +#define CONVERTER_H + +#include + +#include +#include"Thirdparty/g2o/g2o/types/types_six_dof_expmap.h" +#include"Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" + +namespace ORB_SLAM2 +{ + +class Converter +{ +public: + static std::vector toDescriptorVector(const cv::Mat &Descriptors); + + static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT); + static g2o::SE3Quat toSE3Quat(const g2o::Sim3 &gSim3); + + static cv::Mat toCvMat(const g2o::SE3Quat &SE3); + static cv::Mat toCvMat(const g2o::Sim3 &Sim3); + static cv::Mat toCvMat(const Eigen::Matrix &m); + static cv::Mat toCvMat(const Eigen::Matrix3d &m); + static cv::Mat toCvMat(const Eigen::Matrix &m); + static cv::Mat toCvSE3(const Eigen::Matrix &R, const Eigen::Matrix &t); + + static Eigen::Matrix toVector3d(const cv::Mat &cvVector); + static Eigen::Matrix toVector3d(const cv::Point3f &cvPoint); + static Eigen::Matrix toMatrix3d(const cv::Mat &cvMat3); + + static std::vector toQuaternion(const cv::Mat &M); +}; + +}// namespace ORB_SLAM + +#endif // CONVERTER_H diff --git a/include/Frame.h b/include/Frame.h new file mode 100644 index 0000000000..a6a8032f57 --- /dev/null +++ b/include/Frame.h @@ -0,0 +1,213 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef FRAME_H +#define FRAME_H + +#include + +#include "MapPoint.h" +#include "Thirdparty/DBoW2/DBoW2/BowVector.h" +#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" +#include "ORBVocabulary.h" +#include "KeyFrame.h" +#include "ORBextractor.h" + +#include + +namespace ORB_SLAM2 +{ +#define FRAME_GRID_ROWS 48 +#define FRAME_GRID_COLS 64 + +class MapPoint; +class KeyFrame; + +class Frame +{ +public: + Frame(); + + // Copy constructor. + Frame(const Frame &frame); + + // Constructor for stereo cameras. + Frame(const cv::Mat &imLeft, const cv::Mat &imRight, const double &timeStamp, ORBextractor* extractorLeft, ORBextractor* extractorRight, ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth); + + // Constructor for RGB-D cameras. + Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth); + + // Constructor for Monocular cameras. + Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth); + + // Extract ORB on the image. 0 for left image and 1 for right image. + void ExtractORB(int flag, const cv::Mat &im); + + // Compute Bag of Words representation. + void ComputeBoW(); + + // Set the camera pose. + void SetPose(cv::Mat Tcw); + + // Computes rotation, translation and camera center matrices from the camera pose. + void UpdatePoseMatrices(); + + // Returns the camera center. + inline cv::Mat GetCameraCenter(){ + return mOw.clone(); + } + + // Returns inverse of rotation + inline cv::Mat GetRotationInverse(){ + return mRwc.clone(); + } + + // Check if a MapPoint is in the frustum of the camera + // and fill variables of the MapPoint to be used by the tracking + bool isInFrustum(MapPoint* pMP, float viewingCosLimit); + + // Compute the cell of a keypoint (return false if outside the grid) + bool PosInGrid(const cv::KeyPoint &kp, int &posX, int &posY); + + vector GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel=-1, const int maxLevel=-1) const; + + // Search a match for each keypoint in the left image to a keypoint in the right image. + // If there is a match, depth is computed and the right coordinate associated to the left keypoint is stored. + void ComputeStereoMatches(); + + // Associate a "right" coordinate to a keypoint if there is valid depth in the depthmap. + void ComputeStereoFromRGBD(const cv::Mat &imDepth); + + // Backprojects a keypoint (if stereo/depth info available) into 3D world coordinates. + cv::Mat UnprojectStereo(const int &i); + +public: + // Vocabulary used for relocalization. + ORBVocabulary* mpORBvocabulary; + + // Feature extractor. The right is used only in the stereo case. + ORBextractor* mpORBextractorLeft, *mpORBextractorRight; + + // Frame timestamp. + double mTimeStamp; + + // Calibration matrix and OpenCV distortion parameters. + cv::Mat mK; + static float fx; + static float fy; + static float cx; + static float cy; + static float invfx; + static float invfy; + cv::Mat mDistCoef; + + // Stereo baseline multiplied by fx. + float mbf; + + // Stereo baseline in meters. + float mb; + + // Threshold close/far points. Close points are inserted from 1 view. + // Far points are inserted as in the monocular case from 2 views. + float mThDepth; + + // Number of KeyPoints. + int N; + + // Vector of keypoints (original for visualization) and undistorted (actually used by the system). + // In the stereo case, mvKeysUn is redundant as images must be rectified. + // In the RGB-D case, RGB images can be distorted. + std::vector mvKeys, mvKeysRight; + std::vector mvKeysUn; + + // Corresponding stereo coordinate and depth for each keypoint. + // "Monocular" keypoints have a negative value. + std::vector mvuRight; + std::vector mvDepth; + + // Bag of Words Vector structures. + DBoW2::BowVector mBowVec; + DBoW2::FeatureVector mFeatVec; + + // ORB descriptor, each row associated to a keypoint. + cv::Mat mDescriptors, mDescriptorsRight; + + // MapPoints associated to keypoints, NULL pointer if no association. + std::vector mvpMapPoints; + + // Flag to identify outlier associations. + std::vector mvbOutlier; + + // Keypoints are assigned to cells in a grid to reduce matching complexity when projecting MapPoints. + static float mfGridElementWidthInv; + static float mfGridElementHeightInv; + std::vector mGrid[FRAME_GRID_COLS][FRAME_GRID_ROWS]; + + // Camera pose. + cv::Mat mTcw; + + // Current and Next Frame id. + static long unsigned int nNextId; + long unsigned int mnId; + + // Reference Keyframe. + KeyFrame* mpReferenceKF; + + // Scale pyramid info. + int mnScaleLevels; + float mfScaleFactor; + float mfLogScaleFactor; + vector mvScaleFactors; + vector mvInvScaleFactors; + vector mvLevelSigma2; + vector mvInvLevelSigma2; + + // Undistorted Image Bounds (computed once). + static float mnMinX; + static float mnMaxX; + static float mnMinY; + static float mnMaxY; + + static bool mbInitialComputations; + + +private: + + // Undistort keypoints given OpenCV distortion parameters. + // Only for the RGB-D case. Stereo must be already rectified! + // (called in the constructor). + void UndistortKeyPoints(); + + // Computes image bounds for the undistorted image (called in the constructor). + void ComputeImageBounds(const cv::Mat &imLeft); + + // Assign keypoints to the grid for speed up feature matching (called in the constructor). + void AssignFeaturesToGrid(); + + // Rotation, translation and camera center + cv::Mat mRcw; + cv::Mat mtcw; + cv::Mat mRwc; + cv::Mat mOw; //==mtwc +}; + +}// namespace ORB_SLAM + +#endif // FRAME_H diff --git a/include/FrameDrawer.h b/include/FrameDrawer.h new file mode 100644 index 0000000000..95c1df9d9e --- /dev/null +++ b/include/FrameDrawer.h @@ -0,0 +1,73 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef FRAMEDRAWER_H +#define FRAMEDRAWER_H + +#include "Tracking.h" +#include "MapPoint.h" +#include "Map.h" + +#include +#include + +#include + + +namespace ORB_SLAM2 +{ + +class Tracking; +class Viewer; + +class FrameDrawer +{ +public: + FrameDrawer(Map* pMap); + + // Update info from the last processed frame. + void Update(Tracking *pTracker); + + // Draw last processed frame. + cv::Mat DrawFrame(); + +protected: + + void DrawTextInfo(cv::Mat &im, int nState, cv::Mat &imText); + + // Info of the frame to be drawn + cv::Mat mIm; + int N; + vector mvCurrentKeys; + vector mvbMap, mvbVO; + bool mbOnlyTracking; + int mnTracked, mnTrackedVO; + vector mvIniKeys; + vector mvIniMatches; + int mState; + + Map* mpMap; + + std::mutex mMutex; +}; + +} //namespace ORB_SLAM + +#endif // FRAMEDRAWER_H diff --git a/include/Initializer.h b/include/Initializer.h new file mode 100644 index 0000000000..09b27a65bb --- /dev/null +++ b/include/Initializer.h @@ -0,0 +1,101 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ +#ifndef INITIALIZER_H +#define INITIALIZER_H + +#include +#include "Frame.h" + + +namespace ORB_SLAM2 +{ + +// THIS IS THE INITIALIZER FOR MONOCULAR SLAM. NOT USED IN THE STEREO OR RGBD CASE. +class Initializer +{ + typedef pair Match; + +public: + + // Fix the reference frame + Initializer(const Frame &ReferenceFrame, float sigma = 1.0, int iterations = 200); + + // Computes in parallel a fundamental matrix and a homography + // Selects a model and tries to recover the motion and the structure from motion + bool Initialize(const Frame &CurrentFrame, const vector &vMatches12, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated); + + +private: + + void FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21); + void FindFundamental(vector &vbInliers, float &score, cv::Mat &F21); + + cv::Mat ComputeH21(const vector &vP1, const vector &vP2); + cv::Mat ComputeF21(const vector &vP1, const vector &vP2); + + float CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma); + + float CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma); + + bool ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); + + bool ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated); + + void Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D); + + void Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T); + + int CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, + const vector &vMatches12, vector &vbInliers, + const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax); + + void DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t); + + + // Keypoints from Reference Frame (Frame 1) + vector mvKeys1; + + // Keypoints from Current Frame (Frame 2) + vector mvKeys2; + + // Current Matches from Reference to Current + vector mvMatches12; + vector mvbMatched1; + + // Calibration + cv::Mat mK; + + // Standard Deviation and Variance + float mSigma, mSigma2; + + // Ransac max iterations + int mMaxIterations; + + // Ransac sets + vector > mvSets; + +}; + +} //namespace ORB_SLAM + +#endif // INITIALIZER_H diff --git a/include/KeyFrame.h b/include/KeyFrame.h new file mode 100644 index 0000000000..67f4348273 --- /dev/null +++ b/include/KeyFrame.h @@ -0,0 +1,238 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef KEYFRAME_H +#define KEYFRAME_H + +#include "MapPoint.h" +#include "Thirdparty/DBoW2/DBoW2/BowVector.h" +#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" +#include "ORBVocabulary.h" +#include "ORBextractor.h" +#include "Frame.h" +#include "KeyFrameDatabase.h" + +#include + + +namespace ORB_SLAM2 +{ + +class Map; +class MapPoint; +class Frame; +class KeyFrameDatabase; + +class KeyFrame +{ +public: + KeyFrame(Frame &F, Map* pMap, KeyFrameDatabase* pKFDB); + + // Pose functions + void SetPose(const cv::Mat &Tcw); + cv::Mat GetPose(); + cv::Mat GetPoseInverse(); + cv::Mat GetCameraCenter(); + cv::Mat GetStereoCenter(); + cv::Mat GetRotation(); + cv::Mat GetTranslation(); + + // Bag of Words Representation + void ComputeBoW(); + + // Covisibility graph functions + void AddConnection(KeyFrame* pKF, const int &weight); + void EraseConnection(KeyFrame* pKF); + void UpdateConnections(); + void UpdateBestCovisibles(); + std::set GetConnectedKeyFrames(); + std::vector GetVectorCovisibleKeyFrames(); + std::vector GetBestCovisibilityKeyFrames(const int &N); + std::vector GetCovisiblesByWeight(const int &w); + int GetWeight(KeyFrame* pKF); + + // Spanning tree functions + void AddChild(KeyFrame* pKF); + void EraseChild(KeyFrame* pKF); + void ChangeParent(KeyFrame* pKF); + std::set GetChilds(); + KeyFrame* GetParent(); + bool hasChild(KeyFrame* pKF); + + // Loop Edges + void AddLoopEdge(KeyFrame* pKF); + std::set GetLoopEdges(); + + // MapPoint observation functions + void AddMapPoint(MapPoint* pMP, const size_t &idx); + void EraseMapPointMatch(const size_t &idx); + void EraseMapPointMatch(MapPoint* pMP); + void ReplaceMapPointMatch(const size_t &idx, MapPoint* pMP); + std::set GetMapPoints(); + std::vector GetMapPointMatches(); + int TrackedMapPoints(const int &minObs); + MapPoint* GetMapPoint(const size_t &idx); + + // KeyPoint functions + std::vector GetFeaturesInArea(const float &x, const float &y, const float &r) const; + cv::Mat UnprojectStereo(int i); + + // Image + bool IsInImage(const float &x, const float &y) const; + + // Enable/Disable bad flag changes + void SetNotErase(); + void SetErase(); + + // Set/check bad flag + void SetBadFlag(); + bool isBad(); + + // Compute Scene Depth (q=2 median). Used in monocular. + float ComputeSceneMedianDepth(const int q); + + static bool weightComp( int a, int b){ + return a>b; + } + + static bool lId(KeyFrame* pKF1, KeyFrame* pKF2){ + return pKF1->mnIdmnId; + } + + + // The following variables are accesed from only 1 thread or never change (no mutex needed). +public: + + static long unsigned int nNextId; + long unsigned int mnId; + const long unsigned int mnFrameId; + + const double mTimeStamp; + + // Grid (to speed up feature matching) + const int mnGridCols; + const int mnGridRows; + const float mfGridElementWidthInv; + const float mfGridElementHeightInv; + + // Variables used by the tracking + long unsigned int mnTrackReferenceForFrame; + long unsigned int mnFuseTargetForKF; + + // Variables used by the local mapping + long unsigned int mnBALocalForKF; + long unsigned int mnBAFixedForKF; + + // Variables used by the keyframe database + long unsigned int mnLoopQuery; + int mnLoopWords; + float mLoopScore; + long unsigned int mnRelocQuery; + int mnRelocWords; + float mRelocScore; + + // Variables used by loop closing + cv::Mat mTcwGBA; + cv::Mat mTcwBefGBA; + long unsigned int mnBAGlobalForKF; + + // Calibration parameters + const float fx, fy, cx, cy, invfx, invfy, mbf, mb, mThDepth; + + // Number of KeyPoints + const int N; + + // KeyPoints, stereo coordinate and descriptors (all associated by an index) + const std::vector mvKeys; + const std::vector mvKeysUn; + const std::vector mvuRight; // negative value for monocular points + const std::vector mvDepth; // negative value for monocular points + const cv::Mat mDescriptors; + + //BoW + DBoW2::BowVector mBowVec; + DBoW2::FeatureVector mFeatVec; + + // Pose relative to parent (this is computed when bad flag is activated) + cv::Mat mTcp; + + // Scale + const int mnScaleLevels; + const float mfScaleFactor; + const float mfLogScaleFactor; + const std::vector mvScaleFactors; + const std::vector mvLevelSigma2; + const std::vector mvInvLevelSigma2; + + // Image bounds and calibration + const int mnMinX; + const int mnMinY; + const int mnMaxX; + const int mnMaxY; + const cv::Mat mK; + + + // The following variables need to be accessed trough a mutex to be thread safe. +protected: + + // SE3 Pose and camera center + cv::Mat Tcw; + cv::Mat Twc; + cv::Mat Ow; + + cv::Mat Cw; // Stereo middel point. Only for visualization + + // MapPoints associated to keypoints + std::vector mvpMapPoints; + + // BoW + KeyFrameDatabase* mpKeyFrameDB; + ORBVocabulary* mpORBvocabulary; + + // Grid over the image to speed up feature matching + std::vector< std::vector > > mGrid; + + std::map mConnectedKeyFrameWeights; + std::vector mvpOrderedConnectedKeyFrames; + std::vector mvOrderedWeights; + + // Spanning Tree and Loop Edges + bool mbFirstConnection; + KeyFrame* mpParent; + std::set mspChildrens; + std::set mspLoopEdges; + + // Bad flags + bool mbNotErase; + bool mbToBeErased; + bool mbBad; + + float mHalfBaseline; // Only for visualization + + Map* mpMap; + + std::mutex mMutexPose; + std::mutex mMutexConnections; + std::mutex mMutexFeatures; +}; + +} //namespace ORB_SLAM + +#endif // KEYFRAME_H diff --git a/include/KeyFrameDatabase.h b/include/KeyFrameDatabase.h new file mode 100644 index 0000000000..fa3735762d --- /dev/null +++ b/include/KeyFrameDatabase.h @@ -0,0 +1,74 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef KEYFRAMEDATABASE_H +#define KEYFRAMEDATABASE_H + +#include +#include +#include + +#include "KeyFrame.h" +#include "Frame.h" +#include "ORBVocabulary.h" + +#include + + +namespace ORB_SLAM2 +{ + +class KeyFrame; +class Frame; + + +class KeyFrameDatabase +{ +public: + + KeyFrameDatabase(const ORBVocabulary &voc); + + void add(KeyFrame* pKF); + + void erase(KeyFrame* pKF); + + void clear(); + + // Loop Detection + std::vector DetectLoopCandidates(KeyFrame* pKF, float minScore); + + // Relocalization + std::vector DetectRelocalizationCandidates(Frame* F); + +protected: + + // Associated vocabulary + const ORBVocabulary* mpVoc; + + // Inverted file + std::vector > mvInvertedFile; + + // Mutex + std::mutex mMutex; +}; + +} //namespace ORB_SLAM + +#endif diff --git a/include/LocalMapping.h b/include/LocalMapping.h new file mode 100644 index 0000000000..1361a5757a --- /dev/null +++ b/include/LocalMapping.h @@ -0,0 +1,128 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef LOCALMAPPING_H +#define LOCALMAPPING_H + +#include "KeyFrame.h" +#include "Map.h" +#include "LoopClosing.h" +#include "Tracking.h" +#include "KeyFrameDatabase.h" + +#include + + +namespace ORB_SLAM2 +{ + +class Tracking; +class LoopClosing; +class Map; + +class LocalMapping +{ +public: + LocalMapping(Map* pMap, const float bMonocular); + + void SetLoopCloser(LoopClosing* pLoopCloser); + + void SetTracker(Tracking* pTracker); + + // Main function + void Run(); + + void InsertKeyFrame(KeyFrame* pKF); + + // Thread Synch + void RequestStop(); + void RequestReset(); + bool Stop(); + void Release(); + bool isStopped(); + bool stopRequested(); + bool AcceptKeyFrames(); + void SetAcceptKeyFrames(bool flag); + bool SetNotStop(bool flag); + + void InterruptBA(); + + void RequestFinish(); + bool isFinished(); + + int KeyframesInQueue(){ + unique_lock lock(mMutexNewKFs); + return mlNewKeyFrames.size(); + } + +protected: + + bool CheckNewKeyFrames(); + void ProcessNewKeyFrame(); + void CreateNewMapPoints(); + + void MapPointCulling(); + void SearchInNeighbors(); + + void KeyFrameCulling(); + + cv::Mat ComputeF12(KeyFrame* &pKF1, KeyFrame* &pKF2); + + cv::Mat SkewSymmetricMatrix(const cv::Mat &v); + + bool mbMonocular; + + void ResetIfRequested(); + bool mbResetRequested; + std::mutex mMutexReset; + + bool CheckFinish(); + void SetFinish(); + bool mbFinishRequested; + bool mbFinished; + std::mutex mMutexFinish; + + Map* mpMap; + + LoopClosing* mpLoopCloser; + Tracking* mpTracker; + + std::list mlNewKeyFrames; + + KeyFrame* mpCurrentKeyFrame; + + std::list mlpRecentAddedMapPoints; + + std::mutex mMutexNewKFs; + + bool mbAbortBA; + + bool mbStopped; + bool mbStopRequested; + bool mbNotStop; + std::mutex mMutexStop; + + bool mbAcceptKeyFrames; + std::mutex mMutexAccept; +}; + +} //namespace ORB_SLAM + +#endif // LOCALMAPPING_H diff --git a/include/LoopClosing.h b/include/LoopClosing.h new file mode 100644 index 0000000000..b1736fed78 --- /dev/null +++ b/include/LoopClosing.h @@ -0,0 +1,146 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef LOOPCLOSING_H +#define LOOPCLOSING_H + +#include "KeyFrame.h" +#include "LocalMapping.h" +#include "Map.h" +#include "ORBVocabulary.h" +#include "Tracking.h" + +#include "KeyFrameDatabase.h" + +#include +#include +#include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" + +namespace ORB_SLAM2 +{ + +class Tracking; +class LocalMapping; +class KeyFrameDatabase; + + +class LoopClosing +{ +public: + + typedef pair,int> ConsistentGroup; + typedef map, + Eigen::aligned_allocator > > KeyFrameAndPose; + +public: + + LoopClosing(Map* pMap, KeyFrameDatabase* pDB, ORBVocabulary* pVoc,const bool bFixScale); + + void SetTracker(Tracking* pTracker); + + void SetLocalMapper(LocalMapping* pLocalMapper); + + // Main function + void Run(); + + void InsertKeyFrame(KeyFrame *pKF); + + void RequestReset(); + + // This function will run in a separate thread + void RunGlobalBundleAdjustment(unsigned long nLoopKF); + + bool isRunningGBA(){ + unique_lock lock(mMutexGBA); + return mbRunningGBA; + } + bool isFinishedGBA(){ + unique_lock lock(mMutexGBA); + return mbFinishedGBA; + } + + void RequestFinish(); + + bool isFinished(); + +protected: + + bool CheckNewKeyFrames(); + + bool DetectLoop(); + + bool ComputeSim3(); + + void SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap); + + void CorrectLoop(); + + void ResetIfRequested(); + bool mbResetRequested; + std::mutex mMutexReset; + + bool CheckFinish(); + void SetFinish(); + bool mbFinishRequested; + bool mbFinished; + std::mutex mMutexFinish; + + Map* mpMap; + Tracking* mpTracker; + + KeyFrameDatabase* mpKeyFrameDB; + ORBVocabulary* mpORBVocabulary; + + LocalMapping *mpLocalMapper; + + std::list mlpLoopKeyFrameQueue; + + std::mutex mMutexLoopQueue; + + // Loop detector parameters + float mnCovisibilityConsistencyTh; + + // Loop detector variables + KeyFrame* mpCurrentKF; + KeyFrame* mpMatchedKF; + std::vector mvConsistentGroups; + std::vector mvpEnoughConsistentCandidates; + std::vector mvpCurrentConnectedKFs; + std::vector mvpCurrentMatchedPoints; + std::vector mvpLoopMapPoints; + cv::Mat mScw; + g2o::Sim3 mg2oScw; + + long unsigned int mLastLoopKFid; + + // Variables related to Global Bundle Adjustment + bool mbRunningGBA; + bool mbFinishedGBA; + bool mbStopGBA; + std::mutex mMutexGBA; + std::thread* mpThreadGBA; + + // Fix scale in the stereo/RGB-D case + bool mbFixScale; +}; + +} //namespace ORB_SLAM + +#endif // LOOPCLOSING_H diff --git a/include/Map.h b/include/Map.h new file mode 100644 index 0000000000..49ffab7374 --- /dev/null +++ b/include/Map.h @@ -0,0 +1,80 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef MAP_H +#define MAP_H + +#include "MapPoint.h" +#include "KeyFrame.h" +#include + +#include + + + +namespace ORB_SLAM2 +{ + +class MapPoint; +class KeyFrame; + +class Map +{ +public: + Map(); + + void AddKeyFrame(KeyFrame* pKF); + void AddMapPoint(MapPoint* pMP); + void EraseMapPoint(MapPoint* pMP); + void EraseKeyFrame(KeyFrame* pKF); + void SetReferenceMapPoints(const std::vector &vpMPs); + + std::vector GetAllKeyFrames(); + std::vector GetAllMapPoints(); + std::vector GetReferenceMapPoints(); + + long unsigned int MapPointsInMap(); + long unsigned KeyFramesInMap(); + + long unsigned int GetMaxKFid(); + + void clear(); + + vector mvpKeyFrameOrigins; + + std::mutex mMutexMapUpdate; + + // This avoid that two points are created simultaneously in separate threads (id conflict) + std::mutex mMutexPointCreation; + +protected: + std::set mspMapPoints; + std::set mspKeyFrames; + + std::vector mvpReferenceMapPoints; + + long unsigned int mnMaxKFid; + + std::mutex mMutexMap; +}; + +} //namespace ORB_SLAM + +#endif // MAP_H diff --git a/include/MapDrawer.h b/include/MapDrawer.h new file mode 100644 index 0000000000..83b282676d --- /dev/null +++ b/include/MapDrawer.h @@ -0,0 +1,64 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef MAPDRAWER_H +#define MAPDRAWER_H + +#include"Map.h" +#include"MapPoint.h" +#include"KeyFrame.h" +#include + +#include + +namespace ORB_SLAM2 +{ + +class MapDrawer +{ +public: + MapDrawer(Map* pMap, const string &strSettingPath); + + Map* mpMap; + + void DrawMapPoints(); + void DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph); + void DrawCurrentCamera(pangolin::OpenGlMatrix &Twc); + void SetCurrentCameraPose(const cv::Mat &Tcw); + void SetReferenceKeyFrame(KeyFrame *pKF); + void GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M); + +private: + + float mKeyFrameSize; + float mKeyFrameLineWidth; + float mGraphLineWidth; + float mPointSize; + float mCameraSize; + float mCameraLineWidth; + + cv::Mat mCameraPose; + + std::mutex mMutexCamera; +}; + +} //namespace ORB_SLAM + +#endif // MAPDRAWER_H diff --git a/include/MapPoint.h b/include/MapPoint.h new file mode 100644 index 0000000000..11568a504a --- /dev/null +++ b/include/MapPoint.h @@ -0,0 +1,151 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef MAPPOINT_H +#define MAPPOINT_H + +#include"KeyFrame.h" +#include"Frame.h" +#include"Map.h" + +#include +#include + +namespace ORB_SLAM2 +{ + +class KeyFrame; +class Map; +class Frame; + + +class MapPoint +{ +public: + MapPoint(const cv::Mat &Pos, KeyFrame* pRefKF, Map* pMap); + MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF); + + void SetWorldPos(const cv::Mat &Pos); + cv::Mat GetWorldPos(); + + cv::Mat GetNormal(); + KeyFrame* GetReferenceKeyFrame(); + + std::map GetObservations(); + int Observations(); + + void AddObservation(KeyFrame* pKF,size_t idx); + void EraseObservation(KeyFrame* pKF); + + int GetIndexInKeyFrame(KeyFrame* pKF); + bool IsInKeyFrame(KeyFrame* pKF); + + void SetBadFlag(); + bool isBad(); + + void Replace(MapPoint* pMP); + MapPoint* GetReplaced(); + + void IncreaseVisible(int n=1); + void IncreaseFound(int n=1); + float GetFoundRatio(); + inline int GetFound(){ + return mnFound; + } + + void ComputeDistinctiveDescriptors(); + + cv::Mat GetDescriptor(); + + void UpdateNormalAndDepth(); + + float GetMinDistanceInvariance(); + float GetMaxDistanceInvariance(); + int PredictScale(const float ¤tDist, const float &logScaleFactor); + +public: + long unsigned int mnId; + static long unsigned int nNextId; + long int mnFirstKFid; + long int mnFirstFrame; + int nObs; + + // Variables used by the tracking + float mTrackProjX; + float mTrackProjY; + float mTrackProjXR; + bool mbTrackInView; + int mnTrackScaleLevel; + float mTrackViewCos; + long unsigned int mnTrackReferenceForFrame; + long unsigned int mnLastFrameSeen; + + // Variables used by local mapping + long unsigned int mnBALocalForKF; + long unsigned int mnFuseCandidateForKF; + + // Variables used by loop closing + long unsigned int mnLoopPointForKF; + long unsigned int mnCorrectedByKF; + long unsigned int mnCorrectedReference; + cv::Mat mPosGBA; + long unsigned int mnBAGlobalForKF; + + + static std::mutex mGlobalMutex; + +protected: + + // Position in absolute coordinates + cv::Mat mWorldPos; + + // Keyframes observing the point and associated index in keyframe + std::map mObservations; + + // Mean viewing direction + cv::Mat mNormalVector; + + // Best descriptor to fast matching + cv::Mat mDescriptor; + + // Reference KeyFrame + KeyFrame* mpRefKF; + + // Tracking counters + int mnVisible; + int mnFound; + + // Bad flag (we do not currently erase MapPoint from memory) + bool mbBad; + MapPoint* mpReplaced; + + // Scale invariance distances + float mfMinDistance; + float mfMaxDistance; + + Map* mpMap; + + std::mutex mMutexPos; + std::mutex mMutexFeatures; +}; + +} //namespace ORB_SLAM + +#endif // MAPPOINT_H diff --git a/include/ORBVocabulary.h b/include/ORBVocabulary.h new file mode 100644 index 0000000000..ca5fa8d777 --- /dev/null +++ b/include/ORBVocabulary.h @@ -0,0 +1,36 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#ifndef ORBVOCABULARY_H +#define ORBVOCABULARY_H + +#include"Thirdparty/DBoW2/DBoW2/FORB.h" +#include"Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h" + +namespace ORB_SLAM2 +{ + +typedef DBoW2::TemplatedVocabulary + ORBVocabulary; + +} //namespace ORB_SLAM + +#endif // ORBVOCABULARY_H diff --git a/include/ORBextractor.h b/include/ORBextractor.h new file mode 100644 index 0000000000..66e8e7a547 --- /dev/null +++ b/include/ORBextractor.h @@ -0,0 +1,116 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef ORBEXTRACTOR_H +#define ORBEXTRACTOR_H + +#include +#include +#include + + +namespace ORB_SLAM2 +{ + +class ExtractorNode +{ +public: + ExtractorNode():bNoMore(false){} + + void DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4); + + std::vector vKeys; + cv::Point2i UL, UR, BL, BR; + std::list::iterator lit; + bool bNoMore; +}; + +class ORBextractor +{ +public: + + enum {HARRIS_SCORE=0, FAST_SCORE=1 }; + + ORBextractor(int nfeatures, float scaleFactor, int nlevels, + int iniThFAST, int minThFAST); + + ~ORBextractor(){} + + // Compute the ORB features and descriptors on an image. + // ORB are dispersed on the image using an octree. + // Mask is ignored in the current implementation. + void operator()( cv::InputArray image, cv::InputArray mask, + std::vector& keypoints, + cv::OutputArray descriptors); + + int inline GetLevels(){ + return nlevels;} + + float inline GetScaleFactor(){ + return scaleFactor;} + + std::vector inline GetScaleFactors(){ + return mvScaleFactor; + } + + std::vector inline GetInverseScaleFactors(){ + return mvInvScaleFactor; + } + + std::vector inline GetScaleSigmaSquares(){ + return mvLevelSigma2; + } + + std::vector inline GetInverseScaleSigmaSquares(){ + return mvInvLevelSigma2; + } + + std::vector mvImagePyramid; + +protected: + + void ComputePyramid(cv::Mat image); + void ComputeKeyPointsOctTree(std::vector >& allKeypoints); + std::vector DistributeOctTree(const std::vector& vToDistributeKeys, const int &minX, + const int &maxX, const int &minY, const int &maxY, const int &nFeatures, const int &level); + + void ComputeKeyPointsOld(std::vector >& allKeypoints); + std::vector pattern; + + int nfeatures; + double scaleFactor; + int nlevels; + int iniThFAST; + int minThFAST; + + std::vector mnFeaturesPerLevel; + + std::vector umax; + + std::vector mvScaleFactor; + std::vector mvInvScaleFactor; + std::vector mvLevelSigma2; + std::vector mvInvLevelSigma2; +}; + +} //namespace ORB_SLAM + +#endif + diff --git a/include/ORBmatcher.h b/include/ORBmatcher.h new file mode 100644 index 0000000000..ad881ee04a --- /dev/null +++ b/include/ORBmatcher.h @@ -0,0 +1,106 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#ifndef ORBMATCHER_H +#define ORBMATCHER_H + +#include +#include +#include + +#include"MapPoint.h" +#include"KeyFrame.h" +#include"Frame.h" + + +namespace ORB_SLAM2 +{ + +class ORBmatcher +{ +public: + + ORBmatcher(float nnratio=0.6, bool checkOri=true); + + // Computes the Hamming distance between two ORB descriptors + static int DescriptorDistance(const cv::Mat &a, const cv::Mat &b); + + // Search matches between Frame keypoints and projected MapPoints. Returns number of matches + // Used to track the local map (Tracking) + int SearchByProjection(Frame &F, const std::vector &vpMapPoints, const float th=3); + + // Project MapPoints tracked in last frame into the current frame and search matches. + // Used to track from previous frame (Tracking) + int SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono); + + // Project MapPoints seen in KeyFrame into the Frame and search matches. + // Used in relocalisation (Tracking) + int SearchByProjection(Frame &CurrentFrame, KeyFrame* pKF, const std::set &sAlreadyFound, const float th, const int ORBdist); + + // Project MapPoints using a Similarity Transformation and search matches. + // Used in loop detection (Loop Closing) + int SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpPoints, std::vector &vpMatched, int th); + + // Search matches between MapPoints in a KeyFrame and ORB in a Frame. + // Brute force constrained to ORB that belong to the same vocabulary node (at a certain level) + // Used in Relocalisation and Loop Detection + int SearchByBoW(KeyFrame *pKF, Frame &F, std::vector &vpMapPointMatches); + int SearchByBoW(KeyFrame *pKF1, KeyFrame* pKF2, std::vector &vpMatches12); + + // Matching for the Map Initialization (only used in the monocular case) + int SearchForInitialization(Frame &F1, Frame &F2, std::vector &vbPrevMatched, std::vector &vnMatches12, int windowSize=10); + + // Matching to triangulate new MapPoints. Check Epipolar Constraint. + int SearchForTriangulation(KeyFrame *pKF1, KeyFrame* pKF2, cv::Mat F12, + std::vector > &vMatchedPairs, const bool bOnlyStereo); + + // Search matches between MapPoints seen in KF1 and KF2 transforming by a Sim3 [s12*R12|t12] + // In the stereo and RGB-D case, s12=1 + int SearchBySim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector &vpMatches12, const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th); + + // Project MapPoints into KeyFrame and search for duplicated MapPoints. + int Fuse(KeyFrame* pKF, const vector &vpMapPoints, const float th=3.0); + + // Project MapPoints into KeyFrame using a given Sim3 and search for duplicated MapPoints. + int Fuse(KeyFrame* pKF, cv::Mat Scw, const std::vector &vpPoints, float th, vector &vpReplacePoint); + +public: + + static const int TH_LOW; + static const int TH_HIGH; + static const int HISTO_LENGTH; + + +protected: + + bool CheckDistEpipolarLine(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &F12, const KeyFrame *pKF); + + float RadiusByViewingCos(const float &viewCos); + + void ComputeThreeMaxima(std::vector* histo, const int L, int &ind1, int &ind2, int &ind3); + + float mfNNratio; + bool mbCheckOrientation; +}; + +}// namespace ORB_SLAM + +#endif // ORBMATCHER_H diff --git a/include/Optimizer.h b/include/Optimizer.h new file mode 100644 index 0000000000..2c4378ed3b --- /dev/null +++ b/include/Optimizer.h @@ -0,0 +1,62 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#ifndef OPTIMIZER_H +#define OPTIMIZER_H + +#include "Map.h" +#include "MapPoint.h" +#include "KeyFrame.h" +#include "LoopClosing.h" +#include "Frame.h" + +#include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" + +namespace ORB_SLAM2 +{ + +class LoopClosing; + +class Optimizer +{ +public: + void static BundleAdjustment(const std::vector &vpKF, const std::vector &vpMP, + int nIterations = 5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, + const bool bRobust = true); + void static GlobalBundleAdjustemnt(Map* pMap, int nIterations=5, bool *pbStopFlag=NULL, + const unsigned long nLoopKF=0, const bool bRobust = true); + void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, Map *pMap); + int static PoseOptimization(Frame* pFrame); + + // if bFixScale is true, 6DoF optimization (stereo,rgbd), 7DoF otherwise (mono) + void static OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3, + const map > &LoopConnections, + const bool &bFixScale); + + // if bFixScale is true, optimize SE3 (stereo,rgbd), Sim3 otherwise (mono) + static int OptimizeSim3(KeyFrame* pKF1, KeyFrame* pKF2, std::vector &vpMatches1, + g2o::Sim3 &g2oS12, const float th2, const bool bFixScale); +}; + +} //namespace ORB_SLAM + +#endif // OPTIMIZER_H diff --git a/include/PnPsolver.h b/include/PnPsolver.h new file mode 100644 index 0000000000..f92544fc8f --- /dev/null +++ b/include/PnPsolver.h @@ -0,0 +1,198 @@ +/** +* This file is part of ORB-SLAM2. +* This file is a modified version of EPnP , see FreeBSD license below. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +/** +* Copyright (c) 2009, V. Lepetit, EPFL +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* 2. Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR +* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* +* The views and conclusions contained in the software and documentation are those +* of the authors and should not be interpreted as representing official policies, +* either expressed or implied, of the FreeBSD Project +*/ + +#ifndef PNPSOLVER_H +#define PNPSOLVER_H + +#include +#include "MapPoint.h" +#include "Frame.h" + +namespace ORB_SLAM2 +{ + +class PnPsolver { + public: + PnPsolver(const Frame &F, const vector &vpMapPointMatches); + + ~PnPsolver(); + + void SetRansacParameters(double probability = 0.99, int minInliers = 8 , int maxIterations = 300, int minSet = 4, float epsilon = 0.4, + float th2 = 5.991); + + cv::Mat find(vector &vbInliers, int &nInliers); + + cv::Mat iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers); + + private: + + void CheckInliers(); + bool Refine(); + + // Functions from the original EPnP code + void set_maximum_number_of_correspondences(const int n); + void reset_correspondences(void); + void add_correspondence(const double X, const double Y, const double Z, + const double u, const double v); + + double compute_pose(double R[3][3], double T[3]); + + void relative_error(double & rot_err, double & transl_err, + const double Rtrue[3][3], const double ttrue[3], + const double Rest[3][3], const double test[3]); + + void print_pose(const double R[3][3], const double t[3]); + double reprojection_error(const double R[3][3], const double t[3]); + + void choose_control_points(void); + void compute_barycentric_coordinates(void); + void fill_M(CvMat * M, const int row, const double * alphas, const double u, const double v); + void compute_ccs(const double * betas, const double * ut); + void compute_pcs(void); + + void solve_for_sign(void); + + void find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho, double * betas); + void find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho, double * betas); + void find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho, double * betas); + void qr_solve(CvMat * A, CvMat * b, CvMat * X); + + double dot(const double * v1, const double * v2); + double dist2(const double * p1, const double * p2); + + void compute_rho(double * rho); + void compute_L_6x10(const double * ut, double * l_6x10); + + void gauss_newton(const CvMat * L_6x10, const CvMat * Rho, double current_betas[4]); + void compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho, + double cb[4], CvMat * A, CvMat * b); + + double compute_R_and_t(const double * ut, const double * betas, + double R[3][3], double t[3]); + + void estimate_R_and_t(double R[3][3], double t[3]); + + void copy_R_and_t(const double R_dst[3][3], const double t_dst[3], + double R_src[3][3], double t_src[3]); + + void mat_to_quat(const double R[3][3], double q[4]); + + + double uc, vc, fu, fv; + + double * pws, * us, * alphas, * pcs; + int maximum_number_of_correspondences; + int number_of_correspondences; + + double cws[4][3], ccs[4][3]; + double cws_determinant; + + vector mvpMapPointMatches; + + // 2D Points + vector mvP2D; + vector mvSigma2; + + // 3D Points + vector mvP3Dw; + + // Index in Frame + vector mvKeyPointIndices; + + // Current Estimation + double mRi[3][3]; + double mti[3]; + cv::Mat mTcwi; + vector mvbInliersi; + int mnInliersi; + + // Current Ransac State + int mnIterations; + vector mvbBestInliers; + int mnBestInliers; + cv::Mat mBestTcw; + + // Refined + cv::Mat mRefinedTcw; + vector mvbRefinedInliers; + int mnRefinedInliers; + + // Number of Correspondences + int N; + + // Indices for random selection [0 .. N-1] + vector mvAllIndices; + + // RANSAC probability + double mRansacProb; + + // RANSAC min inliers + int mRansacMinInliers; + + // RANSAC max iterations + int mRansacMaxIts; + + // RANSAC expected inliers/total ratio + float mRansacEpsilon; + + // RANSAC Threshold inlier/outlier. Max error e = dist(P1,T_12*P2)^2 + float mRansacTh; + + // RANSAC Minimun Set used at each iteration + int mRansacMinSet; + + // Max square error associated with scale level. Max error = th*th*sigma(level)*sigma(level) + vector mvMaxError; + +}; + +} //namespace ORB_SLAM + +#endif //PNPSOLVER_H diff --git a/include/Sim3Solver.h b/include/Sim3Solver.h new file mode 100644 index 0000000000..9af66cb26f --- /dev/null +++ b/include/Sim3Solver.h @@ -0,0 +1,133 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#ifndef SIM3SOLVER_H +#define SIM3SOLVER_H + +#include +#include + +#include "KeyFrame.h" + + + +namespace ORB_SLAM2 +{ + +class Sim3Solver +{ +public: + + Sim3Solver(KeyFrame* pKF1, KeyFrame* pKF2, const std::vector &vpMatched12, const bool bFixScale = true); + + void SetRansacParameters(double probability = 0.99, int minInliers = 6 , int maxIterations = 300); + + cv::Mat find(std::vector &vbInliers12, int &nInliers); + + cv::Mat iterate(int nIterations, bool &bNoMore, std::vector &vbInliers, int &nInliers); + + cv::Mat GetEstimatedRotation(); + cv::Mat GetEstimatedTranslation(); + float GetEstimatedScale(); + + +protected: + + void ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C); + + void ComputeSim3(cv::Mat &P1, cv::Mat &P2); + + void CheckInliers(); + + void Project(const std::vector &vP3Dw, std::vector &vP2D, cv::Mat Tcw, cv::Mat K); + void FromCameraToImage(const std::vector &vP3Dc, std::vector &vP2D, cv::Mat K); + + +protected: + + // KeyFrames and matches + KeyFrame* mpKF1; + KeyFrame* mpKF2; + + std::vector mvX3Dc1; + std::vector mvX3Dc2; + std::vector mvpMapPoints1; + std::vector mvpMapPoints2; + std::vector mvpMatches12; + std::vector mvnIndices1; + std::vector mvSigmaSquare1; + std::vector mvSigmaSquare2; + std::vector mvnMaxError1; + std::vector mvnMaxError2; + + int N; + int mN1; + + // Current Estimation + cv::Mat mR12i; + cv::Mat mt12i; + float ms12i; + cv::Mat mT12i; + cv::Mat mT21i; + std::vector mvbInliersi; + int mnInliersi; + + // Current Ransac State + int mnIterations; + std::vector mvbBestInliers; + int mnBestInliers; + cv::Mat mBestT12; + cv::Mat mBestRotation; + cv::Mat mBestTranslation; + float mBestScale; + + // Scale is fixed to 1 in the stereo/RGBD case + bool mbFixScale; + + // Indices for random selection + std::vector mvAllIndices; + + // Projections + std::vector mvP1im1; + std::vector mvP2im2; + + // RANSAC probability + double mRansacProb; + + // RANSAC min inliers + int mRansacMinInliers; + + // RANSAC max iterations + int mRansacMaxIts; + + // Threshold inlier/outlier. e = dist(Pi,T_ij*Pj)^2 < 5.991*mSigma2 + float mTh; + float mSigma2; + + // Calibration + cv::Mat mK1; + cv::Mat mK2; + +}; + +} //namespace ORB_SLAM + +#endif // SIM3SOLVER_H diff --git a/include/System.h b/include/System.h new file mode 100644 index 0000000000..d0a780e3bb --- /dev/null +++ b/include/System.h @@ -0,0 +1,166 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#ifndef SYSTEM_H +#define SYSTEM_H + +#include +#include +#include + +#include "Tracking.h" +#include "FrameDrawer.h" +#include "MapDrawer.h" +#include "Map.h" +#include "LocalMapping.h" +#include "LoopClosing.h" +#include "KeyFrameDatabase.h" +#include "ORBVocabulary.h" +#include "Viewer.h" + +namespace ORB_SLAM2 +{ + +class Viewer; +class FrameDrawer; +class Map; +class Tracking; +class LocalMapping; +class LoopClosing; + +class System +{ +public: + // Input sensor + enum eSensor{ + MONOCULAR=0, + STEREO=1, + RGBD=2 + }; + +public: + + // Initialize the SLAM system. It launches the Local Mapping, Loop Closing and Viewer threads. + System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, const bool bUseViewer = true); + + // Proccess the given stereo frame. Images must be synchronized and rectified. + // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. + // Returns the camera pose (empty if tracking fails). + cv::Mat TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double ×tamp); + + // Process the given rgbd frame. Depthmap must be registered to the RGB frame. + // Input image: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. + // Input depthmap: Float (CV_32F). + // Returns the camera pose (empty if tracking fails). + cv::Mat TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double ×tamp); + + // Proccess the given monocular frame + // Input images: RGB (CV_8UC3) or grayscale (CV_8U). RGB is converted to grayscale. + // Returns the camera pose (empty if tracking fails). + cv::Mat TrackMonocular(const cv::Mat &im, const double ×tamp); + + // This stops local mapping thread (map building) and performs only camera tracking. + void ActivateLocalizationMode(); + // This resumes local mapping thread and performs SLAM again. + void DeactivateLocalizationMode(); + + // Reset the system (clear map) + void Reset(); + + // All threads will be requested to finish. + // It waits until all threads have finished. + // This function must be called before saving the trajectory. + void Shutdown(); + + // Save camera trajectory in the TUM RGB-D dataset format. + // Call first Shutdown() + // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset + void SaveTrajectoryTUM(const string &filename); + + // Save keyframe poses in the TUM RGB-D dataset format. + // Use this function in the monocular case. + // Call first Shutdown() + // See format details at: http://vision.in.tum.de/data/datasets/rgbd-dataset + void SaveKeyFrameTrajectoryTUM(const string &filename); + + // Save camera trajectory in the KITTI dataset format. + // Call first Shutdown() + // See format details at: http://www.cvlibs.net/datasets/kitti/eval_odometry.php + void SaveTrajectoryKITTI(const string &filename); + + // TODO: Reset function + // Reset(); + + // TODO: Save/Load functions + // SaveMap(const string &filename); + // LoadMap(const string &filename); + +private: + + // Input sensor + eSensor mSensor; + + // ORB vocabulary used for place recognition and feature matching. + ORBVocabulary* mpVocabulary; + + // KeyFrame database for place recognition (relocalization and loop detection). + KeyFrameDatabase* mpKeyFrameDatabase; + + // Map structure that stores the pointers to all KeyFrames and MapPoints. + Map* mpMap; + + // Tracker. It receives a frame and computes the associated camera pose. + // It also decides when to insert a new keyframe, create some new MapPoints and + // performs relocalization if tracking fails. + Tracking* mpTracker; + + // Local Mapper. It manages the local map and performs local bundle adjustment. + LocalMapping* mpLocalMapper; + + // Loop Closer. It searches loops with every new keyframe. If there is a loop it performs + // a pose graph optimization and full bundle adjustment (in a new thread) afterwards. + LoopClosing* mpLoopCloser; + + // The viewer draws the map and the current camera pose. It uses Pangolin. + Viewer* mpViewer; + + FrameDrawer* mpFrameDrawer; + MapDrawer* mpMapDrawer; + + // System threads: Local Mapping, Loop Closing, Viewer. + // The Tracking thread "lives" in the main execution thread that creates the System object. + std::thread* mptLocalMapping; + std::thread* mptLoopClosing; + std::thread* mptViewer; + + // Reset flag + std::mutex mMutexReset; + bool mbReset; + + // Change mode flags + std::mutex mMutexMode; + bool mbActivateLocalizationMode; + bool mbDeactivateLocalizationMode; +}; + +}// namespace ORB_SLAM + +#endif // SYSTEM_H diff --git a/include/Tracking.h b/include/Tracking.h new file mode 100644 index 0000000000..b418168479 --- /dev/null +++ b/include/Tracking.h @@ -0,0 +1,218 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#ifndef TRACKING_H +#define TRACKING_H + +#include +#include + +#include"Viewer.h" +#include"FrameDrawer.h" +#include"Map.h" +#include"LocalMapping.h" +#include"LoopClosing.h" +#include"Frame.h" +#include "ORBVocabulary.h" +#include"KeyFrameDatabase.h" +#include"ORBextractor.h" +#include "Initializer.h" +#include "MapDrawer.h" +#include "System.h" + +#include + +namespace ORB_SLAM2 +{ + +class Viewer; +class FrameDrawer; +class Map; +class LocalMapping; +class LoopClosing; +class System; + +class Tracking +{ + +public: + Tracking(ORBVocabulary* pVoc, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Map* pMap, + KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor); + + // Preprocess the input and call Track(). Extract features and performs stereo matching. + cv::Mat GrabImageStereo(const cv::Mat &imRectLeft,const cv::Mat &imRectRight, const double ×tamp); + cv::Mat GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp); + cv::Mat GrabImageMonocular(const cv::Mat &im, const double ×tamp); + + void SetLocalMapper(LocalMapping* pLocalMapper); + void SetLoopClosing(LoopClosing* pLoopClosing); + void SetViewer(Viewer* pViewer); + + // Load new settings + // The focal lenght should be similar or scale prediction will fail when projecting points + // TODO: Modify MapPoint::PredictScale to take into account focal lenght + void ChangeCalibration(const string &strSettingPath); + + // Use this function if you have deactivated local mapping and you only want to localize the camera. + void InformOnlyTracking(const bool &flag); + + +public: + + // Tracking states + enum eTrackingState{ + SYSTEM_NOT_READY=-1, + NO_IMAGES_YET=0, + NOT_INITIALIZED=1, + OK=2, + LOST=3 + }; + + eTrackingState mState; + eTrackingState mLastProcessedState; + + // Input sensor + int mSensor; + + // Current Frame + Frame mCurrentFrame; + cv::Mat mImGray; + + // Initialization Variables (Monocular) + std::vector mvIniLastMatches; + std::vector mvIniMatches; + std::vector mvbPrevMatched; + std::vector mvIniP3D; + Frame mInitialFrame; + + // Lists used to recover the full camera trajectory at the end of the execution. + // Basically we store the reference keyframe for each frame and its relative transformation + list mlRelativeFramePoses; + list mlpReferences; + list mlFrameTimes; + list mlbLost; + + // True if local mapping is deactivated and we are performing only localization + bool mbOnlyTracking; + + void Reset(); + +protected: + + // Main tracking function. It is independent of the input sensor. + void Track(); + + // Map initialization for stereo and RGB-D + void StereoInitialization(); + + // Map initialization for monocular + void MonocularInitialization(); + void CreateInitialMapMonocular(); + + void CheckReplacedInLastFrame(); + bool TrackReferenceKeyFrame(); + void UpdateLastFrame(); + bool TrackWithMotionModel(); + + bool Relocalization(); + + void UpdateLocalMap(); + void UpdateLocalPoints(); + void UpdateLocalKeyFrames(); + + bool TrackLocalMap(); + void SearchLocalPoints(); + + bool NeedNewKeyFrame(); + void CreateNewKeyFrame(); + + // In case of performing only localization, this flag is true when there are no matches to + // points in the map. Still tracking will continue if there are enough matches with temporal points. + // In that case we are doing visual odometry. The system will try to do relocalization to recover + // "zero-drift" localization to the map. + bool mbVO; + + //Other Thread Pointers + LocalMapping* mpLocalMapper; + LoopClosing* mpLoopClosing; + + //ORB + ORBextractor* mpORBextractorLeft, *mpORBextractorRight; + ORBextractor* mpIniORBextractor; + + //BoW + ORBVocabulary* mpORBVocabulary; + KeyFrameDatabase* mpKeyFrameDB; + + // Initalization (only for monocular) + Initializer* mpInitializer; + + //Local Map + KeyFrame* mpReferenceKF; + std::vector mvpLocalKeyFrames; + std::vector mvpLocalMapPoints; + + //Drawers + Viewer* mpViewer; + FrameDrawer* mpFrameDrawer; + MapDrawer* mpMapDrawer; + + //Map + Map* mpMap; + + //Calibration matrix + cv::Mat mK; + cv::Mat mDistCoef; + float mbf; + + //New KeyFrame rules (according to fps) + int mMinFrames; + int mMaxFrames; + + // Threshold close/far points + // Points seen as close by the stereo/RGBD sensor are considered reliable + // and inserted from just one frame. Far points requiere a match in two keyframes. + float mThDepth; + + // For RGB-D inputs only. For some datasets (e.g. TUM) the depthmap values are scaled. + float mDepthMapFactor; + + //Current matches in frame + int mnMatchesInliers; + + //Last Frame, KeyFrame and Relocalisation Info + KeyFrame* mpLastKeyFrame; + Frame mLastFrame; + unsigned int mnLastKeyFrameId; + unsigned int mnLastRelocFrameId; + + //Motion Model + cv::Mat mVelocity; + + //Color order (true RGB, false BGR, ignored if grayscale) + bool mbRGB; + + list mlpTemporalPoints; +}; + +} //namespace ORB_SLAM + +#endif // TRACKING_H diff --git a/include/Viewer.h b/include/Viewer.h new file mode 100644 index 0000000000..251e223c54 --- /dev/null +++ b/include/Viewer.h @@ -0,0 +1,91 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#ifndef VIEWER_H +#define VIEWER_H + +#include "FrameDrawer.h" +#include "MapDrawer.h" +#include "Tracking.h" +#include "System.h" + +#include + +namespace ORB_SLAM2 +{ + +class Tracking; +class FrameDrawer; +class MapDrawer; +class System; + +class Viewer +{ +public: + Viewer(System* pSystem, FrameDrawer* pFrameDrawer, MapDrawer* pMapDrawer, Tracking *pTracking, const string &strSettingPath); + + // Main thread function. Draw points, keyframes, the current camera pose and the last processed + // frame. Drawing is refreshed according to the camera fps. We use Pangolin. + void Run(); + + void RequestFinish(); + + void RequestStop(); + + bool isFinished(); + + bool isStopped(); + + void Release(); + +private: + + bool Stop(); + + System* mpSystem; + FrameDrawer* mpFrameDrawer; + MapDrawer* mpMapDrawer; + Tracking* mpTracker; + + // 1/fps in ms + double mT; + float mImageWidth, mImageHeight; + + float mViewpointX, mViewpointY, mViewpointZ, mViewpointF; + + bool CheckFinish(); + void SetFinish(); + bool mbFinishRequested; + bool mbFinished; + std::mutex mMutexFinish; + + bool mbStopped; + bool mbStopRequested; + std::mutex mMutexStop; + +}; + +} + + +#endif // VIEWER_H + + diff --git a/src/Converter.cc b/src/Converter.cc new file mode 100644 index 0000000000..00ea8ee597 --- /dev/null +++ b/src/Converter.cc @@ -0,0 +1,151 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include "Converter.h" + +namespace ORB_SLAM2 +{ + +std::vector Converter::toDescriptorVector(const cv::Mat &Descriptors) +{ + std::vector vDesc; + vDesc.reserve(Descriptors.rows); + for (int j=0;j R; + R << cvT.at(0,0), cvT.at(0,1), cvT.at(0,2), + cvT.at(1,0), cvT.at(1,1), cvT.at(1,2), + cvT.at(2,0), cvT.at(2,1), cvT.at(2,2); + + Eigen::Matrix t(cvT.at(0,3), cvT.at(1,3), cvT.at(2,3)); + + return g2o::SE3Quat(R,t); +} + +cv::Mat Converter::toCvMat(const g2o::SE3Quat &SE3) +{ + Eigen::Matrix eigMat = SE3.to_homogeneous_matrix(); + return toCvMat(eigMat); +} + +cv::Mat Converter::toCvMat(const g2o::Sim3 &Sim3) +{ + Eigen::Matrix3d eigR = Sim3.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = Sim3.translation(); + double s = Sim3.scale(); + return toCvSE3(s*eigR,eigt); +} + +cv::Mat Converter::toCvMat(const Eigen::Matrix &m) +{ + cv::Mat cvMat(4,4,CV_32F); + for(int i=0;i<4;i++) + for(int j=0; j<4; j++) + cvMat.at(i,j)=m(i,j); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvMat(const Eigen::Matrix3d &m) +{ + cv::Mat cvMat(3,3,CV_32F); + for(int i=0;i<3;i++) + for(int j=0; j<3; j++) + cvMat.at(i,j)=m(i,j); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvMat(const Eigen::Matrix &m) +{ + cv::Mat cvMat(3,1,CV_32F); + for(int i=0;i<3;i++) + cvMat.at(i)=m(i); + + return cvMat.clone(); +} + +cv::Mat Converter::toCvSE3(const Eigen::Matrix &R, const Eigen::Matrix &t) +{ + cv::Mat cvMat = cv::Mat::eye(4,4,CV_32F); + for(int i=0;i<3;i++) + { + for(int j=0;j<3;j++) + { + cvMat.at(i,j)=R(i,j); + } + } + for(int i=0;i<3;i++) + { + cvMat.at(i,3)=t(i); + } + + return cvMat.clone(); +} + +Eigen::Matrix Converter::toVector3d(const cv::Mat &cvVector) +{ + Eigen::Matrix v; + v << cvVector.at(0), cvVector.at(1), cvVector.at(2); + + return v; +} + +Eigen::Matrix Converter::toVector3d(const cv::Point3f &cvPoint) +{ + Eigen::Matrix v; + v << cvPoint.x, cvPoint.y, cvPoint.z; + + return v; +} + +Eigen::Matrix Converter::toMatrix3d(const cv::Mat &cvMat3) +{ + Eigen::Matrix M; + + M << cvMat3.at(0,0), cvMat3.at(0,1), cvMat3.at(0,2), + cvMat3.at(1,0), cvMat3.at(1,1), cvMat3.at(1,2), + cvMat3.at(2,0), cvMat3.at(2,1), cvMat3.at(2,2); + + return M; +} + +std::vector Converter::toQuaternion(const cv::Mat &M) +{ + Eigen::Matrix eigMat = toMatrix3d(M); + Eigen::Quaterniond q(eigMat); + + std::vector v(4); + v[0] = q.x(); + v[1] = q.y(); + v[2] = q.z(); + v[3] = q.w(); + + return v; +} + +} //namespace ORB_SLAM diff --git a/src/Frame.cc b/src/Frame.cc new file mode 100644 index 0000000000..d4c362bfe9 --- /dev/null +++ b/src/Frame.cc @@ -0,0 +1,680 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "Frame.h" +#include "Converter.h" +#include "ORBmatcher.h" +#include + +namespace ORB_SLAM2 +{ + +long unsigned int Frame::nNextId=0; +bool Frame::mbInitialComputations=true; +float Frame::cx, Frame::cy, Frame::fx, Frame::fy, Frame::invfx, Frame::invfy; +float Frame::mnMinX, Frame::mnMinY, Frame::mnMaxX, Frame::mnMaxY; +float Frame::mfGridElementWidthInv, Frame::mfGridElementHeightInv; + +Frame::Frame() +{} + +//Copy Constructor +Frame::Frame(const Frame &frame) + :mpORBvocabulary(frame.mpORBvocabulary), mpORBextractorLeft(frame.mpORBextractorLeft), mpORBextractorRight(frame.mpORBextractorRight), + mTimeStamp(frame.mTimeStamp), mK(frame.mK.clone()), mDistCoef(frame.mDistCoef.clone()), + mbf(frame.mbf), mb(frame.mb), mThDepth(frame.mThDepth), N(frame.N), mvKeys(frame.mvKeys), + mvKeysRight(frame.mvKeysRight), mvKeysUn(frame.mvKeysUn), mvuRight(frame.mvuRight), + mvDepth(frame.mvDepth), mBowVec(frame.mBowVec), mFeatVec(frame.mFeatVec), + mDescriptors(frame.mDescriptors.clone()), mDescriptorsRight(frame.mDescriptorsRight.clone()), + mvpMapPoints(frame.mvpMapPoints), mvbOutlier(frame.mvbOutlier), mnId(frame.mnId), + mpReferenceKF(frame.mpReferenceKF), mnScaleLevels(frame.mnScaleLevels), + mfScaleFactor(frame.mfScaleFactor), mfLogScaleFactor(frame.mfLogScaleFactor), + mvScaleFactors(frame.mvScaleFactors), mvInvScaleFactors(frame.mvInvScaleFactors), + mvLevelSigma2(frame.mvLevelSigma2), mvInvLevelSigma2(frame.mvInvLevelSigma2) +{ + for(int i=0;i(NULL)) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction + thread threadLeft(&Frame::ExtractORB,this,0,imLeft); + thread threadRight(&Frame::ExtractORB,this,1,imRight); + threadLeft.join(); + threadRight.join(); + + if(mvKeys.empty()) + return; + + N = mvKeys.size(); + + UndistortKeyPoints(); + + ComputeStereoMatches(); + + mvpMapPoints = vector(N,static_cast(NULL)); + mvbOutlier = vector(N,false); + + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imLeft); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/(mnMaxY-mnMinY); + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf/fx; + + AssignFeaturesToGrid(); +} + +Frame::Frame(const cv::Mat &imGray, const cv::Mat &imDepth, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth) + :mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast(NULL)), + mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction + ExtractORB(0,imGray); + + N = mvKeys.size(); + + if(mvKeys.empty()) + return; + + UndistortKeyPoints(); + + ComputeStereoFromRGBD(imDepth); + + mvpMapPoints = vector(N,static_cast(NULL)); + mvbOutlier = vector(N,false); + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imGray); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/static_cast(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/static_cast(mnMaxY-mnMinY); + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf/fx; + + AssignFeaturesToGrid(); +} + + +Frame::Frame(const cv::Mat &imGray, const double &timeStamp, ORBextractor* extractor,ORBVocabulary* voc, cv::Mat &K, cv::Mat &distCoef, const float &bf, const float &thDepth) + :mpORBvocabulary(voc),mpORBextractorLeft(extractor),mpORBextractorRight(static_cast(NULL)), + mTimeStamp(timeStamp), mK(K.clone()),mDistCoef(distCoef.clone()), mbf(bf), mThDepth(thDepth) +{ + // Frame ID + mnId=nNextId++; + + // Scale Level Info + mnScaleLevels = mpORBextractorLeft->GetLevels(); + mfScaleFactor = mpORBextractorLeft->GetScaleFactor(); + mfLogScaleFactor = log(mfScaleFactor); + mvScaleFactors = mpORBextractorLeft->GetScaleFactors(); + mvInvScaleFactors = mpORBextractorLeft->GetInverseScaleFactors(); + mvLevelSigma2 = mpORBextractorLeft->GetScaleSigmaSquares(); + mvInvLevelSigma2 = mpORBextractorLeft->GetInverseScaleSigmaSquares(); + + // ORB extraction + ExtractORB(0,imGray); + + N = mvKeys.size(); + + if(mvKeys.empty()) + return; + + UndistortKeyPoints(); + + // Set no stereo information + mvuRight = vector(N,-1); + mvDepth = vector(N,-1); + + mvpMapPoints = vector(N,static_cast(NULL)); + mvbOutlier = vector(N,false); + + // This is done only for the first Frame (or after a change in the calibration) + if(mbInitialComputations) + { + ComputeImageBounds(imGray); + + mfGridElementWidthInv=static_cast(FRAME_GRID_COLS)/static_cast(mnMaxX-mnMinX); + mfGridElementHeightInv=static_cast(FRAME_GRID_ROWS)/static_cast(mnMaxY-mnMinY); + + fx = K.at(0,0); + fy = K.at(1,1); + cx = K.at(0,2); + cy = K.at(1,2); + invfx = 1.0f/fx; + invfy = 1.0f/fy; + + mbInitialComputations=false; + } + + mb = mbf/fx; + + AssignFeaturesToGrid(); +} + +void Frame::AssignFeaturesToGrid() +{ + int nReserve = 0.5f*N/(FRAME_GRID_COLS*FRAME_GRID_ROWS); + for(unsigned int i=0; imbTrackInView = false; + + // 3D in absolute coordinates + cv::Mat P = pMP->GetWorldPos(); + + // 3D in camera coordinates + const cv::Mat Pc = mRcw*P+mtcw; + const float &PcX = Pc.at(0); + const float &PcY= Pc.at(1); + const float &PcZ = Pc.at(2); + + // Check positive depth + if(PcZ<0.0f) + return false; + + // Project in image and check it is not outside + const float invz = 1.0f/PcZ; + const float u=fx*PcX*invz+cx; + const float v=fy*PcY*invz+cy; + + if(umnMaxX) + return false; + if(vmnMaxY) + return false; + + // Check distance is in the scale invariance region of the MapPoint + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const cv::Mat PO = P-mOw; + const float dist = cv::norm(PO); + + if(distmaxDistance) + return false; + + // Check viewing angle + cv::Mat Pn = pMP->GetNormal(); + + const float viewCos = PO.dot(Pn)/dist; + + if(viewCosPredictScale(dist,mfLogScaleFactor); + + // Data used by the tracking + pMP->mbTrackInView = true; + pMP->mTrackProjX = u; + pMP->mTrackProjXR = u - mbf*invz; + pMP->mTrackProjY = v; + pMP->mnTrackScaleLevel= nPredictedLevel; + pMP->mTrackViewCos = viewCos; + + return true; +} + +vector Frame::GetFeaturesInArea(const float &x, const float &y, const float &r, const int minLevel, const int maxLevel) const +{ + vector vIndices; + vIndices.reserve(N); + + const int nMinCellX = max(0,(int)floor((x-mnMinX-r)*mfGridElementWidthInv)); + if(nMinCellX>=FRAME_GRID_COLS) + return vIndices; + + const int nMaxCellX = min((int)FRAME_GRID_COLS-1,(int)ceil((x-mnMinX+r)*mfGridElementWidthInv)); + if(nMaxCellX<0) + return vIndices; + + const int nMinCellY = max(0,(int)floor((y-mnMinY-r)*mfGridElementHeightInv)); + if(nMinCellY>=FRAME_GRID_ROWS) + return vIndices; + + const int nMaxCellY = min((int)FRAME_GRID_ROWS-1,(int)ceil((y-mnMinY+r)*mfGridElementHeightInv)); + if(nMaxCellY<0) + return vIndices; + + const bool bCheckLevels = (minLevel>0) || (maxLevel>=0); + + for(int ix = nMinCellX; ix<=nMaxCellX; ix++) + { + for(int iy = nMinCellY; iy<=nMaxCellY; iy++) + { + const vector vCell = mGrid[ix][iy]; + if(vCell.empty()) + continue; + + for(size_t j=0, jend=vCell.size(); j=0) + if(kpUn.octave>maxLevel) + continue; + } + + const float distx = kpUn.pt.x-x; + const float disty = kpUn.pt.y-y; + + if(fabs(distx)=FRAME_GRID_COLS || posY<0 || posY>=FRAME_GRID_ROWS) + return false; + + return true; +} + + +void Frame::ComputeBoW() +{ + if(mBowVec.empty()) + { + vector vCurrentDesc = Converter::toDescriptorVector(mDescriptors); + mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4); + } +} + +void Frame::UndistortKeyPoints() +{ + if(mDistCoef.at(0)==0.0) + { + mvKeysUn=mvKeys; + return; + } + + // Fill matrix with points + cv::Mat mat(N,2,CV_32F); + for(int i=0; i(i,0)=mvKeys[i].pt.x; + mat.at(i,1)=mvKeys[i].pt.y; + } + + // Undistort points + mat=mat.reshape(2); + cv::undistortPoints(mat,mat,mK,mDistCoef,cv::Mat(),mK); + mat=mat.reshape(1); + + // Fill undistorted keypoint vector + mvKeysUn.resize(N); + for(int i=0; i(i,0); + kp.pt.y=mat.at(i,1); + mvKeysUn[i]=kp; + } +} + +void Frame::ComputeImageBounds(const cv::Mat &imLeft) +{ + if(mDistCoef.at(0)!=0.0) + { + cv::Mat mat(4,2,CV_32F); + mat.at(0,0)=0.0; mat.at(0,1)=0.0; + mat.at(1,0)=imLeft.cols; mat.at(1,1)=0.0; + mat.at(2,0)=0.0; mat.at(2,1)=imLeft.rows; + mat.at(3,0)=imLeft.cols; mat.at(3,1)=imLeft.rows; + + // Undistort corners + mat=mat.reshape(2); + cv::undistortPoints(mat,mat,mK,mDistCoef,cv::Mat(),mK); + mat=mat.reshape(1); + + mnMinX = min(mat.at(0,0),mat.at(2,0)); + mnMaxX = max(mat.at(1,0),mat.at(3,0)); + mnMinY = min(mat.at(0,1),mat.at(1,1)); + mnMaxY = max(mat.at(2,1),mat.at(3,1)); + + } + else + { + mnMinX = 0.0f; + mnMaxX = imLeft.cols; + mnMinY = 0.0f; + mnMaxY = imLeft.rows; + } +} + +void Frame::ComputeStereoMatches() +{ + mvuRight = vector(N,-1.0f); + mvDepth = vector(N,-1.0f); + + const int nRows = mpORBextractorLeft->mvImagePyramid[0].rows; + + //Assign keypoints to row table + vector > vRowIndices(nRows,vector()); + + for(int i=0; i > vDistIdx; + vDistIdx.reserve(N); + + for(int iL=0; iL &vCandidates = vRowIndices[vL]; + + if(vCandidates.empty()) + continue; + + const float minU = uL-maxD; + const float maxU = uL-minD; + + if(maxU<0) + continue; + + int bestDist = ORBmatcher::TH_HIGH; + size_t bestIdxR = 0; + + const cv::Mat &dL = mDescriptors.row(iL); + + // Compare descriptor to right keypoints + for(size_t iC=0; iClevelL+1) + continue; + + const float &uR = kpR.pt.x; + + if(uR>=minU && uR<=maxU) + { + const cv::Mat &dR = mDescriptorsRight.row(iR); + const int dist = ORBmatcher::DescriptorDistance(dL,dR); + + if(distmvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduL-w,scaleduL+w+1); + IL.convertTo(IL,CV_32F); + IL = IL - IL.at(w,w) *cv::Mat::ones(IL.rows,IL.cols,CV_32F); + + int bestDist = INT_MAX; + int bestincR = 0; + const int L = 5; + vector vDists; + vDists.resize(2*L+1); + + const float iniu = scaleduR0+L-w; + const float endu = scaleduR0+L+w+1; + if(iniu<0 || endu >= mpORBextractorRight->mvImagePyramid[kpL.octave].cols) + continue; + + for(int incR=-L; incR<=+L; incR++) + { + cv::Mat IR = mpORBextractorRight->mvImagePyramid[kpL.octave].rowRange(scaledvL-w,scaledvL+w+1).colRange(scaleduR0+incR-w,scaleduR0+incR+w+1); + IR.convertTo(IR,CV_32F); + IR = IR - IR.at(w,w) *cv::Mat::ones(IR.rows,IR.cols,CV_32F); + + float dist = cv::norm(IL,IR,cv::NORM_L1); + if(dist1) + continue; + + // Re-scaled coordinate + float bestuR = mvScaleFactors[kpL.octave]*((float)scaleduR0+(float)bestincR+deltaR); + + float disparity = (uL-bestuR); + + if(disparity>=0 && disparity(bestDist,iL)); + } + } + } + + sort(vDistIdx.begin(),vDistIdx.end()); + const float median = vDistIdx[vDistIdx.size()/2].first; + const float thDist = 1.5f*1.4f*median; + + for(int i=vDistIdx.size()-1;i>=0;i--) + { + if(vDistIdx[i].first(N,-1); + mvDepth = vector(N,-1); + + for(int i=0; i(v,u); + + if(d>0) + { + mvDepth[i] = d; + mvuRight[i] = kpU.pt.x-mbf/d; + } + } +} + +cv::Mat Frame::UnprojectStereo(const int &i) +{ + const float z = mvDepth[i]; + if(z>0) + { + const float u = mvKeysUn[i].pt.x; + const float v = mvKeysUn[i].pt.y; + const float x = (u-cx)*z*invfx; + const float y = (v-cy)*z*invfy; + cv::Mat x3Dc = (cv::Mat_(3,1) << x, y, z); + return mRwc*x3Dc+mOw; + } + else + return cv::Mat(); +} + +} //namespace ORB_SLAM diff --git a/src/FrameDrawer.cc b/src/FrameDrawer.cc new file mode 100644 index 0000000000..a325c31c2a --- /dev/null +++ b/src/FrameDrawer.cc @@ -0,0 +1,202 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "FrameDrawer.h" +#include "Tracking.h" + +#include +#include + +#include + +namespace ORB_SLAM2 +{ + +FrameDrawer::FrameDrawer(Map* pMap):mpMap(pMap) +{ + mState=Tracking::SYSTEM_NOT_READY; + mIm = cv::Mat(480,640,CV_8UC3, cv::Scalar(0,0,0)); +} + +cv::Mat FrameDrawer::DrawFrame() +{ + cv::Mat im; + vector vIniKeys; // Initialization: KeyPoints in reference frame + vector vMatches; // Initialization: correspondeces with reference keypoints + vector vCurrentKeys; // KeyPoints in current frame + vector vbVO, vbMap; // Tracked MapPoints in current frame + int state; // Tracking state + + //Copy variables within scoped mutex + { + unique_lock lock(mMutex); + state=mState; + if(mState==Tracking::SYSTEM_NOT_READY) + mState=Tracking::NO_IMAGES_YET; + + mIm.copyTo(im); + + if(mState==Tracking::NOT_INITIALIZED) + { + vCurrentKeys = mvCurrentKeys; + vIniKeys = mvIniKeys; + vMatches = mvIniMatches; + } + else if(mState==Tracking::OK) + { + vCurrentKeys = mvCurrentKeys; + vbVO = mvbVO; + vbMap = mvbMap; + } + else if(mState==Tracking::LOST) + { + vCurrentKeys = mvCurrentKeys; + } + } // destroy scoped mutex -> release mutex + + if(im.channels()<3) //this should be always true + cvtColor(im,im,CV_GRAY2BGR); + + //Draw + if(state==Tracking::NOT_INITIALIZED) //INITIALIZING + { + for(unsigned int i=0; i=0) + { + cv::line(im,vIniKeys[i].pt,vCurrentKeys[vMatches[i]].pt, + cv::Scalar(0,255,0)); + } + } + } + else if(state==Tracking::OK) //TRACKING + { + mnTracked=0; + mnTrackedVO=0; + const float r = 5; + for(int i=0;iKeyFramesInMap(); + int nMPs = mpMap->MapPointsInMap(); + s << "KFs: " << nKFs << ", MPs: " << nMPs << ", Matches: " << mnTracked; + if(mnTrackedVO>0) + s << ", + VO matches: " << mnTrackedVO; + } + else if(nState==Tracking::LOST) + { + s << " TRACK LOST. TRYING TO RELOCALIZE "; + } + else if(nState==Tracking::SYSTEM_NOT_READY) + { + s << " LOADING ORB VOCABULARY. PLEASE WAIT..."; + } + + int baseline=0; + cv::Size textSize = cv::getTextSize(s.str(),cv::FONT_HERSHEY_PLAIN,1,1,&baseline); + + imText = cv::Mat(im.rows+textSize.height+10,im.cols,im.type()); + im.copyTo(imText.rowRange(0,im.rows).colRange(0,im.cols)); + imText.rowRange(im.rows,imText.rows) = cv::Mat::zeros(textSize.height+10,im.cols,im.type()); + cv::putText(imText,s.str(),cv::Point(5,imText.rows-5),cv::FONT_HERSHEY_PLAIN,1,cv::Scalar(255,255,255),1,8); + +} + +void FrameDrawer::Update(Tracking *pTracker) +{ + unique_lock lock(mMutex); + pTracker->mImGray.copyTo(mIm); + mvCurrentKeys=pTracker->mCurrentFrame.mvKeys; + N = mvCurrentKeys.size(); + mvbVO = vector(N,false); + mvbMap = vector(N,false); + mbOnlyTracking = pTracker->mbOnlyTracking; + + + if(pTracker->mLastProcessedState==Tracking::NOT_INITIALIZED) + { + mvIniKeys=pTracker->mInitialFrame.mvKeys; + mvIniMatches=pTracker->mvIniMatches; + } + else if(pTracker->mLastProcessedState==Tracking::OK) + { + for(int i=0;imCurrentFrame.mvpMapPoints[i]; + if(pMP) + { + if(!pTracker->mCurrentFrame.mvbOutlier[i]) + { + if(pMP->Observations()>0) + mvbMap[i]=true; + else + mvbVO[i]=true; + } + } + } + } + mState=static_cast(pTracker->mLastProcessedState); +} + +} //namespace ORB_SLAM diff --git a/src/Initializer.cc b/src/Initializer.cc new file mode 100644 index 0000000000..6094b8f51b --- /dev/null +++ b/src/Initializer.cc @@ -0,0 +1,931 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "Initializer.h" + +#include "Thirdparty/DBoW2/DUtils/Random.h" + +#include "Optimizer.h" +#include "ORBmatcher.h" + +#include + +namespace ORB_SLAM2 +{ + +Initializer::Initializer(const Frame &ReferenceFrame, float sigma, int iterations) +{ + mK = ReferenceFrame.mK.clone(); + + mvKeys1 = ReferenceFrame.mvKeysUn; + + mSigma = sigma; + mSigma2 = sigma*sigma; + mMaxIterations = iterations; +} + +bool Initializer::Initialize(const Frame &CurrentFrame, const vector &vMatches12, cv::Mat &R21, cv::Mat &t21, + vector &vP3D, vector &vbTriangulated) +{ + // Fill structures with current keypoints and matches with reference frame + // Reference Frame: 1, Current Frame: 2 + mvKeys2 = CurrentFrame.mvKeysUn; + + mvMatches12.clear(); + mvMatches12.reserve(mvKeys2.size()); + mvbMatched1.resize(mvKeys1.size()); + for(size_t i=0, iend=vMatches12.size();i=0) + { + mvMatches12.push_back(make_pair(i,vMatches12[i])); + mvbMatched1[i]=true; + } + else + mvbMatched1[i]=false; + } + + const int N = mvMatches12.size(); + + // Indices for minimum set selection + vector vAllIndices; + vAllIndices.reserve(N); + vector vAvailableIndices; + + for(int i=0; i >(mMaxIterations,vector(8,0)); + + DUtils::Random::SeedRandOnce(0); + + for(int it=0; it vbMatchesInliersH, vbMatchesInliersF; + float SH, SF; + cv::Mat H, F; + + thread threadH(&Initializer::FindHomography,this,ref(vbMatchesInliersH), ref(SH), ref(H)); + thread threadF(&Initializer::FindFundamental,this,ref(vbMatchesInliersF), ref(SF), ref(F)); + + // Wait until both threads have finished + threadH.join(); + threadF.join(); + + // Compute ratio of scores + float RH = SH/(SH+SF); + + // Try to reconstruct from homography or fundamental depending on the ratio (0.40-0.45) + if(RH>0.40) + return ReconstructH(vbMatchesInliersH,H,mK,R21,t21,vP3D,vbTriangulated,1.0,50); + else //if(pF_HF>0.6) + return ReconstructF(vbMatchesInliersF,F,mK,R21,t21,vP3D,vbTriangulated,1.0,50); + + return false; +} + + +void Initializer::FindHomography(vector &vbMatchesInliers, float &score, cv::Mat &H21) +{ + // Number of putative matches + const int N = mvMatches12.size(); + + // Normalize coordinates + vector vPn1, vPn2; + cv::Mat T1, T2; + Normalize(mvKeys1,vPn1, T1); + Normalize(mvKeys2,vPn2, T2); + cv::Mat T2inv = T2.inv(); + + // Best Results variables + score = 0.0; + vbMatchesInliers = vector(N,false); + + // Iteration variables + vector vPn1i(8); + vector vPn2i(8); + cv::Mat H21i, H12i; + vector vbCurrentInliers(N,false); + float currentScore; + + // Perform all RANSAC iterations and save the solution with highest score + for(int it=0; itscore) + { + H21 = H21i.clone(); + vbMatchesInliers = vbCurrentInliers; + score = currentScore; + } + } +} + + +void Initializer::FindFundamental(vector &vbMatchesInliers, float &score, cv::Mat &F21) +{ + // Number of putative matches + const int N = vbMatchesInliers.size(); + + // Normalize coordinates + vector vPn1, vPn2; + cv::Mat T1, T2; + Normalize(mvKeys1,vPn1, T1); + Normalize(mvKeys2,vPn2, T2); + cv::Mat T2t = T2.t(); + + // Best Results variables + score = 0.0; + vbMatchesInliers = vector(N,false); + + // Iteration variables + vector vPn1i(8); + vector vPn2i(8); + cv::Mat F21i; + vector vbCurrentInliers(N,false); + float currentScore; + + // Perform all RANSAC iterations and save the solution with highest score + for(int it=0; itscore) + { + F21 = F21i.clone(); + vbMatchesInliers = vbCurrentInliers; + score = currentScore; + } + } +} + + +cv::Mat Initializer::ComputeH21(const vector &vP1, const vector &vP2) +{ + const int N = vP1.size(); + + cv::Mat A(2*N,9,CV_32F); + + for(int i=0; i(2*i,0) = 0.0; + A.at(2*i,1) = 0.0; + A.at(2*i,2) = 0.0; + A.at(2*i,3) = -u1; + A.at(2*i,4) = -v1; + A.at(2*i,5) = -1; + A.at(2*i,6) = v2*u1; + A.at(2*i,7) = v2*v1; + A.at(2*i,8) = v2; + + A.at(2*i+1,0) = u1; + A.at(2*i+1,1) = v1; + A.at(2*i+1,2) = 1; + A.at(2*i+1,3) = 0.0; + A.at(2*i+1,4) = 0.0; + A.at(2*i+1,5) = 0.0; + A.at(2*i+1,6) = -u2*u1; + A.at(2*i+1,7) = -u2*v1; + A.at(2*i+1,8) = -u2; + + } + + cv::Mat u,w,vt; + + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + return vt.row(8).reshape(0, 3); +} + +cv::Mat Initializer::ComputeF21(const vector &vP1,const vector &vP2) +{ + const int N = vP1.size(); + + cv::Mat A(N,9,CV_32F); + + for(int i=0; i(i,0) = u2*u1; + A.at(i,1) = u2*v1; + A.at(i,2) = u2; + A.at(i,3) = v2*u1; + A.at(i,4) = v2*v1; + A.at(i,5) = v2; + A.at(i,6) = u1; + A.at(i,7) = v1; + A.at(i,8) = 1; + } + + cv::Mat u,w,vt; + + cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + cv::Mat Fpre = vt.row(8).reshape(0, 3); + + cv::SVDecomp(Fpre,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); + + w.at(2)=0; + + return u*cv::Mat::diag(w)*vt; +} + +float Initializer::CheckHomography(const cv::Mat &H21, const cv::Mat &H12, vector &vbMatchesInliers, float sigma) +{ + const int N = mvMatches12.size(); + + const float h11 = H21.at(0,0); + const float h12 = H21.at(0,1); + const float h13 = H21.at(0,2); + const float h21 = H21.at(1,0); + const float h22 = H21.at(1,1); + const float h23 = H21.at(1,2); + const float h31 = H21.at(2,0); + const float h32 = H21.at(2,1); + const float h33 = H21.at(2,2); + + const float h11inv = H12.at(0,0); + const float h12inv = H12.at(0,1); + const float h13inv = H12.at(0,2); + const float h21inv = H12.at(1,0); + const float h22inv = H12.at(1,1); + const float h23inv = H12.at(1,2); + const float h31inv = H12.at(2,0); + const float h32inv = H12.at(2,1); + const float h33inv = H12.at(2,2); + + vbMatchesInliers.resize(N); + + float score = 0; + + const float th = 5.991; + + const float invSigmaSquare = 1.0/(sigma*sigma); + + for(int i=0; ith) + bIn = false; + else + score += th - chiSquare1; + + // Reprojection error in second image + // x1in2 = H21*x1 + + const float w1in2inv = 1.0/(h31*u1+h32*v1+h33); + const float u1in2 = (h11*u1+h12*v1+h13)*w1in2inv; + const float v1in2 = (h21*u1+h22*v1+h23)*w1in2inv; + + const float squareDist2 = (u2-u1in2)*(u2-u1in2)+(v2-v1in2)*(v2-v1in2); + + const float chiSquare2 = squareDist2*invSigmaSquare; + + if(chiSquare2>th) + bIn = false; + else + score += th - chiSquare2; + + if(bIn) + vbMatchesInliers[i]=true; + else + vbMatchesInliers[i]=false; + } + + return score; +} + +float Initializer::CheckFundamental(const cv::Mat &F21, vector &vbMatchesInliers, float sigma) +{ + const int N = mvMatches12.size(); + + const float f11 = F21.at(0,0); + const float f12 = F21.at(0,1); + const float f13 = F21.at(0,2); + const float f21 = F21.at(1,0); + const float f22 = F21.at(1,1); + const float f23 = F21.at(1,2); + const float f31 = F21.at(2,0); + const float f32 = F21.at(2,1); + const float f33 = F21.at(2,2); + + vbMatchesInliers.resize(N); + + float score = 0; + + const float th = 3.841; + const float thScore = 5.991; + + const float invSigmaSquare = 1.0/(sigma*sigma); + + for(int i=0; ith) + bIn = false; + else + score += thScore - chiSquare1; + + // Reprojection error in second image + // l1 =x2tF21=(a1,b1,c1) + + const float a1 = f11*u2+f21*v2+f31; + const float b1 = f12*u2+f22*v2+f32; + const float c1 = f13*u2+f23*v2+f33; + + const float num1 = a1*u1+b1*v1+c1; + + const float squareDist2 = num1*num1/(a1*a1+b1*b1); + + const float chiSquare2 = squareDist2*invSigmaSquare; + + if(chiSquare2>th) + bIn = false; + else + score += thScore - chiSquare2; + + if(bIn) + vbMatchesInliers[i]=true; + else + vbMatchesInliers[i]=false; + } + + return score; +} + +bool Initializer::ReconstructF(vector &vbMatchesInliers, cv::Mat &F21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated) +{ + int N=0; + for(size_t i=0, iend = vbMatchesInliers.size() ; i vP3D1, vP3D2, vP3D3, vP3D4; + vector vbTriangulated1,vbTriangulated2,vbTriangulated3, vbTriangulated4; + float parallax1,parallax2, parallax3, parallax4; + + int nGood1 = CheckRT(R1,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D1, 4.0*mSigma2, vbTriangulated1, parallax1); + int nGood2 = CheckRT(R2,t1,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D2, 4.0*mSigma2, vbTriangulated2, parallax2); + int nGood3 = CheckRT(R1,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D3, 4.0*mSigma2, vbTriangulated3, parallax3); + int nGood4 = CheckRT(R2,t2,mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K, vP3D4, 4.0*mSigma2, vbTriangulated4, parallax4); + + int maxGood = max(nGood1,max(nGood2,max(nGood3,nGood4))); + + R21 = cv::Mat(); + t21 = cv::Mat(); + + int nMinGood = max(static_cast(0.9*N),minTriangulated); + + int nsimilar = 0; + if(nGood1>0.7*maxGood) + nsimilar++; + if(nGood2>0.7*maxGood) + nsimilar++; + if(nGood3>0.7*maxGood) + nsimilar++; + if(nGood4>0.7*maxGood) + nsimilar++; + + // If there is not a clear winner or not enough triangulated points reject initialization + if(maxGood1) + { + return false; + } + + // If best reconstruction has enough parallax initialize + if(maxGood==nGood1) + { + if(parallax1>minParallax) + { + vP3D = vP3D1; + vbTriangulated = vbTriangulated1; + + R1.copyTo(R21); + t1.copyTo(t21); + return true; + } + }else if(maxGood==nGood2) + { + if(parallax2>minParallax) + { + vP3D = vP3D2; + vbTriangulated = vbTriangulated2; + + R2.copyTo(R21); + t1.copyTo(t21); + return true; + } + }else if(maxGood==nGood3) + { + if(parallax3>minParallax) + { + vP3D = vP3D3; + vbTriangulated = vbTriangulated3; + + R1.copyTo(R21); + t2.copyTo(t21); + return true; + } + }else if(maxGood==nGood4) + { + if(parallax4>minParallax) + { + vP3D = vP3D4; + vbTriangulated = vbTriangulated4; + + R2.copyTo(R21); + t2.copyTo(t21); + return true; + } + } + + return false; +} + +bool Initializer::ReconstructH(vector &vbMatchesInliers, cv::Mat &H21, cv::Mat &K, + cv::Mat &R21, cv::Mat &t21, vector &vP3D, vector &vbTriangulated, float minParallax, int minTriangulated) +{ + int N=0; + for(size_t i=0, iend = vbMatchesInliers.size() ; i(0); + float d2 = w.at(1); + float d3 = w.at(2); + + if(d1/d2<1.00001 || d2/d3<1.00001) + { + return false; + } + + vector vR, vt, vn; + vR.reserve(8); + vt.reserve(8); + vn.reserve(8); + + //n'=[x1 0 x3] 4 posibilities e1=e3=1, e1=1 e3=-1, e1=-1 e3=1, e1=e3=-1 + float aux1 = sqrt((d1*d1-d2*d2)/(d1*d1-d3*d3)); + float aux3 = sqrt((d2*d2-d3*d3)/(d1*d1-d3*d3)); + float x1[] = {aux1,aux1,-aux1,-aux1}; + float x3[] = {aux3,-aux3,aux3,-aux3}; + + //case d'=d2 + float aux_stheta = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1+d3)*d2); + + float ctheta = (d2*d2+d1*d3)/((d1+d3)*d2); + float stheta[] = {aux_stheta, -aux_stheta, -aux_stheta, aux_stheta}; + + for(int i=0; i<4; i++) + { + cv::Mat Rp=cv::Mat::eye(3,3,CV_32F); + Rp.at(0,0)=ctheta; + Rp.at(0,2)=-stheta[i]; + Rp.at(2,0)=stheta[i]; + Rp.at(2,2)=ctheta; + + cv::Mat R = s*U*Rp*Vt; + vR.push_back(R); + + cv::Mat tp(3,1,CV_32F); + tp.at(0)=x1[i]; + tp.at(1)=0; + tp.at(2)=-x3[i]; + tp*=d1-d3; + + cv::Mat t = U*tp; + vt.push_back(t/cv::norm(t)); + + cv::Mat np(3,1,CV_32F); + np.at(0)=x1[i]; + np.at(1)=0; + np.at(2)=x3[i]; + + cv::Mat n = V*np; + if(n.at(2)<0) + n=-n; + vn.push_back(n); + } + + //case d'=-d2 + float aux_sphi = sqrt((d1*d1-d2*d2)*(d2*d2-d3*d3))/((d1-d3)*d2); + + float cphi = (d1*d3-d2*d2)/((d1-d3)*d2); + float sphi[] = {aux_sphi, -aux_sphi, -aux_sphi, aux_sphi}; + + for(int i=0; i<4; i++) + { + cv::Mat Rp=cv::Mat::eye(3,3,CV_32F); + Rp.at(0,0)=cphi; + Rp.at(0,2)=sphi[i]; + Rp.at(1,1)=-1; + Rp.at(2,0)=sphi[i]; + Rp.at(2,2)=-cphi; + + cv::Mat R = s*U*Rp*Vt; + vR.push_back(R); + + cv::Mat tp(3,1,CV_32F); + tp.at(0)=x1[i]; + tp.at(1)=0; + tp.at(2)=x3[i]; + tp*=d1+d3; + + cv::Mat t = U*tp; + vt.push_back(t/cv::norm(t)); + + cv::Mat np(3,1,CV_32F); + np.at(0)=x1[i]; + np.at(1)=0; + np.at(2)=x3[i]; + + cv::Mat n = V*np; + if(n.at(2)<0) + n=-n; + vn.push_back(n); + } + + + int bestGood = 0; + int secondBestGood = 0; + int bestSolutionIdx = -1; + float bestParallax = -1; + vector bestP3D; + vector bestTriangulated; + + // Instead of applying the visibility constraints proposed in the Faugeras' paper (which could fail for points seen with low parallax) + // We reconstruct all hypotheses and check in terms of triangulated points and parallax + for(size_t i=0; i<8; i++) + { + float parallaxi; + vector vP3Di; + vector vbTriangulatedi; + int nGood = CheckRT(vR[i],vt[i],mvKeys1,mvKeys2,mvMatches12,vbMatchesInliers,K,vP3Di, 4.0*mSigma2, vbTriangulatedi, parallaxi); + + if(nGood>bestGood) + { + secondBestGood = bestGood; + bestGood = nGood; + bestSolutionIdx = i; + bestParallax = parallaxi; + bestP3D = vP3Di; + bestTriangulated = vbTriangulatedi; + } + else if(nGood>secondBestGood) + { + secondBestGood = nGood; + } + } + + + if(secondBestGood<0.75*bestGood && bestParallax>=minParallax && bestGood>minTriangulated && bestGood>0.9*N) + { + vR[bestSolutionIdx].copyTo(R21); + vt[bestSolutionIdx].copyTo(t21); + vP3D = bestP3D; + vbTriangulated = bestTriangulated; + + return true; + } + + return false; +} + +void Initializer::Triangulate(const cv::KeyPoint &kp1, const cv::KeyPoint &kp2, const cv::Mat &P1, const cv::Mat &P2, cv::Mat &x3D) +{ + cv::Mat A(4,4,CV_32F); + + A.row(0) = kp1.pt.x*P1.row(2)-P1.row(0); + A.row(1) = kp1.pt.y*P1.row(2)-P1.row(1); + A.row(2) = kp2.pt.x*P2.row(2)-P2.row(0); + A.row(3) = kp2.pt.y*P2.row(2)-P2.row(1); + + cv::Mat u,w,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + x3D = vt.row(3).t(); + x3D = x3D.rowRange(0,3)/x3D.at(3); +} + +void Initializer::Normalize(const vector &vKeys, vector &vNormalizedPoints, cv::Mat &T) +{ + float meanX = 0; + float meanY = 0; + const int N = vKeys.size(); + + vNormalizedPoints.resize(N); + + for(int i=0; i(0,0) = sX; + T.at(1,1) = sY; + T.at(0,2) = -meanX*sX; + T.at(1,2) = -meanY*sY; +} + + +int Initializer::CheckRT(const cv::Mat &R, const cv::Mat &t, const vector &vKeys1, const vector &vKeys2, + const vector &vMatches12, vector &vbMatchesInliers, + const cv::Mat &K, vector &vP3D, float th2, vector &vbGood, float ¶llax) +{ + // Calibration parameters + const float fx = K.at(0,0); + const float fy = K.at(1,1); + const float cx = K.at(0,2); + const float cy = K.at(1,2); + + vbGood = vector(vKeys1.size(),false); + vP3D.resize(vKeys1.size()); + + vector vCosParallax; + vCosParallax.reserve(vKeys1.size()); + + // Camera 1 Projection Matrix K[I|0] + cv::Mat P1(3,4,CV_32F,cv::Scalar(0)); + K.copyTo(P1.rowRange(0,3).colRange(0,3)); + + cv::Mat O1 = cv::Mat::zeros(3,1,CV_32F); + + // Camera 2 Projection Matrix K[R|t] + cv::Mat P2(3,4,CV_32F); + R.copyTo(P2.rowRange(0,3).colRange(0,3)); + t.copyTo(P2.rowRange(0,3).col(3)); + P2 = K*P2; + + cv::Mat O2 = -R.t()*t; + + int nGood=0; + + for(size_t i=0, iend=vMatches12.size();i(0)) || !isfinite(p3dC1.at(1)) || !isfinite(p3dC1.at(2))) + { + vbGood[vMatches12[i].first]=false; + continue; + } + + // Check parallax + cv::Mat normal1 = p3dC1 - O1; + float dist1 = cv::norm(normal1); + + cv::Mat normal2 = p3dC1 - O2; + float dist2 = cv::norm(normal2); + + float cosParallax = normal1.dot(normal2)/(dist1*dist2); + + // Check depth in front of first camera (only if enough parallax, as "infinite" points can easily go to negative depth) + if(p3dC1.at(2)<=0 && cosParallax<0.99998) + continue; + + // Check depth in front of second camera (only if enough parallax, as "infinite" points can easily go to negative depth) + cv::Mat p3dC2 = R*p3dC1+t; + + if(p3dC2.at(2)<=0 && cosParallax<0.99998) + continue; + + // Check reprojection error in first image + float im1x, im1y; + float invZ1 = 1.0/p3dC1.at(2); + im1x = fx*p3dC1.at(0)*invZ1+cx; + im1y = fy*p3dC1.at(1)*invZ1+cy; + + float squareError1 = (im1x-kp1.pt.x)*(im1x-kp1.pt.x)+(im1y-kp1.pt.y)*(im1y-kp1.pt.y); + + if(squareError1>th2) + continue; + + // Check reprojection error in second image + float im2x, im2y; + float invZ2 = 1.0/p3dC2.at(2); + im2x = fx*p3dC2.at(0)*invZ2+cx; + im2y = fy*p3dC2.at(1)*invZ2+cy; + + float squareError2 = (im2x-kp2.pt.x)*(im2x-kp2.pt.x)+(im2y-kp2.pt.y)*(im2y-kp2.pt.y); + + if(squareError2>th2) + continue; + + vCosParallax.push_back(cosParallax); + vP3D[vMatches12[i].first] = cv::Point3f(p3dC1.at(0),p3dC1.at(1),p3dC1.at(2)); + nGood++; + + if(cosParallax<0.99998) + vbGood[vMatches12[i].first]=true; + } + + if(nGood>0) + { + sort(vCosParallax.begin(),vCosParallax.end()); + + size_t idx = min(50,int(vCosParallax.size()-1)); + parallax = acos(vCosParallax[idx])*180/CV_PI; + } + else + parallax=0; + + return nGood; +} + +void Initializer::DecomposeE(const cv::Mat &E, cv::Mat &R1, cv::Mat &R2, cv::Mat &t) +{ + cv::Mat u,w,vt; + cv::SVD::compute(E,w,u,vt); + + u.col(2).copyTo(t); + t=t/cv::norm(t); + + cv::Mat W(3,3,CV_32F,cv::Scalar(0)); + W.at(0,1)=-1; + W.at(1,0)=1; + W.at(2,2)=1; + + R1 = u*W*vt; + if(cv::determinant(R1)<0) + R1=-R1; + + R2 = u*W.t()*vt; + if(cv::determinant(R2)<0) + R2=-R2; +} + +} //namespace ORB_SLAM diff --git a/src/KeyFrame.cc b/src/KeyFrame.cc new file mode 100644 index 0000000000..4ef1e78e0f --- /dev/null +++ b/src/KeyFrame.cc @@ -0,0 +1,665 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "KeyFrame.h" +#include "Converter.h" +#include "ORBmatcher.h" +#include + +namespace ORB_SLAM2 +{ + +long unsigned int KeyFrame::nNextId=0; + +KeyFrame::KeyFrame(Frame &F, Map *pMap, KeyFrameDatabase *pKFDB): + mnFrameId(F.mnId), mTimeStamp(F.mTimeStamp), mnGridCols(FRAME_GRID_COLS), mnGridRows(FRAME_GRID_ROWS), + mfGridElementWidthInv(F.mfGridElementWidthInv), mfGridElementHeightInv(F.mfGridElementHeightInv), + mnTrackReferenceForFrame(0), mnFuseTargetForKF(0), mnBALocalForKF(0), mnBAFixedForKF(0), + mnLoopQuery(0), mnLoopWords(0), mnRelocQuery(0), mnRelocWords(0), mnBAGlobalForKF(0), + fx(F.fx), fy(F.fy), cx(F.cx), cy(F.cy), invfx(F.invfx), invfy(F.invfy), + mbf(F.mbf), mb(F.mb), mThDepth(F.mThDepth), N(F.N), mvKeys(F.mvKeys), mvKeysUn(F.mvKeysUn), + mvuRight(F.mvuRight), mvDepth(F.mvDepth), mDescriptors(F.mDescriptors.clone()), + mBowVec(F.mBowVec), mFeatVec(F.mFeatVec), mnScaleLevels(F.mnScaleLevels), mfScaleFactor(F.mfScaleFactor), + mfLogScaleFactor(F.mfLogScaleFactor), mvScaleFactors(F.mvScaleFactors), mvLevelSigma2(F.mvLevelSigma2), + mvInvLevelSigma2(F.mvInvLevelSigma2), mnMinX(F.mnMinX), mnMinY(F.mnMinY), mnMaxX(F.mnMaxX), + mnMaxY(F.mnMaxY), mK(F.mK), mvpMapPoints(F.mvpMapPoints), mpKeyFrameDB(pKFDB), + mpORBvocabulary(F.mpORBvocabulary), mbFirstConnection(true), mpParent(NULL), mbNotErase(false), + mbToBeErased(false), mbBad(false), mHalfBaseline(F.mb/2), mpMap(pMap) +{ + mnId=nNextId++; + + mGrid.resize(mnGridCols); + for(int i=0; i vCurrentDesc = Converter::toDescriptorVector(mDescriptors); + // Feature vector associate features with nodes in the 4th level (from leaves up) + // We assume the vocabulary tree has 6 levels, change the 4 otherwise + mpORBvocabulary->transform(vCurrentDesc,mBowVec,mFeatVec,4); + } +} + +void KeyFrame::SetPose(const cv::Mat &Tcw_) +{ + unique_lock lock(mMutexPose); + Tcw_.copyTo(Tcw); + cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3); + cv::Mat tcw = Tcw.rowRange(0,3).col(3); + cv::Mat Rwc = Rcw.t(); + Ow = -Rwc*tcw; + + Twc = cv::Mat::eye(4,4,Tcw.type()); + Rwc.copyTo(Twc.rowRange(0,3).colRange(0,3)); + Ow.copyTo(Twc.rowRange(0,3).col(3)); + cv::Mat center = (cv::Mat_(4,1) << mHalfBaseline, 0 , 0, 1); + Cw = Twc*center; +} + +cv::Mat KeyFrame::GetPose() +{ + unique_lock lock(mMutexPose); + return Tcw.clone(); +} + +cv::Mat KeyFrame::GetPoseInverse() +{ + unique_lock lock(mMutexPose); + return Twc.clone(); +} + +cv::Mat KeyFrame::GetCameraCenter() +{ + unique_lock lock(mMutexPose); + return Ow.clone(); +} + +cv::Mat KeyFrame::GetStereoCenter() +{ + unique_lock lock(mMutexPose); + return Cw.clone(); +} + + +cv::Mat KeyFrame::GetRotation() +{ + unique_lock lock(mMutexPose); + return Tcw.rowRange(0,3).colRange(0,3).clone(); +} + +cv::Mat KeyFrame::GetTranslation() +{ + unique_lock lock(mMutexPose); + return Tcw.rowRange(0,3).col(3).clone(); +} + +void KeyFrame::AddConnection(KeyFrame *pKF, const int &weight) +{ + { + unique_lock lock(mMutexConnections); + if(!mConnectedKeyFrameWeights.count(pKF)) + mConnectedKeyFrameWeights[pKF]=weight; + else if(mConnectedKeyFrameWeights[pKF]!=weight) + mConnectedKeyFrameWeights[pKF]=weight; + else + return; + } + + UpdateBestCovisibles(); +} + +void KeyFrame::UpdateBestCovisibles() +{ + unique_lock lock(mMutexConnections); + vector > vPairs; + vPairs.reserve(mConnectedKeyFrameWeights.size()); + for(map::iterator mit=mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++) + vPairs.push_back(make_pair(mit->second,mit->first)); + + sort(vPairs.begin(),vPairs.end()); + list lKFs; + list lWs; + for(size_t i=0, iend=vPairs.size(); i(lKFs.begin(),lKFs.end()); + mvOrderedWeights = vector(lWs.begin(), lWs.end()); +} + +set KeyFrame::GetConnectedKeyFrames() +{ + unique_lock lock(mMutexConnections); + set s; + for(map::iterator mit=mConnectedKeyFrameWeights.begin();mit!=mConnectedKeyFrameWeights.end();mit++) + s.insert(mit->first); + return s; +} + +vector KeyFrame::GetVectorCovisibleKeyFrames() +{ + unique_lock lock(mMutexConnections); + return mvpOrderedConnectedKeyFrames; +} + +vector KeyFrame::GetBestCovisibilityKeyFrames(const int &N) +{ + unique_lock lock(mMutexConnections); + if((int)mvpOrderedConnectedKeyFrames.size()(mvpOrderedConnectedKeyFrames.begin(),mvpOrderedConnectedKeyFrames.begin()+N); + +} + +vector KeyFrame::GetCovisiblesByWeight(const int &w) +{ + unique_lock lock(mMutexConnections); + + if(mvpOrderedConnectedKeyFrames.empty()) + return vector(); + + vector::iterator it = upper_bound(mvOrderedWeights.begin(),mvOrderedWeights.end(),w,KeyFrame::weightComp); + if(it==mvOrderedWeights.end()) + return vector(); + else + { + int n = it-mvOrderedWeights.begin(); + return vector(mvpOrderedConnectedKeyFrames.begin(), mvpOrderedConnectedKeyFrames.begin()+n); + } +} + +int KeyFrame::GetWeight(KeyFrame *pKF) +{ + unique_lock lock(mMutexConnections); + if(mConnectedKeyFrameWeights.count(pKF)) + return mConnectedKeyFrameWeights[pKF]; + else + return 0; +} + +void KeyFrame::AddMapPoint(MapPoint *pMP, const size_t &idx) +{ + unique_lock lock(mMutexFeatures); + mvpMapPoints[idx]=pMP; +} + +void KeyFrame::EraseMapPointMatch(const size_t &idx) +{ + unique_lock lock(mMutexFeatures); + mvpMapPoints[idx]=static_cast(NULL); +} + +void KeyFrame::EraseMapPointMatch(MapPoint* pMP) +{ + int idx = pMP->GetIndexInKeyFrame(this); + if(idx>=0) + mvpMapPoints[idx]=static_cast(NULL); +} + + +void KeyFrame::ReplaceMapPointMatch(const size_t &idx, MapPoint* pMP) +{ + mvpMapPoints[idx]=pMP; +} + +set KeyFrame::GetMapPoints() +{ + unique_lock lock(mMutexFeatures); + set s; + for(size_t i=0, iend=mvpMapPoints.size(); iisBad()) + s.insert(pMP); + } + return s; +} + +int KeyFrame::TrackedMapPoints(const int &minObs) +{ + unique_lock lock(mMutexFeatures); + + int nPoints=0; + const bool bCheckObs = minObs>0; + for(int i=0; iisBad()) + { + if(bCheckObs) + { + if(mvpMapPoints[i]->Observations()>=minObs) + nPoints++; + } + else + nPoints++; + } + } + } + + return nPoints; +} + +vector KeyFrame::GetMapPointMatches() +{ + unique_lock lock(mMutexFeatures); + return mvpMapPoints; +} + +MapPoint* KeyFrame::GetMapPoint(const size_t &idx) +{ + unique_lock lock(mMutexFeatures); + return mvpMapPoints[idx]; +} + +void KeyFrame::UpdateConnections() +{ + map KFcounter; + + vector vpMP; + + { + unique_lock lockMPs(mMutexFeatures); + vpMP = mvpMapPoints; + } + + //For all map points in keyframe check in which other keyframes are they seen + //Increase counter for those keyframes + for(vector::iterator vit=vpMP.begin(), vend=vpMP.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + + if(!pMP) + continue; + + if(pMP->isBad()) + continue; + + map observations = pMP->GetObservations(); + + for(map::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + if(mit->first->mnId==mnId) + continue; + KFcounter[mit->first]++; + } + } + + // This should not happen + if(KFcounter.empty()) + return; + + //If the counter is greater than threshold add connection + //In case no keyframe counter is over threshold add the one with maximum counter + int nmax=0; + KeyFrame* pKFmax=NULL; + int th = 15; + + vector > vPairs; + vPairs.reserve(KFcounter.size()); + for(map::iterator mit=KFcounter.begin(), mend=KFcounter.end(); mit!=mend; mit++) + { + if(mit->second>nmax) + { + nmax=mit->second; + pKFmax=mit->first; + } + if(mit->second>=th) + { + vPairs.push_back(make_pair(mit->second,mit->first)); + (mit->first)->AddConnection(this,mit->second); + } + } + + if(vPairs.empty()) + { + vPairs.push_back(make_pair(nmax,pKFmax)); + pKFmax->AddConnection(this,nmax); + } + + sort(vPairs.begin(),vPairs.end()); + list lKFs; + list lWs; + for(size_t i=0; i lockCon(mMutexConnections); + + // mspConnectedKeyFrames = spConnectedKeyFrames; + mConnectedKeyFrameWeights = KFcounter; + mvpOrderedConnectedKeyFrames = vector(lKFs.begin(),lKFs.end()); + mvOrderedWeights = vector(lWs.begin(), lWs.end()); + + if(mbFirstConnection && mnId!=0) + { + mpParent = mvpOrderedConnectedKeyFrames.front(); + mpParent->AddChild(this); + mbFirstConnection = false; + } + + } +} + +void KeyFrame::AddChild(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mspChildrens.insert(pKF); +} + +void KeyFrame::EraseChild(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mspChildrens.erase(pKF); +} + +void KeyFrame::ChangeParent(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mpParent = pKF; + pKF->AddChild(this); +} + +set KeyFrame::GetChilds() +{ + unique_lock lockCon(mMutexConnections); + return mspChildrens; +} + +KeyFrame* KeyFrame::GetParent() +{ + unique_lock lockCon(mMutexConnections); + return mpParent; +} + +bool KeyFrame::hasChild(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + return mspChildrens.count(pKF); +} + +void KeyFrame::AddLoopEdge(KeyFrame *pKF) +{ + unique_lock lockCon(mMutexConnections); + mbNotErase = true; + mspLoopEdges.insert(pKF); +} + +set KeyFrame::GetLoopEdges() +{ + unique_lock lockCon(mMutexConnections); + return mspLoopEdges; +} + +void KeyFrame::SetNotErase() +{ + unique_lock lock(mMutexConnections); + mbNotErase = true; +} + +void KeyFrame::SetErase() +{ + { + unique_lock lock(mMutexConnections); + if(mspLoopEdges.empty()) + { + mbNotErase = false; + } + } + + if(mbToBeErased) + { + SetBadFlag(); + } +} + +void KeyFrame::SetBadFlag() +{ + { + unique_lock lock(mMutexConnections); + if(mnId==0) + return; + else if(mbNotErase) + { + mbToBeErased = true; + return; + } + } + + for(map::iterator mit = mConnectedKeyFrameWeights.begin(), mend=mConnectedKeyFrameWeights.end(); mit!=mend; mit++) + mit->first->EraseConnection(this); + + for(size_t i=0; iEraseObservation(this); + { + unique_lock lock(mMutexConnections); + unique_lock lock1(mMutexFeatures); + + mConnectedKeyFrameWeights.clear(); + mvpOrderedConnectedKeyFrames.clear(); + + // Update Spanning Tree + set sParentCandidates; + sParentCandidates.insert(mpParent); + + // Assign at each iteration one children with a parent (the pair with highest covisibility weight) + // Include that children as new parent candidate for the rest + while(!mspChildrens.empty()) + { + bool bContinue = false; + + int max = -1; + KeyFrame* pC; + KeyFrame* pP; + + for(set::iterator sit=mspChildrens.begin(), send=mspChildrens.end(); sit!=send; sit++) + { + KeyFrame* pKF = *sit; + if(pKF->isBad()) + continue; + + // Check if a parent candidate is connected to the keyframe + vector vpConnected = pKF->GetVectorCovisibleKeyFrames(); + for(size_t i=0, iend=vpConnected.size(); i::iterator spcit=sParentCandidates.begin(), spcend=sParentCandidates.end(); spcit!=spcend; spcit++) + { + if(vpConnected[i]->mnId == (*spcit)->mnId) + { + int w = pKF->GetWeight(vpConnected[i]); + if(w>max) + { + pC = pKF; + pP = vpConnected[i]; + max = w; + bContinue = true; + } + } + } + } + } + + if(bContinue) + { + pC->ChangeParent(pP); + sParentCandidates.insert(pC); + mspChildrens.erase(pC); + } + else + break; + } + + // If a children has no covisibility links with any parent candidate, assign to the original parent of this KF + if(!mspChildrens.empty()) + for(set::iterator sit=mspChildrens.begin(); sit!=mspChildrens.end(); sit++) + { + (*sit)->ChangeParent(mpParent); + } + + mpParent->EraseChild(this); + mTcp = Tcw*mpParent->GetPoseInverse(); + mbBad = true; + } + + + mpMap->EraseKeyFrame(this); + mpKeyFrameDB->erase(this); +} + +bool KeyFrame::isBad() +{ + unique_lock lock(mMutexConnections); + return mbBad; +} + +void KeyFrame::EraseConnection(KeyFrame* pKF) +{ + bool bUpdate = false; + { + unique_lock lock(mMutexConnections); + if(mConnectedKeyFrameWeights.count(pKF)) + { + mConnectedKeyFrameWeights.erase(pKF); + bUpdate=true; + } + } + + if(bUpdate) + UpdateBestCovisibles(); +} + +vector KeyFrame::GetFeaturesInArea(const float &x, const float &y, const float &r) const +{ + vector vIndices; + vIndices.reserve(N); + + const int nMinCellX = max(0,(int)floor((x-mnMinX-r)*mfGridElementWidthInv)); + if(nMinCellX>=mnGridCols) + return vIndices; + + const int nMaxCellX = min((int)mnGridCols-1,(int)ceil((x-mnMinX+r)*mfGridElementWidthInv)); + if(nMaxCellX<0) + return vIndices; + + const int nMinCellY = max(0,(int)floor((y-mnMinY-r)*mfGridElementHeightInv)); + if(nMinCellY>=mnGridRows) + return vIndices; + + const int nMaxCellY = min((int)mnGridRows-1,(int)ceil((y-mnMinY+r)*mfGridElementHeightInv)); + if(nMaxCellY<0) + return vIndices; + + for(int ix = nMinCellX; ix<=nMaxCellX; ix++) + { + for(int iy = nMinCellY; iy<=nMaxCellY; iy++) + { + const vector vCell = mGrid[ix][iy]; + for(size_t j=0, jend=vCell.size(); j=mnMinX && x=mnMinY && y0) + { + const float u = mvKeys[i].pt.x; + const float v = mvKeys[i].pt.y; + const float x = (u-cx)*z*invfx; + const float y = (v-cy)*z*invfy; + cv::Mat x3Dc = (cv::Mat_(3,1) << x, y, z); + + unique_lock lock(mMutexPose); + return Twc.rowRange(0,3).colRange(0,3)*x3Dc+Twc.rowRange(0,3).col(3); + } + else + return cv::Mat(); +} + +float KeyFrame::ComputeSceneMedianDepth(const int q) +{ + vector vpMapPoints; + cv::Mat Tcw_; + { + unique_lock lock(mMutexFeatures); + unique_lock lock2(mMutexPose); + vpMapPoints = mvpMapPoints; + Tcw_ = Tcw.clone(); + } + + vector vDepths; + vDepths.reserve(N); + cv::Mat Rcw2 = Tcw_.row(2).colRange(0,3); + Rcw2 = Rcw2.t(); + float zcw = Tcw_.at(2,3); + for(int i=0; iGetWorldPos(); + float z = Rcw2.dot(x3Dw)+zcw; + vDepths.push_back(z); + } + } + + sort(vDepths.begin(),vDepths.end()); + + return vDepths[(vDepths.size()-1)/q]; +} + +} //namespace ORB_SLAM diff --git a/src/KeyFrameDatabase.cc b/src/KeyFrameDatabase.cc new file mode 100644 index 0000000000..826860cab9 --- /dev/null +++ b/src/KeyFrameDatabase.cc @@ -0,0 +1,311 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "KeyFrameDatabase.h" + +#include "KeyFrame.h" +#include "Thirdparty/DBoW2/DBoW2/BowVector.h" + +#include + +using namespace std; + +namespace ORB_SLAM2 +{ + +KeyFrameDatabase::KeyFrameDatabase (const ORBVocabulary &voc): + mpVoc(&voc) +{ + mvInvertedFile.resize(voc.size()); +} + + +void KeyFrameDatabase::add(KeyFrame *pKF) +{ + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit= pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++) + mvInvertedFile[vit->first].push_back(pKF); +} + +void KeyFrameDatabase::erase(KeyFrame* pKF) +{ + unique_lock lock(mMutex); + + // Erase elements in the Inverse File for the entry + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit!=vend; vit++) + { + // List of keyframes that share the word + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + if(pKF==*lit) + { + lKFs.erase(lit); + break; + } + } + } +} + +void KeyFrameDatabase::clear() +{ + mvInvertedFile.clear(); + mvInvertedFile.resize(mpVoc->size()); +} + + +vector KeyFrameDatabase::DetectLoopCandidates(KeyFrame* pKF, float minScore) +{ + set spConnectedKeyFrames = pKF->GetConnectedKeyFrames(); + list lKFsSharingWords; + + // Search all keyframes that share a word with current keyframes + // Discard keyframes connected to the query keyframe + { + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit=pKF->mBowVec.begin(), vend=pKF->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + if(pKFi->mnLoopQuery!=pKF->mnId) + { + pKFi->mnLoopWords=0; + if(!spConnectedKeyFrames.count(pKFi)) + { + pKFi->mnLoopQuery=pKF->mnId; + lKFsSharingWords.push_back(pKFi); + } + } + pKFi->mnLoopWords++; + } + } + } + + if(lKFsSharingWords.empty()) + return vector(); + + list > lScoreAndMatch; + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + if((*lit)->mnLoopWords>maxCommonWords) + maxCommonWords=(*lit)->mnLoopWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + int nscores=0; + + // Compute similarity score. Retain the matches whose score is higher than minScore + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnLoopWords>minCommonWords) + { + nscores++; + + float si = mpVoc->score(pKF->mBowVec,pKFi->mBowVec); + + pKFi->mLoopScore = si; + if(si>=minScore) + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(lScoreAndMatch.empty()) + return vector(); + + list > lAccScoreAndMatch; + float bestAccScore = minScore; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = it->first; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnLoopQuery==pKF->mnId && pKF2->mnLoopWords>minCommonWords) + { + accScore+=pKF2->mLoopScore; + if(pKF2->mLoopScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mLoopScore; + } + } + } + + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + + set spAlreadyAddedKF; + vector vpLoopCandidates; + vpLoopCandidates.reserve(lAccScoreAndMatch.size()); + + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + if(it->first>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + vpLoopCandidates.push_back(pKFi); + spAlreadyAddedKF.insert(pKFi); + } + } + } + + + return vpLoopCandidates; +} + +vector KeyFrameDatabase::DetectRelocalizationCandidates(Frame *F) +{ + list lKFsSharingWords; + + // Search all keyframes that share a word with current frame + { + unique_lock lock(mMutex); + + for(DBoW2::BowVector::const_iterator vit=F->mBowVec.begin(), vend=F->mBowVec.end(); vit != vend; vit++) + { + list &lKFs = mvInvertedFile[vit->first]; + + for(list::iterator lit=lKFs.begin(), lend= lKFs.end(); lit!=lend; lit++) + { + KeyFrame* pKFi=*lit; + if(pKFi->mnRelocQuery!=F->mnId) + { + pKFi->mnRelocWords=0; + pKFi->mnRelocQuery=F->mnId; + lKFsSharingWords.push_back(pKFi); + } + pKFi->mnRelocWords++; + } + } + } + if(lKFsSharingWords.empty()) + return vector(); + + // Only compare against those keyframes that share enough words + int maxCommonWords=0; + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + if((*lit)->mnRelocWords>maxCommonWords) + maxCommonWords=(*lit)->mnRelocWords; + } + + int minCommonWords = maxCommonWords*0.8f; + + list > lScoreAndMatch; + + int nscores=0; + + // Compute similarity score. + for(list::iterator lit=lKFsSharingWords.begin(), lend= lKFsSharingWords.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + + if(pKFi->mnRelocWords>minCommonWords) + { + nscores++; + float si = mpVoc->score(F->mBowVec,pKFi->mBowVec); + pKFi->mRelocScore=si; + lScoreAndMatch.push_back(make_pair(si,pKFi)); + } + } + + if(lScoreAndMatch.empty()) + return vector(); + + list > lAccScoreAndMatch; + float bestAccScore = 0; + + // Lets now accumulate score by covisibility + for(list >::iterator it=lScoreAndMatch.begin(), itend=lScoreAndMatch.end(); it!=itend; it++) + { + KeyFrame* pKFi = it->second; + vector vpNeighs = pKFi->GetBestCovisibilityKeyFrames(10); + + float bestScore = it->first; + float accScore = bestScore; + KeyFrame* pBestKF = pKFi; + for(vector::iterator vit=vpNeighs.begin(), vend=vpNeighs.end(); vit!=vend; vit++) + { + KeyFrame* pKF2 = *vit; + if(pKF2->mnRelocQuery!=F->mnId) + continue; + + accScore+=pKF2->mRelocScore; + if(pKF2->mRelocScore>bestScore) + { + pBestKF=pKF2; + bestScore = pKF2->mRelocScore; + } + + } + lAccScoreAndMatch.push_back(make_pair(accScore,pBestKF)); + if(accScore>bestAccScore) + bestAccScore=accScore; + } + + // Return all those keyframes with a score higher than 0.75*bestScore + float minScoreToRetain = 0.75f*bestAccScore; + set spAlreadyAddedKF; + vector vpRelocCandidates; + vpRelocCandidates.reserve(lAccScoreAndMatch.size()); + for(list >::iterator it=lAccScoreAndMatch.begin(), itend=lAccScoreAndMatch.end(); it!=itend; it++) + { + const float &si = it->first; + if(si>minScoreToRetain) + { + KeyFrame* pKFi = it->second; + if(!spAlreadyAddedKF.count(pKFi)) + { + vpRelocCandidates.push_back(pKFi); + spAlreadyAddedKF.insert(pKFi); + } + } + } + + return vpRelocCandidates; +} + +} //namespace ORB_SLAM diff --git a/src/LocalMapping.cc b/src/LocalMapping.cc new file mode 100644 index 0000000000..d80f61ebd6 --- /dev/null +++ b/src/LocalMapping.cc @@ -0,0 +1,760 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "LocalMapping.h" +#include "LoopClosing.h" +#include "ORBmatcher.h" +#include "Optimizer.h" + +#include + +namespace ORB_SLAM2 +{ + +LocalMapping::LocalMapping(Map *pMap, const float bMonocular): + mbMonocular(bMonocular), mbResetRequested(false), mbFinishRequested(false), mbFinished(true), mpMap(pMap), + mbAbortBA(false), mbStopped(false), mbStopRequested(false), mbNotStop(false), mbAcceptKeyFrames(true) +{ +} + +void LocalMapping::SetLoopCloser(LoopClosing* pLoopCloser) +{ + mpLoopCloser = pLoopCloser; +} + +void LocalMapping::SetTracker(Tracking *pTracker) +{ + mpTracker=pTracker; +} + +void LocalMapping::Run() +{ + + mbFinished = false; + + while(1) + { + // Tracking will see that Local Mapping is busy + SetAcceptKeyFrames(false); + + // Check if there are keyframes in the queue + if(CheckNewKeyFrames()) + { + // BoW conversion and insertion in Map + ProcessNewKeyFrame(); + + // Check recent MapPoints + MapPointCulling(); + + // Triangulate new MapPoints + CreateNewMapPoints(); + + if(!CheckNewKeyFrames()) + { + // Find more matches in neighbor keyframes and fuse point duplications + SearchInNeighbors(); + } + + mbAbortBA = false; + + if(!CheckNewKeyFrames() && !stopRequested()) + { + // Local BA + if(mpMap->KeyFramesInMap()>2) + Optimizer::LocalBundleAdjustment(mpCurrentKeyFrame,&mbAbortBA, mpMap); + + // Check redundant local Keyframes + KeyFrameCulling(); + } + + mpLoopCloser->InsertKeyFrame(mpCurrentKeyFrame); + } + else if(Stop()) + { + // Safe area to stop + while(isStopped()) + { + usleep(3000); + } + } + + ResetIfRequested(); + + // Tracking will see that Local Mapping is busy + SetAcceptKeyFrames(true); + + if(CheckFinish()) + break; + + usleep(3000); + } + + SetFinish(); +} + +void LocalMapping::InsertKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexNewKFs); + mlNewKeyFrames.push_back(pKF); + mbAbortBA=true; +} + + +bool LocalMapping::CheckNewKeyFrames() +{ + unique_lock lock(mMutexNewKFs); + return(!mlNewKeyFrames.empty()); +} + +void LocalMapping::ProcessNewKeyFrame() +{ + { + unique_lock lock(mMutexNewKFs); + mpCurrentKeyFrame = mlNewKeyFrames.front(); + mlNewKeyFrames.pop_front(); + } + + // Compute Bags of Words structures + mpCurrentKeyFrame->ComputeBoW(); + + // Associate MapPoints to the new keyframe and update normal and descriptor + const vector vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches(); + + for(size_t i=0; iisBad()) + { + if(!pMP->IsInKeyFrame(mpCurrentKeyFrame)) + { + pMP->AddObservation(mpCurrentKeyFrame, i); + pMP->UpdateNormalAndDepth(); + pMP->ComputeDistinctiveDescriptors(); + } + else // this can only happen for new stereo points inserted by the Tracking + { + mlpRecentAddedMapPoints.push_back(pMP); + } + } + } + } + + // Update links in the Covisibility Graph + mpCurrentKeyFrame->UpdateConnections(); + + // Insert Keyframe in Map + mpMap->AddKeyFrame(mpCurrentKeyFrame); +} + +void LocalMapping::MapPointCulling() +{ + // Check Recent Added MapPoints + list::iterator lit = mlpRecentAddedMapPoints.begin(); + const unsigned long int nCurrentKFid = mpCurrentKeyFrame->mnId; + + int nThObs; + if(mbMonocular) + nThObs = 2; + else + nThObs = 3; + const int cnThObs = nThObs; + + while(lit!=mlpRecentAddedMapPoints.end()) + { + MapPoint* pMP = *lit; + if(pMP->isBad()) + { + lit = mlpRecentAddedMapPoints.erase(lit); + } + else if(pMP->GetFoundRatio()<0.25f ) + { + pMP->SetBadFlag(); + lit = mlpRecentAddedMapPoints.erase(lit); + } + else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=2 && pMP->Observations()<=cnThObs) + { + pMP->SetBadFlag(); + lit = mlpRecentAddedMapPoints.erase(lit); + } + else if(((int)nCurrentKFid-(int)pMP->mnFirstKFid)>=3) + lit = mlpRecentAddedMapPoints.erase(lit); + else + lit++; + } +} + +void LocalMapping::CreateNewMapPoints() +{ + // Retrieve neighbor keyframes in covisibility graph + int nn = 10; + if(mbMonocular) + nn=20; + const vector vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn); + + ORBmatcher matcher(0.6,false); + + cv::Mat Rcw1 = mpCurrentKeyFrame->GetRotation(); + cv::Mat Rwc1 = Rcw1.t(); + cv::Mat tcw1 = mpCurrentKeyFrame->GetTranslation(); + cv::Mat Tcw1(3,4,CV_32F); + Rcw1.copyTo(Tcw1.colRange(0,3)); + tcw1.copyTo(Tcw1.col(3)); + cv::Mat Ow1 = mpCurrentKeyFrame->GetCameraCenter(); + + const float &fx1 = mpCurrentKeyFrame->fx; + const float &fy1 = mpCurrentKeyFrame->fy; + const float &cx1 = mpCurrentKeyFrame->cx; + const float &cy1 = mpCurrentKeyFrame->cy; + const float &invfx1 = mpCurrentKeyFrame->invfx; + const float &invfy1 = mpCurrentKeyFrame->invfy; + + const float ratioFactor = 1.5f*mpCurrentKeyFrame->mfScaleFactor; + + int nnew=0; + + // Search matches with epipolar restriction and triangulate + for(size_t i=0; i0 && CheckNewKeyFrames()) + return; + + KeyFrame* pKF2 = vpNeighKFs[i]; + + // Check first that baseline is not too short + cv::Mat Ow2 = pKF2->GetCameraCenter(); + cv::Mat vBaseline = Ow2-Ow1; + const float baseline = cv::norm(vBaseline); + + if(!mbMonocular) + { + if(baselinemb) + continue; + } + else + { + const float medianDepthKF2 = pKF2->ComputeSceneMedianDepth(2); + const float ratioBaselineDepth = baseline/medianDepthKF2; + + if(ratioBaselineDepth<0.01) + continue; + } + + // Compute Fundamental Matrix + cv::Mat F12 = ComputeF12(mpCurrentKeyFrame,pKF2); + + // Search matches that fullfil epipolar constraint + vector > vMatchedIndices; + matcher.SearchForTriangulation(mpCurrentKeyFrame,pKF2,F12,vMatchedIndices,false); + + cv::Mat Rcw2 = pKF2->GetRotation(); + cv::Mat Rwc2 = Rcw2.t(); + cv::Mat tcw2 = pKF2->GetTranslation(); + cv::Mat Tcw2(3,4,CV_32F); + Rcw2.copyTo(Tcw2.colRange(0,3)); + tcw2.copyTo(Tcw2.col(3)); + + const float &fx2 = pKF2->fx; + const float &fy2 = pKF2->fy; + const float &cx2 = pKF2->cx; + const float &cy2 = pKF2->cy; + const float &invfx2 = pKF2->invfx; + const float &invfy2 = pKF2->invfy; + + // Triangulate each match + const int nmatches = vMatchedIndices.size(); + for(int ikp=0; ikpmvKeysUn[idx1]; + const float kp1_ur=mpCurrentKeyFrame->mvuRight[idx1]; + bool bStereo1 = kp1_ur>=0; + + const cv::KeyPoint &kp2 = pKF2->mvKeysUn[idx2]; + const float kp2_ur = pKF2->mvuRight[idx2]; + bool bStereo2 = kp2_ur>=0; + + // Check parallax between rays + cv::Mat xn1 = (cv::Mat_(3,1) << (kp1.pt.x-cx1)*invfx1, (kp1.pt.y-cy1)*invfy1, 1.0); + cv::Mat xn2 = (cv::Mat_(3,1) << (kp2.pt.x-cx2)*invfx2, (kp2.pt.y-cy2)*invfy2, 1.0); + + cv::Mat ray1 = Rwc1*xn1; + cv::Mat ray2 = Rwc2*xn2; + const float cosParallaxRays = ray1.dot(ray2)/(cv::norm(ray1)*cv::norm(ray2)); + + float cosParallaxStereo = cosParallaxRays+1; + float cosParallaxStereo1 = cosParallaxStereo; + float cosParallaxStereo2 = cosParallaxStereo; + + if(bStereo1) + cosParallaxStereo1 = cos(2*atan2(mpCurrentKeyFrame->mb/2,mpCurrentKeyFrame->mvDepth[idx1])); + else if(bStereo2) + cosParallaxStereo2 = cos(2*atan2(pKF2->mb/2,pKF2->mvDepth[idx2])); + + cosParallaxStereo = min(cosParallaxStereo1,cosParallaxStereo2); + + cv::Mat x3D; + if(cosParallaxRays0 && (bStereo1 || bStereo2 || cosParallaxRays<0.9998)) + { + // Linear Triangulation Method + cv::Mat A(4,4,CV_32F); + A.row(0) = xn1.at(0)*Tcw1.row(2)-Tcw1.row(0); + A.row(1) = xn1.at(1)*Tcw1.row(2)-Tcw1.row(1); + A.row(2) = xn2.at(0)*Tcw2.row(2)-Tcw2.row(0); + A.row(3) = xn2.at(1)*Tcw2.row(2)-Tcw2.row(1); + + cv::Mat w,u,vt; + cv::SVD::compute(A,w,u,vt,cv::SVD::MODIFY_A| cv::SVD::FULL_UV); + + x3D = vt.row(3).t(); + + if(x3D.at(3)==0) + continue; + + // Euclidean coordinates + x3D = x3D.rowRange(0,3)/x3D.at(3); + + } + else if(bStereo1 && cosParallaxStereo1UnprojectStereo(idx1); + } + else if(bStereo2 && cosParallaxStereo2UnprojectStereo(idx2); + } + else + continue; //No stereo and very low parallax + + cv::Mat x3Dt = x3D.t(); + + //Check triangulation in front of cameras + float z1 = Rcw1.row(2).dot(x3Dt)+tcw1.at(2); + if(z1<=0) + continue; + + float z2 = Rcw2.row(2).dot(x3Dt)+tcw2.at(2); + if(z2<=0) + continue; + + //Check reprojection error in first keyframe + const float &sigmaSquare1 = mpCurrentKeyFrame->mvLevelSigma2[kp1.octave]; + const float x1 = Rcw1.row(0).dot(x3Dt)+tcw1.at(0); + const float y1 = Rcw1.row(1).dot(x3Dt)+tcw1.at(1); + const float invz1 = 1.0/z1; + + if(!bStereo1) + { + float u1 = fx1*x1*invz1+cx1; + float v1 = fy1*y1*invz1+cy1; + float errX1 = u1 - kp1.pt.x; + float errY1 = v1 - kp1.pt.y; + if((errX1*errX1+errY1*errY1)>5.991*sigmaSquare1) + continue; + } + else + { + float u1 = fx1*x1*invz1+cx1; + float u1_r = u1 - mpCurrentKeyFrame->mbf*invz1; + float v1 = fy1*y1*invz1+cy1; + float errX1 = u1 - kp1.pt.x; + float errY1 = v1 - kp1.pt.y; + float errX1_r = u1_r - kp1_ur; + if((errX1*errX1+errY1*errY1+errX1_r*errX1_r)>7.8*sigmaSquare1) + continue; + } + + //Check reprojection error in second keyframe + const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave]; + const float x2 = Rcw2.row(0).dot(x3Dt)+tcw2.at(0); + const float y2 = Rcw2.row(1).dot(x3Dt)+tcw2.at(1); + const float invz2 = 1.0/z2; + if(!bStereo2) + { + float u2 = fx2*x2*invz2+cx2; + float v2 = fy2*y2*invz2+cy2; + float errX2 = u2 - kp2.pt.x; + float errY2 = v2 - kp2.pt.y; + if((errX2*errX2+errY2*errY2)>5.991*sigmaSquare2) + continue; + } + else + { + float u2 = fx2*x2*invz2+cx2; + float u2_r = u2 - mpCurrentKeyFrame->mbf*invz2; + float v2 = fy2*y2*invz2+cy2; + float errX2 = u2 - kp2.pt.x; + float errY2 = v2 - kp2.pt.y; + float errX2_r = u2_r - kp2_ur; + if((errX2*errX2+errY2*errY2+errX2_r*errX2_r)>7.8*sigmaSquare2) + continue; + } + + //Check scale consistency + cv::Mat normal1 = x3D-Ow1; + float dist1 = cv::norm(normal1); + + cv::Mat normal2 = x3D-Ow2; + float dist2 = cv::norm(normal2); + + if(dist1==0 || dist2==0) + continue; + + const float ratioDist = dist2/dist1; + const float ratioOctave = mpCurrentKeyFrame->mvScaleFactors[kp1.octave]/pKF2->mvScaleFactors[kp2.octave]; + + /*if(fabs(ratioDist-ratioOctave)>ratioFactor) + continue;*/ + if(ratioDist*ratioFactorratioOctave*ratioFactor) + continue; + + // Triangulation is succesfull + MapPoint* pMP = new MapPoint(x3D,mpCurrentKeyFrame,mpMap); + + pMP->AddObservation(mpCurrentKeyFrame,idx1); + pMP->AddObservation(pKF2,idx2); + + mpCurrentKeyFrame->AddMapPoint(pMP,idx1); + pKF2->AddMapPoint(pMP,idx2); + + pMP->ComputeDistinctiveDescriptors(); + + pMP->UpdateNormalAndDepth(); + + mpMap->AddMapPoint(pMP); + mlpRecentAddedMapPoints.push_back(pMP); + + nnew++; + } + } +} + +void LocalMapping::SearchInNeighbors() +{ + // Retrieve neighbor keyframes + int nn = 10; + if(mbMonocular) + nn=20; + const vector vpNeighKFs = mpCurrentKeyFrame->GetBestCovisibilityKeyFrames(nn); + vector vpTargetKFs; + for(vector::const_iterator vit=vpNeighKFs.begin(), vend=vpNeighKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + if(pKFi->isBad() || pKFi->mnFuseTargetForKF == mpCurrentKeyFrame->mnId) + continue; + vpTargetKFs.push_back(pKFi); + pKFi->mnFuseTargetForKF = mpCurrentKeyFrame->mnId; + + // Extend to some second neighbors + const vector vpSecondNeighKFs = pKFi->GetBestCovisibilityKeyFrames(5); + for(vector::const_iterator vit2=vpSecondNeighKFs.begin(), vend2=vpSecondNeighKFs.end(); vit2!=vend2; vit2++) + { + KeyFrame* pKFi2 = *vit2; + if(pKFi2->isBad() || pKFi2->mnFuseTargetForKF==mpCurrentKeyFrame->mnId || pKFi2->mnId==mpCurrentKeyFrame->mnId) + continue; + vpTargetKFs.push_back(pKFi2); + } + } + + + // Search matches by projection from current KF in target KFs + ORBmatcher matcher; + vector vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches(); + for(vector::iterator vit=vpTargetKFs.begin(), vend=vpTargetKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + + matcher.Fuse(pKFi,vpMapPointMatches); + } + + // Search matches by projection from target KFs in current KF + vector vpFuseCandidates; + vpFuseCandidates.reserve(vpTargetKFs.size()*vpMapPointMatches.size()); + + for(vector::iterator vitKF=vpTargetKFs.begin(), vendKF=vpTargetKFs.end(); vitKF!=vendKF; vitKF++) + { + KeyFrame* pKFi = *vitKF; + + vector vpMapPointsKFi = pKFi->GetMapPointMatches(); + + for(vector::iterator vitMP=vpMapPointsKFi.begin(), vendMP=vpMapPointsKFi.end(); vitMP!=vendMP; vitMP++) + { + MapPoint* pMP = *vitMP; + if(!pMP) + continue; + if(pMP->isBad() || pMP->mnFuseCandidateForKF == mpCurrentKeyFrame->mnId) + continue; + pMP->mnFuseCandidateForKF = mpCurrentKeyFrame->mnId; + vpFuseCandidates.push_back(pMP); + } + } + + matcher.Fuse(mpCurrentKeyFrame,vpFuseCandidates); + + + // Update points + vpMapPointMatches = mpCurrentKeyFrame->GetMapPointMatches(); + for(size_t i=0, iend=vpMapPointMatches.size(); iisBad()) + { + pMP->ComputeDistinctiveDescriptors(); + pMP->UpdateNormalAndDepth(); + } + } + } + + // Update connections in covisibility graph + mpCurrentKeyFrame->UpdateConnections(); +} + +cv::Mat LocalMapping::ComputeF12(KeyFrame *&pKF1, KeyFrame *&pKF2) +{ + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + + cv::Mat R12 = R1w*R2w.t(); + cv::Mat t12 = -R1w*R2w.t()*t2w+t1w; + + cv::Mat t12x = SkewSymmetricMatrix(t12); + + const cv::Mat &K1 = pKF1->mK; + const cv::Mat &K2 = pKF2->mK; + + + return K1.t().inv()*t12x*R12*K2.inv(); +} + +void LocalMapping::RequestStop() +{ + unique_lock lock(mMutexStop); + mbStopRequested = true; + unique_lock lock2(mMutexNewKFs); + mbAbortBA = true; +} + +bool LocalMapping::Stop() +{ + unique_lock lock(mMutexStop); + if(mbStopRequested && !mbNotStop) + { + mbStopped = true; + cout << "Local Mapping STOP" << endl; + return true; + } + + return false; +} + +bool LocalMapping::isStopped() +{ + unique_lock lock(mMutexStop); + return mbStopped; +} + +bool LocalMapping::stopRequested() +{ + unique_lock lock(mMutexStop); + return mbStopRequested; +} + +void LocalMapping::Release() +{ + unique_lock lock(mMutexStop); + unique_lock lock2(mMutexFinish); + if(mbFinished) + return; + mbStopped = false; + mbStopRequested = false; + for(list::iterator lit = mlNewKeyFrames.begin(), lend=mlNewKeyFrames.end(); lit!=lend; lit++) + delete *lit; + mlNewKeyFrames.clear(); + + cout << "Local Mapping RELEASE" << endl; +} + +bool LocalMapping::AcceptKeyFrames() +{ + unique_lock lock(mMutexAccept); + return mbAcceptKeyFrames; +} + +void LocalMapping::SetAcceptKeyFrames(bool flag) +{ + unique_lock lock(mMutexAccept); + mbAcceptKeyFrames=flag; +} + +bool LocalMapping::SetNotStop(bool flag) +{ + unique_lock lock(mMutexStop); + + if(flag && mbStopped) + return false; + + mbNotStop = flag; + + return true; +} + +void LocalMapping::InterruptBA() +{ + mbAbortBA = true; +} + +void LocalMapping::KeyFrameCulling() +{ + // Check redundant keyframes (only local keyframes) + // A keyframe is considered redundant if the 90% of the MapPoints it sees, are seen + // in at least other 3 keyframes (in the same or finer scale) + // We only consider close stereo points + vector vpLocalKeyFrames = mpCurrentKeyFrame->GetVectorCovisibleKeyFrames(); + + for(vector::iterator vit=vpLocalKeyFrames.begin(), vend=vpLocalKeyFrames.end(); vit!=vend; vit++) + { + KeyFrame* pKF = *vit; + if(pKF->mnId==0) + continue; + const vector vpMapPoints = pKF->GetMapPointMatches(); + + int /*nObs = 2; + if(mbMonocular)*/ + nObs = 3; + const int thObs=nObs; + int nRedundantObservations=0; + int nMPs=0; + for(size_t i=0, iend=vpMapPoints.size(); iisBad()) + { + if(!mbMonocular) + { + if(pKF->mvDepth[i]>pKF->mThDepth || pKF->mvDepth[i]<0) + continue; + } + + nMPs++; + if(pMP->Observations()>thObs) + { + const int &scaleLevel = pKF->mvKeysUn[i].octave; + const map observations = pMP->GetObservations(); + int nObs=0; + for(map::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + if(pKFi==pKF) + continue; + const int &scaleLeveli = pKFi->mvKeysUn[mit->second].octave; + + if(scaleLeveli<=scaleLevel+1) + { + nObs++; + if(nObs>=thObs) + break; + } + } + if(nObs>=thObs) + { + nRedundantObservations++; + } + } + } + } + } + + if(nRedundantObservations>0.9*nMPs) + pKF->SetBadFlag(); + } +} + +cv::Mat LocalMapping::SkewSymmetricMatrix(const cv::Mat &v) +{ + return (cv::Mat_(3,3) << 0, -v.at(2), v.at(1), + v.at(2), 0,-v.at(0), + -v.at(1), v.at(0), 0); +} + +void LocalMapping::RequestReset() +{ + { + unique_lock lock(mMutexReset); + mbResetRequested = true; + } + + while(1) + { + { + unique_lock lock2(mMutexReset); + if(!mbResetRequested) + break; + } + usleep(3000); + } +} + +void LocalMapping::ResetIfRequested() +{ + unique_lock lock(mMutexReset); + if(mbResetRequested) + { + mlNewKeyFrames.clear(); + mlpRecentAddedMapPoints.clear(); + mbResetRequested=false; + } +} + +void LocalMapping::RequestFinish() +{ + unique_lock lock(mMutexFinish); + mbFinishRequested = true; +} + +bool LocalMapping::CheckFinish() +{ + unique_lock lock(mMutexFinish); + return mbFinishRequested; +} + +void LocalMapping::SetFinish() +{ + unique_lock lock(mMutexFinish); + mbFinished = true; + unique_lock lock2(mMutexStop); + mbStopped = true; +} + +bool LocalMapping::isFinished() +{ + unique_lock lock(mMutexFinish); + return mbFinished; +} + +} //namespace ORB_SLAM diff --git a/src/LoopClosing.cc b/src/LoopClosing.cc new file mode 100644 index 0000000000..6879125fdd --- /dev/null +++ b/src/LoopClosing.cc @@ -0,0 +1,770 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "LoopClosing.h" + +#include "Sim3Solver.h" + +#include "Converter.h" + +#include "Optimizer.h" + +#include "ORBmatcher.h" + +#include +#include + + +namespace ORB_SLAM2 +{ + +LoopClosing::LoopClosing(Map *pMap, KeyFrameDatabase *pDB, ORBVocabulary *pVoc, const bool bFixScale): + mbResetRequested(false), mbFinishRequested(false), mbFinished(true), mpMap(pMap), + mpKeyFrameDB(pDB), mpORBVocabulary(pVoc), mLastLoopKFid(0), mbRunningGBA(false), mbFinishedGBA(true), + mbStopGBA(false), mbFixScale(bFixScale) +{ + mnCovisibilityConsistencyTh = 3; + mpMatchedKF = NULL; +} + +void LoopClosing::SetTracker(Tracking *pTracker) +{ + mpTracker=pTracker; +} + +void LoopClosing::SetLocalMapper(LocalMapping *pLocalMapper) +{ + mpLocalMapper=pLocalMapper; +} + + +void LoopClosing::Run() +{ + mbFinished =false; + + while(1) + { + // Check if there are keyframes in the queue + if(CheckNewKeyFrames()) + { + // Detect loop candidates and check covisibility consistency + if(DetectLoop()) + { + // Compute similarity transformation [sR|t] + // In the stereo/RGBD case s=1 + if(ComputeSim3()) + { + // Perform loop fusion and pose graph optimization + CorrectLoop(); + } + } + } + + ResetIfRequested(); + + if(CheckFinish()) + break; + + usleep(5000); + } + + SetFinish(); +} + +void LoopClosing::InsertKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexLoopQueue); + if(pKF->mnId!=0) + mlpLoopKeyFrameQueue.push_back(pKF); +} + +bool LoopClosing::CheckNewKeyFrames() +{ + unique_lock lock(mMutexLoopQueue); + return(!mlpLoopKeyFrameQueue.empty()); +} + +bool LoopClosing::DetectLoop() +{ + { + unique_lock lock(mMutexLoopQueue); + mpCurrentKF = mlpLoopKeyFrameQueue.front(); + mlpLoopKeyFrameQueue.pop_front(); + // Avoid that a keyframe can be erased while it is being process by this thread + mpCurrentKF->SetNotErase(); + } + + //If the map contains less than 10 KF or less than 10 KF have passed from last loop detection + if(mpCurrentKF->mnIdadd(mpCurrentKF); + mpCurrentKF->SetErase(); + return false; + } + + // Compute reference BoW similarity score + // This is the lowest score to a connected keyframe in the covisibility graph + // We will impose loop candidates to have a higher similarity than this + const vector vpConnectedKeyFrames = mpCurrentKF->GetVectorCovisibleKeyFrames(); + const DBoW2::BowVector &CurrentBowVec = mpCurrentKF->mBowVec; + float minScore = 1; + for(size_t i=0; iisBad()) + continue; + const DBoW2::BowVector &BowVec = pKF->mBowVec; + + float score = mpORBVocabulary->score(CurrentBowVec, BowVec); + + if(score vpCandidateKFs = mpKeyFrameDB->DetectLoopCandidates(mpCurrentKF, minScore); + + // If there are no loop candidates, just add new keyframe and return false + if(vpCandidateKFs.empty()) + { + mpKeyFrameDB->add(mpCurrentKF); + mvConsistentGroups.clear(); + mpCurrentKF->SetErase(); + return false; + } + + // For each loop candidate check consistency with previous loop candidates + // Each candidate expands a covisibility group (keyframes connected to the loop candidate in the covisibility graph) + // A group is consistent with a previous group if they share at least a keyframe + // We must detect a consistent loop in several consecutive keyframes to accept it + mvpEnoughConsistentCandidates.clear(); + + vector vCurrentConsistentGroups; + vector vbConsistentGroup(mvConsistentGroups.size(),false); + for(size_t i=0, iend=vpCandidateKFs.size(); i spCandidateGroup = pCandidateKF->GetConnectedKeyFrames(); + spCandidateGroup.insert(pCandidateKF); + + bool bEnoughConsistent = false; + bool bConsistentForSomeGroup = false; + for(size_t iG=0, iendG=mvConsistentGroups.size(); iG sPreviousGroup = mvConsistentGroups[iG].first; + + bool bConsistent = false; + for(set::iterator sit=spCandidateGroup.begin(), send=spCandidateGroup.end(); sit!=send;sit++) + { + if(sPreviousGroup.count(*sit)) + { + bConsistent=true; + bConsistentForSomeGroup=true; + break; + } + } + + if(bConsistent) + { + int nPreviousConsistency = mvConsistentGroups[iG].second; + int nCurrentConsistency = nPreviousConsistency + 1; + if(!vbConsistentGroup[iG]) + { + ConsistentGroup cg = make_pair(spCandidateGroup,nCurrentConsistency); + vCurrentConsistentGroups.push_back(cg); + vbConsistentGroup[iG]=true; //this avoid to include the same group more than once + } + if(nCurrentConsistency>=mnCovisibilityConsistencyTh && !bEnoughConsistent) + { + mvpEnoughConsistentCandidates.push_back(pCandidateKF); + bEnoughConsistent=true; //this avoid to insert the same candidate more than once + } + } + } + + // If the group is not consistent with any previous group insert with consistency counter set to zero + if(!bConsistentForSomeGroup) + { + ConsistentGroup cg = make_pair(spCandidateGroup,0); + vCurrentConsistentGroups.push_back(cg); + } + } + + // Update Covisibility Consistent Groups + mvConsistentGroups = vCurrentConsistentGroups; + + + // Add Current Keyframe to database + mpKeyFrameDB->add(mpCurrentKF); + + if(mvpEnoughConsistentCandidates.empty()) + { + mpCurrentKF->SetErase(); + return false; + } + else + { + return true; + } + + mpCurrentKF->SetErase(); + return false; +} + +bool LoopClosing::ComputeSim3() +{ + // For each consistent loop candidate we try to compute a Sim3 + + const int nInitialCandidates = mvpEnoughConsistentCandidates.size(); + + // We compute first ORB matches for each candidate + // If enough matches are found, we setup a Sim3Solver + ORBmatcher matcher(0.75,true); + + vector vpSim3Solvers; + vpSim3Solvers.resize(nInitialCandidates); + + vector > vvpMapPointMatches; + vvpMapPointMatches.resize(nInitialCandidates); + + vector vbDiscarded; + vbDiscarded.resize(nInitialCandidates); + + int nCandidates=0; //candidates with enough matches + + for(int i=0; iSetNotErase(); + + if(pKF->isBad()) + { + vbDiscarded[i] = true; + continue; + } + + int nmatches = matcher.SearchByBoW(mpCurrentKF,pKF,vvpMapPointMatches[i]); + + if(nmatches<20) + { + vbDiscarded[i] = true; + continue; + } + else + { + Sim3Solver* pSolver = new Sim3Solver(mpCurrentKF,pKF,vvpMapPointMatches[i],mbFixScale); + pSolver->SetRansacParameters(0.99,20,300); + vpSim3Solvers[i] = pSolver; + } + + nCandidates++; + } + + bool bMatch = false; + + // Perform alternatively RANSAC iterations for each candidate + // until one is succesful or all fail + while(nCandidates>0 && !bMatch) + { + for(int i=0; i vbInliers; + int nInliers; + bool bNoMore; + + Sim3Solver* pSolver = vpSim3Solvers[i]; + cv::Mat Scm = pSolver->iterate(5,bNoMore,vbInliers,nInliers); + + // If Ransac reachs max. iterations discard keyframe + if(bNoMore) + { + vbDiscarded[i]=true; + nCandidates--; + } + + // If RANSAC returns a Sim3, perform a guided matching and optimize with all correspondences + if(!Scm.empty()) + { + vector vpMapPointMatches(vvpMapPointMatches[i].size(), static_cast(NULL)); + for(size_t j=0, jend=vbInliers.size(); jGetEstimatedRotation(); + cv::Mat t = pSolver->GetEstimatedTranslation(); + const float s = pSolver->GetEstimatedScale(); + matcher.SearchBySim3(mpCurrentKF,pKF,vpMapPointMatches,s,R,t,7.5); + + g2o::Sim3 gScm(Converter::toMatrix3d(R),Converter::toVector3d(t),s); + const int nInliers = Optimizer::OptimizeSim3(mpCurrentKF, pKF, vpMapPointMatches, gScm, 10, mbFixScale); + + // If optimization is succesful stop ransacs and continue + if(nInliers>=20) + { + bMatch = true; + mpMatchedKF = pKF; + g2o::Sim3 gSmw(Converter::toMatrix3d(pKF->GetRotation()),Converter::toVector3d(pKF->GetTranslation()),1.0); + mg2oScw = gScm*gSmw; + mScw = Converter::toCvMat(mg2oScw); + + mvpCurrentMatchedPoints = vpMapPointMatches; + break; + } + } + } + } + + if(!bMatch) + { + for(int i=0; iSetErase(); + mpCurrentKF->SetErase(); + return false; + } + + // Retrieve MapPoints seen in Loop Keyframe and neighbors + vector vpLoopConnectedKFs = mpMatchedKF->GetVectorCovisibleKeyFrames(); + vpLoopConnectedKFs.push_back(mpMatchedKF); + mvpLoopMapPoints.clear(); + for(vector::iterator vit=vpLoopConnectedKFs.begin(); vit!=vpLoopConnectedKFs.end(); vit++) + { + KeyFrame* pKF = *vit; + vector vpMapPoints = pKF->GetMapPointMatches(); + for(size_t i=0, iend=vpMapPoints.size(); iisBad() && pMP->mnLoopPointForKF!=mpCurrentKF->mnId) + { + mvpLoopMapPoints.push_back(pMP); + pMP->mnLoopPointForKF=mpCurrentKF->mnId; + } + } + } + } + + // Find more matches projecting with the computed Sim3 + matcher.SearchByProjection(mpCurrentKF, mScw, mvpLoopMapPoints, mvpCurrentMatchedPoints,10); + + // If enough matches accept Loop + int nTotalMatches = 0; + for(size_t i=0; i=40) + { + for(int i=0; iSetErase(); + return true; + } + else + { + for(int i=0; iSetErase(); + mpCurrentKF->SetErase(); + return false; + } + +} + +void LoopClosing::CorrectLoop() +{ + cout << "Loop detected!" << endl; + + // Send a stop signal to Local Mapping + // Avoid new keyframes are inserted while correcting the loop + mpLocalMapper->RequestStop(); + + // If a Global Bundle Adjustment is running, abort it + if(isRunningGBA()) + { + mbStopGBA = true; + + while(!isFinishedGBA()) + usleep(5000); + + mpThreadGBA->join(); + delete mpThreadGBA; + } + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + // Ensure current keyframe is updated + mpCurrentKF->UpdateConnections(); + + // Retrive keyframes connected to the current keyframe and compute corrected Sim3 pose by propagation + mvpCurrentConnectedKFs = mpCurrentKF->GetVectorCovisibleKeyFrames(); + mvpCurrentConnectedKFs.push_back(mpCurrentKF); + + KeyFrameAndPose CorrectedSim3, NonCorrectedSim3; + CorrectedSim3[mpCurrentKF]=mg2oScw; + cv::Mat Twc = mpCurrentKF->GetPoseInverse(); + + + { + // Get Map Mutex + unique_lock lock(mpMap->mMutexMapUpdate); + + for(vector::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + + cv::Mat Tiw = pKFi->GetPose(); + + if(pKFi!=mpCurrentKF) + { + cv::Mat Tic = Tiw*Twc; + cv::Mat Ric = Tic.rowRange(0,3).colRange(0,3); + cv::Mat tic = Tic.rowRange(0,3).col(3); + g2o::Sim3 g2oSic(Converter::toMatrix3d(Ric),Converter::toVector3d(tic),1.0); + g2o::Sim3 g2oCorrectedSiw = g2oSic*mg2oScw; + //Pose corrected with the Sim3 of the loop closure + CorrectedSim3[pKFi]=g2oCorrectedSiw; + } + + cv::Mat Riw = Tiw.rowRange(0,3).colRange(0,3); + cv::Mat tiw = Tiw.rowRange(0,3).col(3); + g2o::Sim3 g2oSiw(Converter::toMatrix3d(Riw),Converter::toVector3d(tiw),1.0); + //Pose without correction + NonCorrectedSim3[pKFi]=g2oSiw; + } + + // Correct all MapPoints obsrved by current keyframe and neighbors, so that they align with the other side of the loop + for(KeyFrameAndPose::iterator mit=CorrectedSim3.begin(), mend=CorrectedSim3.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + g2o::Sim3 g2oCorrectedSiw = mit->second; + g2o::Sim3 g2oCorrectedSwi = g2oCorrectedSiw.inverse(); + + g2o::Sim3 g2oSiw =NonCorrectedSim3[pKFi]; + + vector vpMPsi = pKFi->GetMapPointMatches(); + for(size_t iMP=0, endMPi = vpMPsi.size(); iMPisBad()) + continue; + if(pMPi->mnCorrectedByKF==mpCurrentKF->mnId) + continue; + + // Project with non-corrected pose and project back with corrected pose + cv::Mat P3Dw = pMPi->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = g2oCorrectedSwi.map(g2oSiw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMPi->SetWorldPos(cvCorrectedP3Dw); + pMPi->mnCorrectedByKF = mpCurrentKF->mnId; + pMPi->mnCorrectedReference = pKFi->mnId; + pMPi->UpdateNormalAndDepth(); + } + + // Update keyframe pose with corrected Sim3. First transform Sim3 to SE3 (scale translation) + Eigen::Matrix3d eigR = g2oCorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = g2oCorrectedSiw.translation(); + double s = g2oCorrectedSiw.scale(); + + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat correctedTiw = Converter::toCvSE3(eigR,eigt); + + pKFi->SetPose(correctedTiw); + + // Make sure connections are updated + pKFi->UpdateConnections(); + } + + // Start Loop Fusion + // Update matched map points and replace if duplicated + for(size_t i=0; iGetMapPoint(i); + if(pCurMP) + pCurMP->Replace(pLoopMP); + else + { + mpCurrentKF->AddMapPoint(pLoopMP,i); + pLoopMP->AddObservation(mpCurrentKF,i); + pLoopMP->ComputeDistinctiveDescriptors(); + } + } + } + + } + + // Project MapPoints observed in the neighborhood of the loop keyframe + // into the current keyframe and neighbors using corrected poses. + // Fuse duplications. + SearchAndFuse(CorrectedSim3); + + + // After the MapPoint fusion, new links in the covisibility graph will appear attaching both sides of the loop + map > LoopConnections; + + for(vector::iterator vit=mvpCurrentConnectedKFs.begin(), vend=mvpCurrentConnectedKFs.end(); vit!=vend; vit++) + { + KeyFrame* pKFi = *vit; + vector vpPreviousNeighbors = pKFi->GetVectorCovisibleKeyFrames(); + + // Update connections. Detect new links. + pKFi->UpdateConnections(); + LoopConnections[pKFi]=pKFi->GetConnectedKeyFrames(); + for(vector::iterator vit_prev=vpPreviousNeighbors.begin(), vend_prev=vpPreviousNeighbors.end(); vit_prev!=vend_prev; vit_prev++) + { + LoopConnections[pKFi].erase(*vit_prev); + } + for(vector::iterator vit2=mvpCurrentConnectedKFs.begin(), vend2=mvpCurrentConnectedKFs.end(); vit2!=vend2; vit2++) + { + LoopConnections[pKFi].erase(*vit2); + } + } + + // Optimize graph + Optimizer::OptimizeEssentialGraph(mpMap, mpMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections, mbFixScale); + + // Add loop edge + mpMatchedKF->AddLoopEdge(mpCurrentKF); + mpCurrentKF->AddLoopEdge(mpMatchedKF); + + // Launch a new thread to perform Global Bundle Adjustment + mbRunningGBA = true; + mbFinishedGBA = false; + mbStopGBA = false; + mpThreadGBA = new thread(&LoopClosing::RunGlobalBundleAdjustment,this,mpCurrentKF->mnId); + + // Loop closed. Release Local Mapping. + mpLocalMapper->Release(); + + cout << "Loop Closed!" << endl; + + mLastLoopKFid = mpCurrentKF->mnId; +} + +void LoopClosing::SearchAndFuse(const KeyFrameAndPose &CorrectedPosesMap) +{ + ORBmatcher matcher(0.8); + + for(KeyFrameAndPose::const_iterator mit=CorrectedPosesMap.begin(), mend=CorrectedPosesMap.end(); mit!=mend;mit++) + { + KeyFrame* pKF = mit->first; + + g2o::Sim3 g2oScw = mit->second; + cv::Mat cvScw = Converter::toCvMat(g2oScw); + + vector vpReplacePoints(mvpLoopMapPoints.size(),static_cast(NULL)); + matcher.Fuse(pKF,cvScw,mvpLoopMapPoints,4,vpReplacePoints); + + // Get Map Mutex + unique_lock lock(mpMap->mMutexMapUpdate); + const int nLP = mvpLoopMapPoints.size(); + for(int i=0; iReplace(mvpLoopMapPoints[i]); + } + } + } +} + + +void LoopClosing::RequestReset() +{ + { + unique_lock lock(mMutexReset); + mbResetRequested = true; + } + + while(1) + { + { + unique_lock lock2(mMutexReset); + if(!mbResetRequested) + break; + } + usleep(5000); + } +} + +void LoopClosing::ResetIfRequested() +{ + unique_lock lock(mMutexReset); + if(mbResetRequested) + { + mlpLoopKeyFrameQueue.clear(); + mLastLoopKFid=0; + mbResetRequested=false; + } +} + +void LoopClosing::RunGlobalBundleAdjustment(unsigned long nLoopKF) +{ + cout << "Starting Global Bundle Adjustment" << endl; + + Optimizer::GlobalBundleAdjustemnt(mpMap,20,&mbStopGBA,nLoopKF,false); + + // Update all MapPoints and KeyFrames + // Local Mapping was active during BA, that means that there might be new keyframes + // not included in the Global BA and they are not consistent with the updated map. + // We need to propagate the correction through the spanning tree + { + unique_lock lock(mMutexGBA); + + + if(!mbStopGBA) + { + cout << "Global Bundle Adjustment finished" << endl; + cout << "Updating map ..." << endl; + mpLocalMapper->RequestStop(); + // Wait until Local Mapping has effectively stopped + + while(!mpLocalMapper->isStopped() && !mpLocalMapper->isFinished()) + { + usleep(1000); + } + + // Get Map Mutex + unique_lock lock(mpMap->mMutexMapUpdate); + + // Correct keyframes starting at map first keyframe + list lpKFtoCheck(mpMap->mvpKeyFrameOrigins.begin(),mpMap->mvpKeyFrameOrigins.end()); + + while(!lpKFtoCheck.empty()) + { + KeyFrame* pKF = lpKFtoCheck.front(); + const set sChilds = pKF->GetChilds(); + cv::Mat Twc = pKF->GetPoseInverse(); + for(set::const_iterator sit=sChilds.begin();sit!=sChilds.end();sit++) + { + KeyFrame* pChild = *sit; + if(pChild->mnBAGlobalForKF!=nLoopKF) + { + cv::Mat Tchildc = pChild->GetPose()*Twc; + pChild->mTcwGBA = Tchildc*pKF->mTcwGBA;//*Tcorc*pKF->mTcwGBA; + pChild->mnBAGlobalForKF=nLoopKF; + + } + lpKFtoCheck.push_back(pChild); + } + + pKF->mTcwBefGBA = pKF->GetPose(); + pKF->SetPose(pKF->mTcwGBA); + lpKFtoCheck.pop_front(); + } + + // Correct MapPoints + const vector vpMPs = mpMap->GetAllMapPoints(); + + for(size_t i=0; iisBad()) + continue; + + if(pMP->mnBAGlobalForKF==nLoopKF) + { + // If optimized by Global BA, just update + pMP->SetWorldPos(pMP->mPosGBA); + } + else + { + // Update according to the correction of its reference keyframe + KeyFrame* pRefKF = pMP->GetReferenceKeyFrame(); + + if(pRefKF->mnBAGlobalForKF!=nLoopKF) + continue; + + // Map to non-corrected camera + cv::Mat Rcw = pRefKF->mTcwBefGBA.rowRange(0,3).colRange(0,3); + cv::Mat tcw = pRefKF->mTcwBefGBA.rowRange(0,3).col(3); + cv::Mat Xc = Rcw*pMP->GetWorldPos()+tcw; + + // Backproject using corrected camera + cv::Mat Twc = pRefKF->GetPoseInverse(); + cv::Mat Rwc = Twc.rowRange(0,3).colRange(0,3); + cv::Mat twc = Twc.rowRange(0,3).col(3); + + pMP->SetWorldPos(Rwc*Xc+twc); + } + } + + mpLocalMapper->Release(); + + cout << "Map updated!" << endl; + } + + mbFinishedGBA = true; + mbRunningGBA = false; + } +} + +void LoopClosing::RequestFinish() +{ + unique_lock lock(mMutexFinish); + mbFinishRequested = true; +} + +bool LoopClosing::CheckFinish() +{ + unique_lock lock(mMutexFinish); + return mbFinishRequested; +} + +void LoopClosing::SetFinish() +{ + unique_lock lock(mMutexFinish); + mbFinished = true; +} + +bool LoopClosing::isFinished() +{ + unique_lock lock(mMutexFinish); + return mbFinished; +} + + +} //namespace ORB_SLAM diff --git a/src/Map.cc b/src/Map.cc new file mode 100644 index 0000000000..f285161644 --- /dev/null +++ b/src/Map.cc @@ -0,0 +1,121 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "Map.h" + +#include + +namespace ORB_SLAM2 +{ + +Map::Map():mnMaxKFid(0) +{ +} + +void Map::AddKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexMap); + mspKeyFrames.insert(pKF); + if(pKF->mnId>mnMaxKFid) + mnMaxKFid=pKF->mnId; +} + +void Map::AddMapPoint(MapPoint *pMP) +{ + unique_lock lock(mMutexMap); + mspMapPoints.insert(pMP); +} + +void Map::EraseMapPoint(MapPoint *pMP) +{ + unique_lock lock(mMutexMap); + mspMapPoints.erase(pMP); + + // TODO: This only erase the pointer. + // Delete the MapPoint +} + +void Map::EraseKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexMap); + mspKeyFrames.erase(pKF); + + // TODO: This only erase the pointer. + // Delete the MapPoint +} + +void Map::SetReferenceMapPoints(const vector &vpMPs) +{ + unique_lock lock(mMutexMap); + mvpReferenceMapPoints = vpMPs; +} + +vector Map::GetAllKeyFrames() +{ + unique_lock lock(mMutexMap); + return vector(mspKeyFrames.begin(),mspKeyFrames.end()); +} + +vector Map::GetAllMapPoints() +{ + unique_lock lock(mMutexMap); + return vector(mspMapPoints.begin(),mspMapPoints.end()); +} + +long unsigned int Map::MapPointsInMap() +{ + unique_lock lock(mMutexMap); + return mspMapPoints.size(); +} + +long unsigned int Map::KeyFramesInMap() +{ + unique_lock lock(mMutexMap); + return mspKeyFrames.size(); +} + +vector Map::GetReferenceMapPoints() +{ + unique_lock lock(mMutexMap); + return mvpReferenceMapPoints; +} + +long unsigned int Map::GetMaxKFid() +{ + unique_lock lock(mMutexMap); + return mnMaxKFid; +} + +void Map::clear() +{ + for(set::iterator sit=mspMapPoints.begin(), send=mspMapPoints.end(); sit!=send; sit++) + delete *sit; + + for(set::iterator sit=mspKeyFrames.begin(), send=mspKeyFrames.end(); sit!=send; sit++) + delete *sit; + + mspMapPoints.clear(); + mspKeyFrames.clear(); + mnMaxKFid = 0; + mvpReferenceMapPoints.clear(); + mvpKeyFrameOrigins.clear(); +} + +} //namespace ORB_SLAM diff --git a/src/MapDrawer.cc b/src/MapDrawer.cc new file mode 100644 index 0000000000..4d9990bc8a --- /dev/null +++ b/src/MapDrawer.cc @@ -0,0 +1,264 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "MapDrawer.h" +#include "MapPoint.h" +#include "KeyFrame.h" +#include +#include + +namespace ORB_SLAM2 +{ + + +MapDrawer::MapDrawer(Map* pMap, const string &strSettingPath):mpMap(pMap) +{ + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + + mKeyFrameSize = fSettings["Viewer.KeyFrameSize"]; + mKeyFrameLineWidth = fSettings["Viewer.KeyFrameLineWidth"]; + mGraphLineWidth = fSettings["Viewer.GraphLineWidth"]; + mPointSize = fSettings["Viewer.PointSize"]; + mCameraSize = fSettings["Viewer.CameraSize"]; + mCameraLineWidth = fSettings["Viewer.CameraLineWidth"]; + +} + +void MapDrawer::DrawMapPoints() +{ + const vector &vpMPs = mpMap->GetAllMapPoints(); + const vector &vpRefMPs = mpMap->GetReferenceMapPoints(); + + set spRefMPs(vpRefMPs.begin(), vpRefMPs.end()); + + if(vpMPs.empty()) + return; + + glPointSize(mPointSize); + glBegin(GL_POINTS); + glColor3f(0.0,0.0,0.0); + + for(size_t i=0, iend=vpMPs.size(); iisBad() || spRefMPs.count(vpMPs[i])) + continue; + cv::Mat pos = vpMPs[i]->GetWorldPos(); + glVertex3f(pos.at(0),pos.at(1),pos.at(2)); + } + glEnd(); + + glPointSize(mPointSize); + glBegin(GL_POINTS); + glColor3f(1.0,0.0,0.0); + + for(set::iterator sit=spRefMPs.begin(), send=spRefMPs.end(); sit!=send; sit++) + { + if((*sit)->isBad()) + continue; + cv::Mat pos = (*sit)->GetWorldPos(); + glVertex3f(pos.at(0),pos.at(1),pos.at(2)); + + } + + glEnd(); +} + +void MapDrawer::DrawKeyFrames(const bool bDrawKF, const bool bDrawGraph) +{ + const float &w = mKeyFrameSize; + const float h = w*0.75; + const float z = w*0.6; + + const vector vpKFs = mpMap->GetAllKeyFrames(); + + if(bDrawKF) + { + for(size_t i=0; iGetPoseInverse().t(); + + glPushMatrix(); + + glMultMatrixf(Twc.ptr(0)); + + glLineWidth(mKeyFrameLineWidth); + glColor3f(0.0f,0.0f,1.0f); + glBegin(GL_LINES); + glVertex3f(0,0,0); + glVertex3f(w,h,z); + glVertex3f(0,0,0); + glVertex3f(w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,h,z); + + glVertex3f(w,h,z); + glVertex3f(w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(-w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(w,h,z); + + glVertex3f(-w,-h,z); + glVertex3f(w,-h,z); + glEnd(); + + glPopMatrix(); + } + } + + if(bDrawGraph) + { + glLineWidth(mGraphLineWidth); + glColor4f(0.0f,1.0f,0.0f,0.6f); + glBegin(GL_LINES); + + for(size_t i=0; i vCovKFs = vpKFs[i]->GetCovisiblesByWeight(100); + cv::Mat Ow = vpKFs[i]->GetCameraCenter(); + if(!vCovKFs.empty()) + { + for(vector::const_iterator vit=vCovKFs.begin(), vend=vCovKFs.end(); vit!=vend; vit++) + { + if((*vit)->mnIdmnId) + continue; + cv::Mat Ow2 = (*vit)->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Ow2.at(0),Ow2.at(1),Ow2.at(2)); + } + } + + // Spanning tree + KeyFrame* pParent = vpKFs[i]->GetParent(); + if(pParent) + { + cv::Mat Owp = pParent->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Owp.at(0),Owp.at(1),Owp.at(2)); + } + + // Loops + set sLoopKFs = vpKFs[i]->GetLoopEdges(); + for(set::iterator sit=sLoopKFs.begin(), send=sLoopKFs.end(); sit!=send; sit++) + { + if((*sit)->mnIdmnId) + continue; + cv::Mat Owl = (*sit)->GetCameraCenter(); + glVertex3f(Ow.at(0),Ow.at(1),Ow.at(2)); + glVertex3f(Owl.at(0),Owl.at(1),Owl.at(2)); + } + } + + glEnd(); + } +} + +void MapDrawer::DrawCurrentCamera(pangolin::OpenGlMatrix &Twc) +{ + const float &w = mCameraSize; + const float h = w*0.75; + const float z = w*0.6; + + glPushMatrix(); + +#ifdef HAVE_GLES + glMultMatrixf(Twc.m); +#else + glMultMatrixd(Twc.m); +#endif + + glLineWidth(mCameraLineWidth); + glColor3f(0.0f,1.0f,0.0f); + glBegin(GL_LINES); + glVertex3f(0,0,0); + glVertex3f(w,h,z); + glVertex3f(0,0,0); + glVertex3f(w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,-h,z); + glVertex3f(0,0,0); + glVertex3f(-w,h,z); + + glVertex3f(w,h,z); + glVertex3f(w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(-w,-h,z); + + glVertex3f(-w,h,z); + glVertex3f(w,h,z); + + glVertex3f(-w,-h,z); + glVertex3f(w,-h,z); + glEnd(); + + glPopMatrix(); +} + + +void MapDrawer::SetCurrentCameraPose(const cv::Mat &Tcw) +{ + unique_lock lock(mMutexCamera); + mCameraPose = Tcw.clone(); +} + +void MapDrawer::GetCurrentOpenGLCameraMatrix(pangolin::OpenGlMatrix &M) +{ + if(!mCameraPose.empty()) + { + cv::Mat Rwc(3,3,CV_32F); + cv::Mat twc(3,1,CV_32F); + { + unique_lock lock(mMutexCamera); + Rwc = mCameraPose.rowRange(0,3).colRange(0,3).t(); + twc = -Rwc*mCameraPose.rowRange(0,3).col(3); + } + + M.m[0] = Rwc.at(0,0); + M.m[1] = Rwc.at(1,0); + M.m[2] = Rwc.at(2,0); + M.m[3] = 0.0; + + M.m[4] = Rwc.at(0,1); + M.m[5] = Rwc.at(1,1); + M.m[6] = Rwc.at(2,1); + M.m[7] = 0.0; + + M.m[8] = Rwc.at(0,2); + M.m[9] = Rwc.at(1,2); + M.m[10] = Rwc.at(2,2); + M.m[11] = 0.0; + + M.m[12] = twc.at(0); + M.m[13] = twc.at(1); + M.m[14] = twc.at(2); + M.m[15] = 1.0; + } + else + M.SetIdentity(); +} + +} //namespace ORB_SLAM diff --git a/src/MapPoint.cc b/src/MapPoint.cc new file mode 100644 index 0000000000..ec41ddbc8b --- /dev/null +++ b/src/MapPoint.cc @@ -0,0 +1,396 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "MapPoint.h" +#include "ORBmatcher.h" + +#include + +namespace ORB_SLAM2 +{ + +long unsigned int MapPoint::nNextId=0; +mutex MapPoint::mGlobalMutex; + +MapPoint::MapPoint(const cv::Mat &Pos, KeyFrame *pRefKF, Map* pMap): + mnFirstKFid(pRefKF->mnId), mnFirstFrame(pRefKF->mnFrameId), nObs(0), mnTrackReferenceForFrame(0), + mnLastFrameSeen(0), mnBALocalForKF(0), mnFuseCandidateForKF(0), mnLoopPointForKF(0), mnCorrectedByKF(0), + mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(pRefKF), mnVisible(1), mnFound(1), mbBad(false), + mpReplaced(static_cast(NULL)), mfMinDistance(0), mfMaxDistance(0), mpMap(pMap) +{ + Pos.copyTo(mWorldPos); + mNormalVector = cv::Mat::zeros(3,1,CV_32F); + + // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id. + unique_lock lock(mpMap->mMutexPointCreation); + mnId=nNextId++; +} + +MapPoint::MapPoint(const cv::Mat &Pos, Map* pMap, Frame* pFrame, const int &idxF): + mnFirstKFid(-1), mnFirstFrame(pFrame->mnId), nObs(0), mnTrackReferenceForFrame(0), mnLastFrameSeen(0), + mnBALocalForKF(0), mnFuseCandidateForKF(0),mnLoopPointForKF(0), mnCorrectedByKF(0), + mnCorrectedReference(0), mnBAGlobalForKF(0), mpRefKF(static_cast(NULL)), mnVisible(1), + mnFound(1), mbBad(false), mpReplaced(NULL), mpMap(pMap) +{ + Pos.copyTo(mWorldPos); + cv::Mat Ow = pFrame->GetCameraCenter(); + mNormalVector = mWorldPos - Ow; + mNormalVector = mNormalVector/cv::norm(mNormalVector); + + cv::Mat PC = Pos - Ow; + const float dist = cv::norm(PC); + const int level = pFrame->mvKeysUn[idxF].octave; + const float levelScaleFactor = pFrame->mvScaleFactors[level]; + const int nLevels = pFrame->mnScaleLevels; + + mfMaxDistance = dist*levelScaleFactor; + mfMinDistance = mfMaxDistance/pFrame->mvScaleFactors[nLevels-1]; + + pFrame->mDescriptors.row(idxF).copyTo(mDescriptor); + + // MapPoints can be created from Tracking and Local Mapping. This mutex avoid conflicts with id. + unique_lock lock(mpMap->mMutexPointCreation); + mnId=nNextId++; +} + +void MapPoint::SetWorldPos(const cv::Mat &Pos) +{ + unique_lock lock2(mGlobalMutex); + unique_lock lock(mMutexPos); + Pos.copyTo(mWorldPos); +} + +cv::Mat MapPoint::GetWorldPos() +{ + unique_lock lock(mMutexPos); + return mWorldPos.clone(); +} + +cv::Mat MapPoint::GetNormal() +{ + unique_lock lock(mMutexPos); + return mNormalVector.clone(); +} + +KeyFrame* MapPoint::GetReferenceKeyFrame() +{ + unique_lock lock(mMutexFeatures); + return mpRefKF; +} + +void MapPoint::AddObservation(KeyFrame* pKF, size_t idx) +{ + unique_lock lock(mMutexFeatures); + if(mObservations.count(pKF)) + return; + mObservations[pKF]=idx; + + if(pKF->mvuRight[idx]>=0) + nObs+=2; + else + nObs++; +} + +void MapPoint::EraseObservation(KeyFrame* pKF) +{ + bool bBad=false; + { + unique_lock lock(mMutexFeatures); + if(mObservations.count(pKF)) + { + int idx = mObservations[pKF]; + if(pKF->mvuRight[idx]>=0) + nObs-=2; + else + nObs--; + + mObservations.erase(pKF); + + if(mpRefKF==pKF) + mpRefKF=mObservations.begin()->first; + + // If only 2 observations or less, discard point + if(nObs<=2) + bBad=true; + } + } + + if(bBad) + SetBadFlag(); +} + +map MapPoint::GetObservations() +{ + unique_lock lock(mMutexFeatures); + return mObservations; +} + +int MapPoint::Observations() +{ + unique_lock lock(mMutexFeatures); + return nObs; +} + +void MapPoint::SetBadFlag() +{ + map obs; + { + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + mbBad=true; + obs = mObservations; + mObservations.clear(); + } + for(map::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + pKF->EraseMapPointMatch(mit->second); + } + + mpMap->EraseMapPoint(this); +} + +MapPoint* MapPoint::GetReplaced() +{ + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + return mpReplaced; +} + +void MapPoint::Replace(MapPoint* pMP) +{ + if(pMP->mnId==this->mnId) + return; + + int nvisible, nfound; + map obs; + { + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + obs=mObservations; + mObservations.clear(); + mbBad=true; + nvisible = mnVisible; + nfound = mnFound; + mpReplaced = pMP; + } + + for(map::iterator mit=obs.begin(), mend=obs.end(); mit!=mend; mit++) + { + // Replace measurement in keyframe + KeyFrame* pKF = mit->first; + + if(!pMP->IsInKeyFrame(pKF)) + { + pKF->ReplaceMapPointMatch(mit->second, pMP); + pMP->AddObservation(pKF,mit->second); + } + else + { + pKF->EraseMapPointMatch(mit->second); + } + } + pMP->IncreaseFound(nfound); + pMP->IncreaseVisible(nvisible); + pMP->ComputeDistinctiveDescriptors(); + + mpMap->EraseMapPoint(this); +} + +bool MapPoint::isBad() +{ + unique_lock lock(mMutexFeatures); + unique_lock lock2(mMutexPos); + return mbBad; +} + +void MapPoint::IncreaseVisible(int n) +{ + unique_lock lock(mMutexFeatures); + mnVisible+=n; +} + +void MapPoint::IncreaseFound(int n) +{ + unique_lock lock(mMutexFeatures); + mnFound+=n; +} + +float MapPoint::GetFoundRatio() +{ + unique_lock lock(mMutexFeatures); + return static_cast(mnFound)/mnVisible; +} + +void MapPoint::ComputeDistinctiveDescriptors() +{ + // Retrieve all observed descriptors + vector vDescriptors; + + map observations; + + { + unique_lock lock1(mMutexFeatures); + if(mbBad) + return; + observations=mObservations; + } + + if(observations.empty()) + return; + + vDescriptors.reserve(observations.size()); + + for(map::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + + if(!pKF->isBad()) + vDescriptors.push_back(pKF->mDescriptors.row(mit->second)); + } + + if(vDescriptors.empty()) + return; + + // Compute distances between them + const size_t N = vDescriptors.size(); + + float Distances[N][N]; + for(size_t i=0;i vDists(Distances[i],Distances[i]+N); + sort(vDists.begin(),vDists.end()); + int median = vDists[0.5*(N-1)]; + + if(median lock(mMutexFeatures); + mDescriptor = vDescriptors[BestIdx].clone(); + } +} + +cv::Mat MapPoint::GetDescriptor() +{ + unique_lock lock(mMutexFeatures); + return mDescriptor.clone(); +} + +int MapPoint::GetIndexInKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexFeatures); + if(mObservations.count(pKF)) + return mObservations[pKF]; + else + return -1; +} + +bool MapPoint::IsInKeyFrame(KeyFrame *pKF) +{ + unique_lock lock(mMutexFeatures); + return (mObservations.count(pKF)); +} + +void MapPoint::UpdateNormalAndDepth() +{ + map observations; + KeyFrame* pRefKF; + cv::Mat Pos; + { + unique_lock lock1(mMutexFeatures); + unique_lock lock2(mMutexPos); + if(mbBad) + return; + observations=mObservations; + pRefKF=mpRefKF; + Pos = mWorldPos.clone(); + } + + if(observations.empty()) + return; + + cv::Mat normal = cv::Mat::zeros(3,1,CV_32F); + int n=0; + for(map::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + cv::Mat Owi = pKF->GetCameraCenter(); + cv::Mat normali = mWorldPos - Owi; + normal = normal + normali/cv::norm(normali); + n++; + } + + cv::Mat PC = Pos - pRefKF->GetCameraCenter(); + const float dist = cv::norm(PC); + const int level = pRefKF->mvKeysUn[observations[pRefKF]].octave; + const float levelScaleFactor = pRefKF->mvScaleFactors[level]; + const int nLevels = pRefKF->mnScaleLevels; + + { + unique_lock lock3(mMutexPos); + mfMaxDistance = dist*levelScaleFactor; + mfMinDistance = mfMaxDistance/pRefKF->mvScaleFactors[nLevels-1]; + mNormalVector = normal/n; + } +} + +float MapPoint::GetMinDistanceInvariance() +{ + unique_lock lock(mMutexPos); + return 0.8f*mfMinDistance; +} + +float MapPoint::GetMaxDistanceInvariance() +{ + unique_lock lock(mMutexPos); + return 1.2f*mfMaxDistance; +} + +int MapPoint::PredictScale(const float ¤tDist, const float &logScaleFactor) +{ + float ratio; + { + unique_lock lock3(mMutexPos); + ratio = mfMaxDistance/currentDist; + } + + return ceil(log(ratio)/logScaleFactor); +} + +} //namespace ORB_SLAM diff --git a/src/ORBextractor.cc b/src/ORBextractor.cc new file mode 100644 index 0000000000..d3b556a598 --- /dev/null +++ b/src/ORBextractor.cc @@ -0,0 +1,1132 @@ +/** +* This file is part of ORB-SLAM2. +* This file is based on the file orb.cpp from the OpenCV library (see BSD license below). +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ +/** +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* +*/ + + +#include +#include +#include + +#include "ORBextractor.h" + + +using namespace cv; +using namespace std; + +namespace ORB_SLAM2 +{ + +const int PATCH_SIZE = 31; +const int HALF_PATCH_SIZE = 15; +const int EDGE_THRESHOLD = 19; + + +static float IC_Angle(const Mat& image, Point2f pt, const vector & u_max) +{ + int m_01 = 0, m_10 = 0; + + const uchar* center = &image.at (cvRound(pt.y), cvRound(pt.x)); + + // Treat the center line differently, v=0 + for (int u = -HALF_PATCH_SIZE; u <= HALF_PATCH_SIZE; ++u) + m_10 += u * center[u]; + + // Go line by line in the circuI853lar patch + int step = (int)image.step1(); + for (int v = 1; v <= HALF_PATCH_SIZE; ++v) + { + // Proceed over the two lines + int v_sum = 0; + int d = u_max[v]; + for (int u = -d; u <= d; ++u) + { + int val_plus = center[u + v*step], val_minus = center[u - v*step]; + v_sum += (val_plus - val_minus); + m_10 += u * (val_plus + val_minus); + } + m_01 += v * v_sum; + } + + return fastAtan2((float)m_01, (float)m_10); +} + + +const float factorPI = (float)(CV_PI/180.f); +static void computeOrbDescriptor(const KeyPoint& kpt, + const Mat& img, const Point* pattern, + uchar* desc) +{ + float angle = (float)kpt.angle*factorPI; + float a = (float)cos(angle), b = (float)sin(angle); + + const uchar* center = &img.at(cvRound(kpt.pt.y), cvRound(kpt.pt.x)); + const int step = (int)img.step; + + #define GET_VALUE(idx) \ + center[cvRound(pattern[idx].x*b + pattern[idx].y*a)*step + \ + cvRound(pattern[idx].x*a - pattern[idx].y*b)] + + + for (int i = 0; i < 32; ++i, pattern += 16) + { + int t0, t1, val; + t0 = GET_VALUE(0); t1 = GET_VALUE(1); + val = t0 < t1; + t0 = GET_VALUE(2); t1 = GET_VALUE(3); + val |= (t0 < t1) << 1; + t0 = GET_VALUE(4); t1 = GET_VALUE(5); + val |= (t0 < t1) << 2; + t0 = GET_VALUE(6); t1 = GET_VALUE(7); + val |= (t0 < t1) << 3; + t0 = GET_VALUE(8); t1 = GET_VALUE(9); + val |= (t0 < t1) << 4; + t0 = GET_VALUE(10); t1 = GET_VALUE(11); + val |= (t0 < t1) << 5; + t0 = GET_VALUE(12); t1 = GET_VALUE(13); + val |= (t0 < t1) << 6; + t0 = GET_VALUE(14); t1 = GET_VALUE(15); + val |= (t0 < t1) << 7; + + desc[i] = (uchar)val; + } + + #undef GET_VALUE +} + + +static int bit_pattern_31_[256*4] = +{ + 8,-3, 9,5/*mean (0), correlation (0)*/, + 4,2, 7,-12/*mean (1.12461e-05), correlation (0.0437584)*/, + -11,9, -8,2/*mean (3.37382e-05), correlation (0.0617409)*/, + 7,-12, 12,-13/*mean (5.62303e-05), correlation (0.0636977)*/, + 2,-13, 2,12/*mean (0.000134953), correlation (0.085099)*/, + 1,-7, 1,6/*mean (0.000528565), correlation (0.0857175)*/, + -2,-10, -2,-4/*mean (0.0188821), correlation (0.0985774)*/, + -13,-13, -11,-8/*mean (0.0363135), correlation (0.0899616)*/, + -13,-3, -12,-9/*mean (0.121806), correlation (0.099849)*/, + 10,4, 11,9/*mean (0.122065), correlation (0.093285)*/, + -13,-8, -8,-9/*mean (0.162787), correlation (0.0942748)*/, + -11,7, -9,12/*mean (0.21561), correlation (0.0974438)*/, + 7,7, 12,6/*mean (0.160583), correlation (0.130064)*/, + -4,-5, -3,0/*mean (0.228171), correlation (0.132998)*/, + -13,2, -12,-3/*mean (0.00997526), correlation (0.145926)*/, + -9,0, -7,5/*mean (0.198234), correlation (0.143636)*/, + 12,-6, 12,-1/*mean (0.0676226), correlation (0.16689)*/, + -3,6, -2,12/*mean (0.166847), correlation (0.171682)*/, + -6,-13, -4,-8/*mean (0.101215), correlation (0.179716)*/, + 11,-13, 12,-8/*mean (0.200641), correlation (0.192279)*/, + 4,7, 5,1/*mean (0.205106), correlation (0.186848)*/, + 5,-3, 10,-3/*mean (0.234908), correlation (0.192319)*/, + 3,-7, 6,12/*mean (0.0709964), correlation (0.210872)*/, + -8,-7, -6,-2/*mean (0.0939834), correlation (0.212589)*/, + -2,11, -1,-10/*mean (0.127778), correlation (0.20866)*/, + -13,12, -8,10/*mean (0.14783), correlation (0.206356)*/, + -7,3, -5,-3/*mean (0.182141), correlation (0.198942)*/, + -4,2, -3,7/*mean (0.188237), correlation (0.21384)*/, + -10,-12, -6,11/*mean (0.14865), correlation (0.23571)*/, + 5,-12, 6,-7/*mean (0.222312), correlation (0.23324)*/, + 5,-6, 7,-1/*mean (0.229082), correlation (0.23389)*/, + 1,0, 4,-5/*mean (0.241577), correlation (0.215286)*/, + 9,11, 11,-13/*mean (0.00338507), correlation (0.251373)*/, + 4,7, 4,12/*mean (0.131005), correlation (0.257622)*/, + 2,-1, 4,4/*mean (0.152755), correlation (0.255205)*/, + -4,-12, -2,7/*mean (0.182771), correlation (0.244867)*/, + -8,-5, -7,-10/*mean (0.186898), correlation (0.23901)*/, + 4,11, 9,12/*mean (0.226226), correlation (0.258255)*/, + 0,-8, 1,-13/*mean (0.0897886), correlation (0.274827)*/, + -13,-2, -8,2/*mean (0.148774), correlation (0.28065)*/, + -3,-2, -2,3/*mean (0.153048), correlation (0.283063)*/, + -6,9, -4,-9/*mean (0.169523), correlation (0.278248)*/, + 8,12, 10,7/*mean (0.225337), correlation (0.282851)*/, + 0,9, 1,3/*mean (0.226687), correlation (0.278734)*/, + 7,-5, 11,-10/*mean (0.00693882), correlation (0.305161)*/, + -13,-6, -11,0/*mean (0.0227283), correlation (0.300181)*/, + 10,7, 12,1/*mean (0.125517), correlation (0.31089)*/, + -6,-3, -6,12/*mean (0.131748), correlation (0.312779)*/, + 10,-9, 12,-4/*mean (0.144827), correlation (0.292797)*/, + -13,8, -8,-12/*mean (0.149202), correlation (0.308918)*/, + -13,0, -8,-4/*mean (0.160909), correlation (0.310013)*/, + 3,3, 7,8/*mean (0.177755), correlation (0.309394)*/, + 5,7, 10,-7/*mean (0.212337), correlation (0.310315)*/, + -1,7, 1,-12/*mean (0.214429), correlation (0.311933)*/, + 3,-10, 5,6/*mean (0.235807), correlation (0.313104)*/, + 2,-4, 3,-10/*mean (0.00494827), correlation (0.344948)*/, + -13,0, -13,5/*mean (0.0549145), correlation (0.344675)*/, + -13,-7, -12,12/*mean (0.103385), correlation (0.342715)*/, + -13,3, -11,8/*mean (0.134222), correlation (0.322922)*/, + -7,12, -4,7/*mean (0.153284), correlation (0.337061)*/, + 6,-10, 12,8/*mean (0.154881), correlation (0.329257)*/, + -9,-1, -7,-6/*mean (0.200967), correlation (0.33312)*/, + -2,-5, 0,12/*mean (0.201518), correlation (0.340635)*/, + -12,5, -7,5/*mean (0.207805), correlation (0.335631)*/, + 3,-10, 8,-13/*mean (0.224438), correlation (0.34504)*/, + -7,-7, -4,5/*mean (0.239361), correlation (0.338053)*/, + -3,-2, -1,-7/*mean (0.240744), correlation (0.344322)*/, + 2,9, 5,-11/*mean (0.242949), correlation (0.34145)*/, + -11,-13, -5,-13/*mean (0.244028), correlation (0.336861)*/, + -1,6, 0,-1/*mean (0.247571), correlation (0.343684)*/, + 5,-3, 5,2/*mean (0.000697256), correlation (0.357265)*/, + -4,-13, -4,12/*mean (0.00213675), correlation (0.373827)*/, + -9,-6, -9,6/*mean (0.0126856), correlation (0.373938)*/, + -12,-10, -8,-4/*mean (0.0152497), correlation (0.364237)*/, + 10,2, 12,-3/*mean (0.0299933), correlation (0.345292)*/, + 7,12, 12,12/*mean (0.0307242), correlation (0.366299)*/, + -7,-13, -6,5/*mean (0.0534975), correlation (0.368357)*/, + -4,9, -3,4/*mean (0.099865), correlation (0.372276)*/, + 7,-1, 12,2/*mean (0.117083), correlation (0.364529)*/, + -7,6, -5,1/*mean (0.126125), correlation (0.369606)*/, + -13,11, -12,5/*mean (0.130364), correlation (0.358502)*/, + -3,7, -2,-6/*mean (0.131691), correlation (0.375531)*/, + 7,-8, 12,-7/*mean (0.160166), correlation (0.379508)*/, + -13,-7, -11,-12/*mean (0.167848), correlation (0.353343)*/, + 1,-3, 12,12/*mean (0.183378), correlation (0.371916)*/, + 2,-6, 3,0/*mean (0.228711), correlation (0.371761)*/, + -4,3, -2,-13/*mean (0.247211), correlation (0.364063)*/, + -1,-13, 1,9/*mean (0.249325), correlation (0.378139)*/, + 7,1, 8,-6/*mean (0.000652272), correlation (0.411682)*/, + 1,-1, 3,12/*mean (0.00248538), correlation (0.392988)*/, + 9,1, 12,6/*mean (0.0206815), correlation (0.386106)*/, + -1,-9, -1,3/*mean (0.0364485), correlation (0.410752)*/, + -13,-13, -10,5/*mean (0.0376068), correlation (0.398374)*/, + 7,7, 10,12/*mean (0.0424202), correlation (0.405663)*/, + 12,-5, 12,9/*mean (0.0942645), correlation (0.410422)*/, + 6,3, 7,11/*mean (0.1074), correlation (0.413224)*/, + 5,-13, 6,10/*mean (0.109256), correlation (0.408646)*/, + 2,-12, 2,3/*mean (0.131691), correlation (0.416076)*/, + 3,8, 4,-6/*mean (0.165081), correlation (0.417569)*/, + 2,6, 12,-13/*mean (0.171874), correlation (0.408471)*/, + 9,-12, 10,3/*mean (0.175146), correlation (0.41296)*/, + -8,4, -7,9/*mean (0.183682), correlation (0.402956)*/, + -11,12, -4,-6/*mean (0.184672), correlation (0.416125)*/, + 1,12, 2,-8/*mean (0.191487), correlation (0.386696)*/, + 6,-9, 7,-4/*mean (0.192668), correlation (0.394771)*/, + 2,3, 3,-2/*mean (0.200157), correlation (0.408303)*/, + 6,3, 11,0/*mean (0.204588), correlation (0.411762)*/, + 3,-3, 8,-8/*mean (0.205904), correlation (0.416294)*/, + 7,8, 9,3/*mean (0.213237), correlation (0.409306)*/, + -11,-5, -6,-4/*mean (0.243444), correlation (0.395069)*/, + -10,11, -5,10/*mean (0.247672), correlation (0.413392)*/, + -5,-8, -3,12/*mean (0.24774), correlation (0.411416)*/, + -10,5, -9,0/*mean (0.00213675), correlation (0.454003)*/, + 8,-1, 12,-6/*mean (0.0293635), correlation (0.455368)*/, + 4,-6, 6,-11/*mean (0.0404971), correlation (0.457393)*/, + -10,12, -8,7/*mean (0.0481107), correlation (0.448364)*/, + 4,-2, 6,7/*mean (0.050641), correlation (0.455019)*/, + -2,0, -2,12/*mean (0.0525978), correlation (0.44338)*/, + -5,-8, -5,2/*mean (0.0629667), correlation (0.457096)*/, + 7,-6, 10,12/*mean (0.0653846), correlation (0.445623)*/, + -9,-13, -8,-8/*mean (0.0858749), correlation (0.449789)*/, + -5,-13, -5,-2/*mean (0.122402), correlation (0.450201)*/, + 8,-8, 9,-13/*mean (0.125416), correlation (0.453224)*/, + -9,-11, -9,0/*mean (0.130128), correlation (0.458724)*/, + 1,-8, 1,-2/*mean (0.132467), correlation (0.440133)*/, + 7,-4, 9,1/*mean (0.132692), correlation (0.454)*/, + -2,1, -1,-4/*mean (0.135695), correlation (0.455739)*/, + 11,-6, 12,-11/*mean (0.142904), correlation (0.446114)*/, + -12,-9, -6,4/*mean (0.146165), correlation (0.451473)*/, + 3,7, 7,12/*mean (0.147627), correlation (0.456643)*/, + 5,5, 10,8/*mean (0.152901), correlation (0.455036)*/, + 0,-4, 2,8/*mean (0.167083), correlation (0.459315)*/, + -9,12, -5,-13/*mean (0.173234), correlation (0.454706)*/, + 0,7, 2,12/*mean (0.18312), correlation (0.433855)*/, + -1,2, 1,7/*mean (0.185504), correlation (0.443838)*/, + 5,11, 7,-9/*mean (0.185706), correlation (0.451123)*/, + 3,5, 6,-8/*mean (0.188968), correlation (0.455808)*/, + -13,-4, -8,9/*mean (0.191667), correlation (0.459128)*/, + -5,9, -3,-3/*mean (0.193196), correlation (0.458364)*/, + -4,-7, -3,-12/*mean (0.196536), correlation (0.455782)*/, + 6,5, 8,0/*mean (0.1972), correlation (0.450481)*/, + -7,6, -6,12/*mean (0.199438), correlation (0.458156)*/, + -13,6, -5,-2/*mean (0.211224), correlation (0.449548)*/, + 1,-10, 3,10/*mean (0.211718), correlation (0.440606)*/, + 4,1, 8,-4/*mean (0.213034), correlation (0.443177)*/, + -2,-2, 2,-13/*mean (0.234334), correlation (0.455304)*/, + 2,-12, 12,12/*mean (0.235684), correlation (0.443436)*/, + -2,-13, 0,-6/*mean (0.237674), correlation (0.452525)*/, + 4,1, 9,3/*mean (0.23962), correlation (0.444824)*/, + -6,-10, -3,-5/*mean (0.248459), correlation (0.439621)*/, + -3,-13, -1,1/*mean (0.249505), correlation (0.456666)*/, + 7,5, 12,-11/*mean (0.00119208), correlation (0.495466)*/, + 4,-2, 5,-7/*mean (0.00372245), correlation (0.484214)*/, + -13,9, -9,-5/*mean (0.00741116), correlation (0.499854)*/, + 7,1, 8,6/*mean (0.0208952), correlation (0.499773)*/, + 7,-8, 7,6/*mean (0.0220085), correlation (0.501609)*/, + -7,-4, -7,1/*mean (0.0233806), correlation (0.496568)*/, + -8,11, -7,-8/*mean (0.0236505), correlation (0.489719)*/, + -13,6, -12,-8/*mean (0.0268781), correlation (0.503487)*/, + 2,4, 3,9/*mean (0.0323324), correlation (0.501938)*/, + 10,-5, 12,3/*mean (0.0399235), correlation (0.494029)*/, + -6,-5, -6,7/*mean (0.0420153), correlation (0.486579)*/, + 8,-3, 9,-8/*mean (0.0548021), correlation (0.484237)*/, + 2,-12, 2,8/*mean (0.0616622), correlation (0.496642)*/, + -11,-2, -10,3/*mean (0.0627755), correlation (0.498563)*/, + -12,-13, -7,-9/*mean (0.0829622), correlation (0.495491)*/, + -11,0, -10,-5/*mean (0.0843342), correlation (0.487146)*/, + 5,-3, 11,8/*mean (0.0929937), correlation (0.502315)*/, + -2,-13, -1,12/*mean (0.113327), correlation (0.48941)*/, + -1,-8, 0,9/*mean (0.132119), correlation (0.467268)*/, + -13,-11, -12,-5/*mean (0.136269), correlation (0.498771)*/, + -10,-2, -10,11/*mean (0.142173), correlation (0.498714)*/, + -3,9, -2,-13/*mean (0.144141), correlation (0.491973)*/, + 2,-3, 3,2/*mean (0.14892), correlation (0.500782)*/, + -9,-13, -4,0/*mean (0.150371), correlation (0.498211)*/, + -4,6, -3,-10/*mean (0.152159), correlation (0.495547)*/, + -4,12, -2,-7/*mean (0.156152), correlation (0.496925)*/, + -6,-11, -4,9/*mean (0.15749), correlation (0.499222)*/, + 6,-3, 6,11/*mean (0.159211), correlation (0.503821)*/, + -13,11, -5,5/*mean (0.162427), correlation (0.501907)*/, + 11,11, 12,6/*mean (0.16652), correlation (0.497632)*/, + 7,-5, 12,-2/*mean (0.169141), correlation (0.484474)*/, + -1,12, 0,7/*mean (0.169456), correlation (0.495339)*/, + -4,-8, -3,-2/*mean (0.171457), correlation (0.487251)*/, + -7,1, -6,7/*mean (0.175), correlation (0.500024)*/, + -13,-12, -8,-13/*mean (0.175866), correlation (0.497523)*/, + -7,-2, -6,-8/*mean (0.178273), correlation (0.501854)*/, + -8,5, -6,-9/*mean (0.181107), correlation (0.494888)*/, + -5,-1, -4,5/*mean (0.190227), correlation (0.482557)*/, + -13,7, -8,10/*mean (0.196739), correlation (0.496503)*/, + 1,5, 5,-13/*mean (0.19973), correlation (0.499759)*/, + 1,0, 10,-13/*mean (0.204465), correlation (0.49873)*/, + 9,12, 10,-1/*mean (0.209334), correlation (0.49063)*/, + 5,-8, 10,-9/*mean (0.211134), correlation (0.503011)*/, + -1,11, 1,-13/*mean (0.212), correlation (0.499414)*/, + -9,-3, -6,2/*mean (0.212168), correlation (0.480739)*/, + -1,-10, 1,12/*mean (0.212731), correlation (0.502523)*/, + -13,1, -8,-10/*mean (0.21327), correlation (0.489786)*/, + 8,-11, 10,-6/*mean (0.214159), correlation (0.488246)*/, + 2,-13, 3,-6/*mean (0.216993), correlation (0.50287)*/, + 7,-13, 12,-9/*mean (0.223639), correlation (0.470502)*/, + -10,-10, -5,-7/*mean (0.224089), correlation (0.500852)*/, + -10,-8, -8,-13/*mean (0.228666), correlation (0.502629)*/, + 4,-6, 8,5/*mean (0.22906), correlation (0.498305)*/, + 3,12, 8,-13/*mean (0.233378), correlation (0.503825)*/, + -4,2, -3,-3/*mean (0.234323), correlation (0.476692)*/, + 5,-13, 10,-12/*mean (0.236392), correlation (0.475462)*/, + 4,-13, 5,-1/*mean (0.236842), correlation (0.504132)*/, + -9,9, -4,3/*mean (0.236977), correlation (0.497739)*/, + 0,3, 3,-9/*mean (0.24314), correlation (0.499398)*/, + -12,1, -6,1/*mean (0.243297), correlation (0.489447)*/, + 3,2, 4,-8/*mean (0.00155196), correlation (0.553496)*/, + -10,-10, -10,9/*mean (0.00239541), correlation (0.54297)*/, + 8,-13, 12,12/*mean (0.0034413), correlation (0.544361)*/, + -8,-12, -6,-5/*mean (0.003565), correlation (0.551225)*/, + 2,2, 3,7/*mean (0.00835583), correlation (0.55285)*/, + 10,6, 11,-8/*mean (0.00885065), correlation (0.540913)*/, + 6,8, 8,-12/*mean (0.0101552), correlation (0.551085)*/, + -7,10, -6,5/*mean (0.0102227), correlation (0.533635)*/, + -3,-9, -3,9/*mean (0.0110211), correlation (0.543121)*/, + -1,-13, -1,5/*mean (0.0113473), correlation (0.550173)*/, + -3,-7, -3,4/*mean (0.0140913), correlation (0.554774)*/, + -8,-2, -8,3/*mean (0.017049), correlation (0.55461)*/, + 4,2, 12,12/*mean (0.01778), correlation (0.546921)*/, + 2,-5, 3,11/*mean (0.0224022), correlation (0.549667)*/, + 6,-9, 11,-13/*mean (0.029161), correlation (0.546295)*/, + 3,-1, 7,12/*mean (0.0303081), correlation (0.548599)*/, + 11,-1, 12,4/*mean (0.0355151), correlation (0.523943)*/, + -3,0, -3,6/*mean (0.0417904), correlation (0.543395)*/, + 4,-11, 4,12/*mean (0.0487292), correlation (0.542818)*/, + 2,-4, 2,1/*mean (0.0575124), correlation (0.554888)*/, + -10,-6, -8,1/*mean (0.0594242), correlation (0.544026)*/, + -13,7, -11,1/*mean (0.0597391), correlation (0.550524)*/, + -13,12, -11,-13/*mean (0.0608974), correlation (0.55383)*/, + 6,0, 11,-13/*mean (0.065126), correlation (0.552006)*/, + 0,-1, 1,4/*mean (0.074224), correlation (0.546372)*/, + -13,3, -9,-2/*mean (0.0808592), correlation (0.554875)*/, + -9,8, -6,-3/*mean (0.0883378), correlation (0.551178)*/, + -13,-6, -8,-2/*mean (0.0901035), correlation (0.548446)*/, + 5,-9, 8,10/*mean (0.0949843), correlation (0.554694)*/, + 2,7, 3,-9/*mean (0.0994152), correlation (0.550979)*/, + -1,-6, -1,-1/*mean (0.10045), correlation (0.552714)*/, + 9,5, 11,-2/*mean (0.100686), correlation (0.552594)*/, + 11,-3, 12,-8/*mean (0.101091), correlation (0.532394)*/, + 3,0, 3,5/*mean (0.101147), correlation (0.525576)*/, + -1,4, 0,10/*mean (0.105263), correlation (0.531498)*/, + 3,-6, 4,5/*mean (0.110785), correlation (0.540491)*/, + -13,0, -10,5/*mean (0.112798), correlation (0.536582)*/, + 5,8, 12,11/*mean (0.114181), correlation (0.555793)*/, + 8,9, 9,-6/*mean (0.117431), correlation (0.553763)*/, + 7,-4, 8,-12/*mean (0.118522), correlation (0.553452)*/, + -10,4, -10,9/*mean (0.12094), correlation (0.554785)*/, + 7,3, 12,4/*mean (0.122582), correlation (0.555825)*/, + 9,-7, 10,-2/*mean (0.124978), correlation (0.549846)*/, + 7,0, 12,-2/*mean (0.127002), correlation (0.537452)*/, + -1,-6, 0,-11/*mean (0.127148), correlation (0.547401)*/ +}; + +ORBextractor::ORBextractor(int _nfeatures, float _scaleFactor, int _nlevels, + int _iniThFAST, int _minThFAST): + nfeatures(_nfeatures), scaleFactor(_scaleFactor), nlevels(_nlevels), + iniThFAST(_iniThFAST), minThFAST(_minThFAST) +{ + mvScaleFactor.resize(nlevels); + mvLevelSigma2.resize(nlevels); + mvScaleFactor[0]=1.0f; + mvLevelSigma2[0]=1.0f; + for(int i=1; i= vmin; --v) + { + while (umax[v0] == umax[v0 + 1]) + ++v0; + umax[v] = v0; + ++v0; + } +} + +static void computeOrientation(const Mat& image, vector& keypoints, const vector& umax) +{ + for (vector::iterator keypoint = keypoints.begin(), + keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint) + { + keypoint->angle = IC_Angle(image, keypoint->pt, umax); + } +} + +void ExtractorNode::DivideNode(ExtractorNode &n1, ExtractorNode &n2, ExtractorNode &n3, ExtractorNode &n4) +{ + const int halfX = ceil(static_cast(UR.x-UL.x)/2); + const int halfY = ceil(static_cast(BR.y-UL.y)/2); + + //Define boundaries of childs + n1.UL = UL; + n1.UR = cv::Point2i(UL.x+halfX,UL.y); + n1.BL = cv::Point2i(UL.x,UL.y+halfY); + n1.BR = cv::Point2i(UL.x+halfX,UL.y+halfY); + n1.vKeys.reserve(vKeys.size()); + + n2.UL = n1.UR; + n2.UR = UR; + n2.BL = n1.BR; + n2.BR = cv::Point2i(UR.x,UL.y+halfY); + n2.vKeys.reserve(vKeys.size()); + + n3.UL = n1.BL; + n3.UR = n1.BR; + n3.BL = BL; + n3.BR = cv::Point2i(n1.BR.x,BL.y); + n3.vKeys.reserve(vKeys.size()); + + n4.UL = n3.UR; + n4.UR = n2.BR; + n4.BL = n3.BR; + n4.BR = BR; + n4.vKeys.reserve(vKeys.size()); + + //Associate points to childs + for(size_t i=0;i ORBextractor::DistributeOctTree(const vector& vToDistributeKeys, const int &minX, + const int &maxX, const int &minY, const int &maxY, const int &N, const int &level) +{ + // Compute how many initial nodes + const int nIni = round(static_cast(maxX-minX)/(maxY-minY)); + + const float hX = static_cast(maxX-minX)/nIni; + + list lNodes; + + vector vpIniNodes; + vpIniNodes.resize(nIni); + + for(int i=0; i(i),0); + ni.UR = cv::Point2i(hX*static_cast(i+1),0); + ni.BL = cv::Point2i(ni.UL.x,maxY-minY); + ni.BR = cv::Point2i(ni.UR.x,maxY-minY); + ni.vKeys.reserve(vToDistributeKeys.size()); + + lNodes.push_back(ni); + vpIniNodes[i] = &lNodes.back(); + } + + //Associate points to childs + for(size_t i=0;ivKeys.push_back(kp); + } + + list::iterator lit = lNodes.begin(); + + while(lit!=lNodes.end()) + { + if(lit->vKeys.size()==1) + { + lit->bNoMore=true; + lit++; + } + else if(lit->vKeys.empty()) + lit = lNodes.erase(lit); + else + lit++; + } + + bool bFinish = false; + + int iteration = 0; + + vector > vSizeAndPointerToNode; + vSizeAndPointerToNode.reserve(lNodes.size()*4); + + while(!bFinish) + { + iteration++; + + int prevSize = lNodes.size(); + + lit = lNodes.begin(); + + int nToExpand = 0; + + vSizeAndPointerToNode.clear(); + + while(lit!=lNodes.end()) + { + if(lit->bNoMore) + { + // If node only contains one point do not subdivide and continue + lit++; + continue; + } + else + { + // If more than one point, subdivide + ExtractorNode n1,n2,n3,n4; + lit->DivideNode(n1,n2,n3,n4); + + // Add childs if they contain points + if(n1.vKeys.size()>0) + { + lNodes.push_front(n1); + if(n1.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n2.vKeys.size()>0) + { + lNodes.push_front(n2); + if(n2.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n3.vKeys.size()>0) + { + lNodes.push_front(n3); + if(n3.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n4.vKeys.size()>0) + { + lNodes.push_front(n4); + if(n4.vKeys.size()>1) + { + nToExpand++; + vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + + lit=lNodes.erase(lit); + continue; + } + } + + // Finish if there are more nodes than required features + // or all nodes contain just one point + if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize) + { + bFinish = true; + } + else if(((int)lNodes.size()+nToExpand*3)>N) + { + + while(!bFinish) + { + + prevSize = lNodes.size(); + + vector > vPrevSizeAndPointerToNode = vSizeAndPointerToNode; + vSizeAndPointerToNode.clear(); + + sort(vPrevSizeAndPointerToNode.begin(),vPrevSizeAndPointerToNode.end()); + for(int j=vPrevSizeAndPointerToNode.size()-1;j>=0;j--) + { + ExtractorNode n1,n2,n3,n4; + vPrevSizeAndPointerToNode[j].second->DivideNode(n1,n2,n3,n4); + + // Add childs if they contain points + if(n1.vKeys.size()>0) + { + lNodes.push_front(n1); + if(n1.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n1.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n2.vKeys.size()>0) + { + lNodes.push_front(n2); + if(n2.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n2.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n3.vKeys.size()>0) + { + lNodes.push_front(n3); + if(n3.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n3.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + if(n4.vKeys.size()>0) + { + lNodes.push_front(n4); + if(n4.vKeys.size()>1) + { + vSizeAndPointerToNode.push_back(make_pair(n4.vKeys.size(),&lNodes.front())); + lNodes.front().lit = lNodes.begin(); + } + } + + lNodes.erase(vPrevSizeAndPointerToNode[j].second->lit); + + if((int)lNodes.size()>=N) + break; + } + + if((int)lNodes.size()>=N || (int)lNodes.size()==prevSize) + bFinish = true; + + } + } + } + + // Retain the best point in each node + vector vResultKeys; + vResultKeys.reserve(nfeatures); + for(list::iterator lit=lNodes.begin(); lit!=lNodes.end(); lit++) + { + vector &vNodeKeys = lit->vKeys; + cv::KeyPoint* pKP = &vNodeKeys[0]; + float maxResponse = pKP->response; + + for(size_t k=1;kmaxResponse) + { + pKP = &vNodeKeys[k]; + maxResponse = vNodeKeys[k].response; + } + } + + vResultKeys.push_back(*pKP); + } + + return vResultKeys; +} + +void ORBextractor::ComputeKeyPointsOctTree(vector >& allKeypoints) +{ + allKeypoints.resize(nlevels); + + const float W = 30; + + for (int level = 0; level < nlevels; ++level) + { + const int minBorderX = EDGE_THRESHOLD-3; + const int minBorderY = minBorderX; + const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD+3; + const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD+3; + + vector vToDistributeKeys; + vToDistributeKeys.reserve(nfeatures*10); + + const float width = (maxBorderX-minBorderX); + const float height = (maxBorderY-minBorderY); + + const int nCols = width/W; + const int nRows = height/W; + const int wCell = ceil(width/nCols); + const int hCell = ceil(height/nRows); + + for(int i=0; i=maxBorderY-3) + continue; + if(maxY>maxBorderY) + maxY = maxBorderY; + + for(int j=0; j=maxBorderX-6) + continue; + if(maxX>maxBorderX) + maxX = maxBorderX; + + vector vKeysCell; + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,iniThFAST,true); + + if(vKeysCell.empty()) + { + FAST(mvImagePyramid[level].rowRange(iniY,maxY).colRange(iniX,maxX), + vKeysCell,minThFAST,true); + } + + if(!vKeysCell.empty()) + { + for(vector::iterator vit=vKeysCell.begin(); vit!=vKeysCell.end();vit++) + { + (*vit).pt.x+=j*wCell; + (*vit).pt.y+=i*hCell; + vToDistributeKeys.push_back(*vit); + } + } + + } + } + + vector & keypoints = allKeypoints[level]; + keypoints.reserve(nfeatures); + + keypoints = DistributeOctTree(vToDistributeKeys, minBorderX, maxBorderX, + minBorderY, maxBorderY,mnFeaturesPerLevel[level], level); + + const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level]; + + // Add border to coordinates and scale information + const int nkps = keypoints.size(); + for(int i=0; i > &allKeypoints) +{ + allKeypoints.resize(nlevels); + + float imageRatio = (float)mvImagePyramid[0].cols/mvImagePyramid[0].rows; + + for (int level = 0; level < nlevels; ++level) + { + const int nDesiredFeatures = mnFeaturesPerLevel[level]; + + const int levelCols = sqrt((float)nDesiredFeatures/(5*imageRatio)); + const int levelRows = imageRatio*levelCols; + + const int minBorderX = EDGE_THRESHOLD; + const int minBorderY = minBorderX; + const int maxBorderX = mvImagePyramid[level].cols-EDGE_THRESHOLD; + const int maxBorderY = mvImagePyramid[level].rows-EDGE_THRESHOLD; + + const int W = maxBorderX - minBorderX; + const int H = maxBorderY - minBorderY; + const int cellW = ceil((float)W/levelCols); + const int cellH = ceil((float)H/levelRows); + + const int nCells = levelRows*levelCols; + const int nfeaturesCell = ceil((float)nDesiredFeatures/nCells); + + vector > > cellKeyPoints(levelRows, vector >(levelCols)); + + vector > nToRetain(levelRows,vector(levelCols,0)); + vector > nTotal(levelRows,vector(levelCols,0)); + vector > bNoMore(levelRows,vector(levelCols,false)); + vector iniXCol(levelCols); + vector iniYRow(levelRows); + int nNoMore = 0; + int nToDistribute = 0; + + + float hY = cellH + 6; + + for(int i=0; infeaturesCell) + { + nToRetain[i][j] = nfeaturesCell; + bNoMore[i][j] = false; + } + else + { + nToRetain[i][j] = nKeys; + nToDistribute += nfeaturesCell-nKeys; + bNoMore[i][j] = true; + nNoMore++; + } + + } + } + + + // Retain by score + + while(nToDistribute>0 && nNoMorenNewFeaturesCell) + { + nToRetain[i][j] = nNewFeaturesCell; + bNoMore[i][j] = false; + } + else + { + nToRetain[i][j] = nTotal[i][j]; + nToDistribute += nNewFeaturesCell-nTotal[i][j]; + bNoMore[i][j] = true; + nNoMore++; + } + } + } + } + } + + vector & keypoints = allKeypoints[level]; + keypoints.reserve(nDesiredFeatures*2); + + const int scaledPatchSize = PATCH_SIZE*mvScaleFactor[level]; + + // Retain by score and transform coordinates + for(int i=0; i &keysCell = cellKeyPoints[i][j]; + KeyPointsFilter::retainBest(keysCell,nToRetain[i][j]); + if((int)keysCell.size()>nToRetain[i][j]) + keysCell.resize(nToRetain[i][j]); + + + for(size_t k=0, kend=keysCell.size(); knDesiredFeatures) + { + KeyPointsFilter::retainBest(keypoints,nDesiredFeatures); + keypoints.resize(nDesiredFeatures); + } + } + + // and compute orientations + for (int level = 0; level < nlevels; ++level) + computeOrientation(mvImagePyramid[level], allKeypoints[level], umax); +} + +static void computeDescriptors(const Mat& image, vector& keypoints, Mat& descriptors, + const vector& pattern) +{ + descriptors = Mat::zeros((int)keypoints.size(), 32, CV_8UC1); + + for (size_t i = 0; i < keypoints.size(); i++) + computeOrbDescriptor(keypoints[i], image, &pattern[0], descriptors.ptr((int)i)); +} + +void ORBextractor::operator()( InputArray _image, InputArray _mask, vector& _keypoints, + OutputArray _descriptors) +{ + if(_image.empty()) + return; + + Mat image = _image.getMat(); + assert(image.type() == CV_8UC1 ); + + // Pre-compute the scale pyramid + ComputePyramid(image); + + vector < vector > allKeypoints; + ComputeKeyPointsOctTree(allKeypoints); + //ComputeKeyPointsOld(allKeypoints); + + Mat descriptors; + + int nkeypoints = 0; + for (int level = 0; level < nlevels; ++level) + nkeypoints += (int)allKeypoints[level].size(); + if( nkeypoints == 0 ) + _descriptors.release(); + else + { + _descriptors.create(nkeypoints, 32, CV_8U); + descriptors = _descriptors.getMat(); + } + + _keypoints.clear(); + _keypoints.reserve(nkeypoints); + + int offset = 0; + for (int level = 0; level < nlevels; ++level) + { + vector& keypoints = allKeypoints[level]; + int nkeypointsLevel = (int)keypoints.size(); + + if(nkeypointsLevel==0) + continue; + + // preprocess the resized image + Mat workingMat = mvImagePyramid[level].clone(); + GaussianBlur(workingMat, workingMat, Size(7, 7), 2, 2, BORDER_REFLECT_101); + + // Compute the descriptors + Mat desc = descriptors.rowRange(offset, offset + nkeypointsLevel); + computeDescriptors(workingMat, keypoints, desc, pattern); + + offset += nkeypointsLevel; + + // Scale keypoint coordinates + if (level != 0) + { + float scale = mvScaleFactor[level]; //getScale(level, firstLevel, scaleFactor); + for (vector::iterator keypoint = keypoints.begin(), + keypointEnd = keypoints.end(); keypoint != keypointEnd; ++keypoint) + keypoint->pt *= scale; + } + // And add the keypoints to the output + _keypoints.insert(_keypoints.end(), keypoints.begin(), keypoints.end()); + } +} + +void ORBextractor::ComputePyramid(cv::Mat image) +{ + for (int level = 0; level < nlevels; ++level) + { + float scale = mvInvScaleFactor[level]; + Size sz(cvRound((float)image.cols*scale), cvRound((float)image.rows*scale)); + Size wholeSize(sz.width + EDGE_THRESHOLD*2, sz.height + EDGE_THRESHOLD*2); + Mat temp(wholeSize, image.type()), masktemp; + mvImagePyramid[level] = temp(Rect(EDGE_THRESHOLD, EDGE_THRESHOLD, sz.width, sz.height)); + + // Compute the resized image + if( level != 0 ) + { + resize(mvImagePyramid[level-1], mvImagePyramid[level], sz, 0, 0, INTER_LINEAR); + + copyMakeBorder(mvImagePyramid[level], temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, + BORDER_REFLECT_101+BORDER_ISOLATED); + } + else + { + copyMakeBorder(image, temp, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, EDGE_THRESHOLD, + BORDER_REFLECT_101); + } + } + +} + +} //namespace ORB_SLAM diff --git a/src/ORBmatcher.cc b/src/ORBmatcher.cc new file mode 100644 index 0000000000..be31e8487e --- /dev/null +++ b/src/ORBmatcher.cc @@ -0,0 +1,1665 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "ORBmatcher.h" + +#include + +#include +#include + +#include "Thirdparty/DBoW2/DBoW2/FeatureVector.h" + +#include + +using namespace std; + +namespace ORB_SLAM2 +{ + +const int ORBmatcher::TH_HIGH = 100; +const int ORBmatcher::TH_LOW = 50; +const int ORBmatcher::HISTO_LENGTH = 30; + +ORBmatcher::ORBmatcher(float nnratio, bool checkOri): mfNNratio(nnratio), mbCheckOrientation(checkOri) +{ +} + +int ORBmatcher::SearchByProjection(Frame &F, const vector &vpMapPoints, const float th) +{ + int nmatches=0; + + const bool bFactor = th!=1.0; + + for(size_t iMP=0; iMPmbTrackInView) + continue; + + if(pMP->isBad()) + continue; + + const int &nPredictedLevel = pMP->mnTrackScaleLevel; + + // The size of the window will depend on the viewing direction + float r = RadiusByViewingCos(pMP->mTrackViewCos); + + if(bFactor) + r*=th; + + const vector vIndices = + F.GetFeaturesInArea(pMP->mTrackProjX,pMP->mTrackProjY,r*F.mvScaleFactors[nPredictedLevel],nPredictedLevel-1,nPredictedLevel); + + if(vIndices.empty()) + continue; + + const cv::Mat MPdescriptor = pMP->GetDescriptor(); + + int bestDist=256; + int bestLevel= -1; + int bestDist2=256; + int bestLevel2 = -1; + int bestIdx =-1 ; + + // Get best and second matches with near keypoints + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + if(F.mvpMapPoints[idx]) + if(F.mvpMapPoints[idx]->Observations()>0) + continue; + + if(F.mvuRight[idx]>0) + { + const float er = fabs(pMP->mTrackProjXR-F.mvuRight[idx]); + if(er>r*F.mvScaleFactors[nPredictedLevel]) + continue; + } + + const cv::Mat &d = F.mDescriptors.row(idx); + + const int dist = DescriptorDistance(MPdescriptor,d); + + if(distmfNNratio*bestDist2) + continue; + + F.mvpMapPoints[bestIdx]=pMP; + nmatches++; + } + } + + return nmatches; +} + +float ORBmatcher::RadiusByViewingCos(const float &viewCos) +{ + if(viewCos>0.998) + return 2.5; + else + return 4.0; +} + + +bool ORBmatcher::CheckDistEpipolarLine(const cv::KeyPoint &kp1,const cv::KeyPoint &kp2,const cv::Mat &F12,const KeyFrame* pKF2) +{ + // Epipolar line in second image l = x1'F12 = [a b c] + const float a = kp1.pt.x*F12.at(0,0)+kp1.pt.y*F12.at(1,0)+F12.at(2,0); + const float b = kp1.pt.x*F12.at(0,1)+kp1.pt.y*F12.at(1,1)+F12.at(2,1); + const float c = kp1.pt.x*F12.at(0,2)+kp1.pt.y*F12.at(1,2)+F12.at(2,2); + + const float num = a*kp2.pt.x+b*kp2.pt.y+c; + + const float den = a*a+b*b; + + if(den==0) + return false; + + const float dsqr = num*num/den; + + return dsqr<3.84*pKF2->mvLevelSigma2[kp2.octave]; +} + +int ORBmatcher::SearchByBoW(KeyFrame* pKF,Frame &F, vector &vpMapPointMatches) +{ + const vector vpMapPointsKF = pKF->GetMapPointMatches(); + + vpMapPointMatches = vector(F.N,static_cast(NULL)); + + const DBoW2::FeatureVector &vFeatVecKF = pKF->mFeatVec; + + int nmatches=0; + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == Fit->first) + { + const vector vIndicesKF = KFit->second; + const vector vIndicesF = Fit->second; + + for(size_t iKF=0; iKFisBad()) + continue; + + const cv::Mat &dKF= pKF->mDescriptors.row(realIdxKF); + + int bestDist1=256; + int bestIdxF =-1 ; + int bestDist2=256; + + for(size_t iF=0; iF(bestDist1)(bestDist2)) + { + vpMapPointMatches[bestIdxF]=pMP; + + const cv::KeyPoint &kp = pKF->mvKeysUn[realIdxKF]; + + if(mbCheckOrientation) + { + float rot = kp.angle-F.mvKeys[bestIdxF].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < Fit->first) + { + KFit = vFeatVecKF.lower_bound(Fit->first); + } + else + { + Fit = F.mFeatVec.lower_bound(KFit->first); + } + } + + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i(NULL); + nmatches--; + } + } + } + + return nmatches; +} + +int ORBmatcher::SearchByProjection(KeyFrame* pKF, cv::Mat Scw, const vector &vpPoints, vector &vpMatched, int th) +{ + // Get Calibration Parameters for later projection + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + + // Decompose Scw + cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3); + const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0))); + cv::Mat Rcw = sRcw/scw; + cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw; + cv::Mat Ow = -Rcw.t()*tcw; + + // Set of MapPoints already found in the KeyFrame + set spAlreadyFound(vpMatched.begin(), vpMatched.end()); + spAlreadyFound.erase(static_cast(NULL)); + + int nmatches=0; + + // For each Candidate MapPoint Project and Match + for(int iMP=0, iendMP=vpPoints.size(); iMPisBad() || spAlreadyFound.count(pMP)) + continue; + + // Get 3D Coords. + cv::Mat p3Dw = pMP->GetWorldPos(); + + // Transform into Camera Coords. + cv::Mat p3Dc = Rcw*p3Dw+tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0) + continue; + + // Project into Image + const float invz = 1/p3Dc.at(2); + const float x = p3Dc.at(0)*invz; + const float y = p3Dc.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF->IsInImage(u,v)) + continue; + + // Depth must be inside the scale invariance region of the point + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist = cv::norm(PO); + + if(distmaxDistance) + continue; + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist) + continue; + + int nPredictedLevel = pMP->PredictScale(dist,pKF->mfLogScaleFactor); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + if(vpMatched[idx]) + continue; + + const int &kpLevel= pKF->mvKeysUn[idx].octave; + + if(kpLevelnPredictedLevel) + continue; + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(dist &vbPrevMatched, vector &vnMatches12, int windowSize) +{ + int nmatches=0; + vnMatches12 = vector(F1.mvKeysUn.size(),-1); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;i vMatchedDistance(F2.mvKeysUn.size(),INT_MAX); + vector vnMatches21(F2.mvKeysUn.size(),-1); + + for(size_t i1=0, iend1=F1.mvKeysUn.size(); i10) + continue; + + vector vIndices2 = F2.GetFeaturesInArea(vbPrevMatched[i1].x,vbPrevMatched[i1].y, windowSize,level1,level1); + + if(vIndices2.empty()) + continue; + + cv::Mat d1 = F1.mDescriptors.row(i1); + + int bestDist = INT_MAX; + int bestDist2 = INT_MAX; + int bestIdx2 = -1; + + for(vector::iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++) + { + size_t i2 = *vit; + + cv::Mat d2 = F2.mDescriptors.row(i2); + + int dist = DescriptorDistance(d1,d2); + + if(vMatchedDistance[i2]<=dist) + continue; + + if(dist=0) + { + vnMatches12[vnMatches21[bestIdx2]]=-1; + nmatches--; + } + vnMatches12[i1]=bestIdx2; + vnMatches21[bestIdx2]=i1; + vMatchedDistance[bestIdx2]=bestDist; + nmatches++; + + if(mbCheckOrientation) + { + float rot = F1.mvKeysUn[i1].angle-F2.mvKeysUn[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin=0) + { + vnMatches12[idx1]=-1; + nmatches--; + } + } + } + + } + + //Update prev matched + for(size_t i1=0, iend1=vnMatches12.size(); i1=0) + vbPrevMatched[i1]=F2.mvKeysUn[vnMatches12[i1]].pt; + + return nmatches; +} + +int ORBmatcher::SearchByBoW(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches12) +{ + const vector &vKeysUn1 = pKF1->mvKeysUn; + const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec; + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + const cv::Mat &Descriptors1 = pKF1->mDescriptors; + + const vector &vKeysUn2 = pKF2->mvKeysUn; + const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec; + const vector vpMapPoints2 = pKF2->GetMapPointMatches(); + const cv::Mat &Descriptors2 = pKF2->mDescriptors; + + vpMatches12 = vector(vpMapPoints1.size(),static_cast(NULL)); + vector vbMatched2(vpMapPoints2.size(),false); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == f2it->first) + { + for(size_t i1=0, iend1=f1it->second.size(); i1second[i1]; + + MapPoint* pMP1 = vpMapPoints1[idx1]; + if(!pMP1) + continue; + if(pMP1->isBad()) + continue; + + const cv::Mat &d1 = Descriptors1.row(idx1); + + int bestDist1=256; + int bestIdx2 =-1 ; + int bestDist2=256; + + for(size_t i2=0, iend2=f2it->second.size(); i2second[i2]; + + MapPoint* pMP2 = vpMapPoints2[idx2]; + + if(vbMatched2[idx2] || !pMP2) + continue; + + if(pMP2->isBad()) + continue; + + const cv::Mat &d2 = Descriptors2.row(idx2); + + int dist = DescriptorDistance(d1,d2); + + if(dist(bestDist1)(bestDist2)) + { + vpMatches12[idx1]=vpMapPoints2[bestIdx2]; + vbMatched2[bestIdx2]=true; + + if(mbCheckOrientation) + { + float rot = vKeysUn1[idx1].angle-vKeysUn2[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < f2it->first) + { + f1it = vFeatVec1.lower_bound(f2it->first); + } + else + { + f2it = vFeatVec2.lower_bound(f1it->first); + } + } + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i(NULL); + nmatches--; + } + } + } + + return nmatches; +} + +int ORBmatcher::SearchForTriangulation(KeyFrame *pKF1, KeyFrame *pKF2, cv::Mat F12, + vector > &vMatchedPairs, const bool bOnlyStereo) +{ + const DBoW2::FeatureVector &vFeatVec1 = pKF1->mFeatVec; + const DBoW2::FeatureVector &vFeatVec2 = pKF2->mFeatVec; + + //Compute epipole in second image + cv::Mat Cw = pKF1->GetCameraCenter(); + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + cv::Mat C2 = R2w*Cw+t2w; + const float invz = 1.0f/C2.at(2); + const float ex =pKF2->fx*C2.at(0)*invz+pKF2->cx; + const float ey =pKF2->fy*C2.at(1)*invz+pKF2->cy; + + // Find matches between not tracked keypoints + // Matching speed-up by ORB Vocabulary + // Compare only ORB that share the same node + + int nmatches=0; + vector vbMatched2(pKF2->N,false); + vector vMatches12(pKF1->N,-1); + + vector rotHist[HISTO_LENGTH]; + for(int i=0;ifirst == f2it->first) + { + for(size_t i1=0, iend1=f1it->second.size(); i1second[i1]; + + MapPoint* pMP1 = pKF1->GetMapPoint(idx1); + + // If there is already a MapPoint skip + if(pMP1) + continue; + + const bool bStereo1 = pKF1->mvuRight[idx1]>=0; + + if(bOnlyStereo) + if(!bStereo1) + continue; + + const cv::KeyPoint &kp1 = pKF1->mvKeysUn[idx1]; + + const cv::Mat &d1 = pKF1->mDescriptors.row(idx1); + + int bestDist = TH_LOW; + int bestIdx2 = -1; + + for(size_t i2=0, iend2=f2it->second.size(); i2second[i2]; + + MapPoint* pMP2 = pKF2->GetMapPoint(idx2); + + // If we have already matched or there is a MapPoint skip + if(vbMatched2[idx2] || pMP2) + continue; + + const bool bStereo2 = pKF2->mvuRight[idx2]>=0; + + if(bOnlyStereo) + if(!bStereo2) + continue; + + const cv::Mat &d2 = pKF2->mDescriptors.row(idx2); + + const int dist = DescriptorDistance(d1,d2); + + if(dist>TH_LOW || dist>bestDist) + continue; + + const cv::KeyPoint &kp2 = pKF2->mvKeysUn[idx2]; + + if(!bStereo1 && !bStereo2) + { + const float distex = ex-kp2.pt.x; + const float distey = ey-kp2.pt.y; + if(distex*distex+distey*distey<100*pKF2->mvScaleFactors[kp2.octave]) + continue; + } + + if(CheckDistEpipolarLine(kp1,kp2,F12,pKF2)) + { + bestIdx2 = idx2; + bestDist = dist; + } + } + + if(bestIdx2>=0) + { + const cv::KeyPoint &kp2 = pKF2->mvKeysUn[bestIdx2]; + vMatches12[idx1]=bestIdx2; + nmatches++; + + if(mbCheckOrientation) + { + float rot = kp1.angle-kp2.angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && binfirst < f2it->first) + { + f1it = vFeatVec1.lower_bound(f2it->first); + } + else + { + f2it = vFeatVec2.lower_bound(f1it->first); + } + } + + if(mbCheckOrientation) + { + int ind1=-1; + int ind2=-1; + int ind3=-1; + + ComputeThreeMaxima(rotHist,HISTO_LENGTH,ind1,ind2,ind3); + + for(int i=0; i &vpMapPoints, const float th) +{ + cv::Mat Rcw = pKF->GetRotation(); + cv::Mat tcw = pKF->GetTranslation(); + + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + const float &bf = pKF->mbf; + + cv::Mat Ow = pKF->GetCameraCenter(); + + int nFused=0; + + const int nMPs = vpMapPoints.size(); + + for(int i=0; iisBad() || pMP->IsInKeyFrame(pKF)) + continue; + + cv::Mat p3Dw = pMP->GetWorldPos(); + cv::Mat p3Dc = Rcw*p3Dw + tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0f) + continue; + + const float invz = 1/p3Dc.at(2); + const float x = p3Dc.at(0)*invz; + const float y = p3Dc.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF->IsInImage(u,v)) + continue; + + const float ur = u-bf*invz; + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist3D = cv::norm(PO); + + // Depth must be inside the scale pyramid of the image + if(dist3DmaxDistance ) + continue; + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist3D) + continue; + + int nPredictedLevel = pMP->PredictScale(dist3D,pKF->mfLogScaleFactor); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + const cv::KeyPoint &kp = pKF->mvKeysUn[idx]; + + const int &kpLevel= kp.octave; + + if(kpLevelnPredictedLevel) + continue; + + if(pKF->mvuRight[idx]>=0) + { + // Check reprojection error in stereo + const float &kpx = kp.pt.x; + const float &kpy = kp.pt.y; + const float &kpr = pKF->mvuRight[idx]; + const float ex = u-kpx; + const float ey = v-kpy; + const float er = ur-kpr; + const float e2 = ex*ex+ey*ey+er*er; + + if(e2*pKF->mvInvLevelSigma2[kpLevel]>7.8) + continue; + } + else + { + const float &kpx = kp.pt.x; + const float &kpy = kp.pt.y; + const float ex = u-kpx; + const float ey = v-kpy; + const float e2 = ex*ex+ey*ey; + + if(e2*pKF->mvInvLevelSigma2[kpLevel]>5.99) + continue; + } + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(distGetMapPoint(bestIdx); + if(pMPinKF) + { + if(!pMPinKF->isBad()) + { + if(pMPinKF->Observations()>pMP->Observations()) + pMP->Replace(pMPinKF); + else + pMPinKF->Replace(pMP); + } + } + else + { + pMP->AddObservation(pKF,bestIdx); + pKF->AddMapPoint(pMP,bestIdx); + } + nFused++; + } + } + + return nFused; +} + +int ORBmatcher::Fuse(KeyFrame *pKF, cv::Mat Scw, const vector &vpPoints, float th, vector &vpReplacePoint) +{ + // Get Calibration Parameters for later projection + const float &fx = pKF->fx; + const float &fy = pKF->fy; + const float &cx = pKF->cx; + const float &cy = pKF->cy; + + // Decompose Scw + cv::Mat sRcw = Scw.rowRange(0,3).colRange(0,3); + const float scw = sqrt(sRcw.row(0).dot(sRcw.row(0))); + cv::Mat Rcw = sRcw/scw; + cv::Mat tcw = Scw.rowRange(0,3).col(3)/scw; + cv::Mat Ow = -Rcw.t()*tcw; + + // Set of MapPoints already found in the KeyFrame + const set spAlreadyFound = pKF->GetMapPoints(); + + int nFused=0; + + const int nPoints = vpPoints.size(); + + // For each candidate MapPoint project and match + for(int iMP=0; iMPisBad() || spAlreadyFound.count(pMP)) + continue; + + // Get 3D Coords. + cv::Mat p3Dw = pMP->GetWorldPos(); + + // Transform into Camera Coords. + cv::Mat p3Dc = Rcw*p3Dw+tcw; + + // Depth must be positive + if(p3Dc.at(2)<0.0f) + continue; + + // Project into Image + const float invz = 1.0/p3Dc.at(2); + const float x = p3Dc.at(0)*invz; + const float y = p3Dc.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF->IsInImage(u,v)) + continue; + + // Depth must be inside the scale pyramid of the image + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + cv::Mat PO = p3Dw-Ow; + const float dist3D = cv::norm(PO); + + if(dist3DmaxDistance) + continue; + + // Viewing angle must be less than 60 deg + cv::Mat Pn = pMP->GetNormal(); + + if(PO.dot(Pn)<0.5*dist3D) + continue; + + // Compute predicted scale level + const int nPredictedLevel = pMP->PredictScale(dist3D,pKF->mfLogScaleFactor); + + // Search in a radius + const float radius = th*pKF->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = INT_MAX; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(); vit!=vIndices.end(); vit++) + { + const size_t idx = *vit; + const int &kpLevel = pKF->mvKeysUn[idx].octave; + + if(kpLevelnPredictedLevel) + continue; + + const cv::Mat &dKF = pKF->mDescriptors.row(idx); + + int dist = DescriptorDistance(dMP,dKF); + + if(distGetMapPoint(bestIdx); + if(pMPinKF) + { + if(!pMPinKF->isBad()) + vpReplacePoint[iMP] = pMPinKF; + } + else + { + pMP->AddObservation(pKF,bestIdx); + pKF->AddMapPoint(pMP,bestIdx); + } + nFused++; + } + } + + return nFused; +} + +int ORBmatcher::SearchBySim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches12, + const float &s12, const cv::Mat &R12, const cv::Mat &t12, const float th) +{ + const float &fx = pKF1->fx; + const float &fy = pKF1->fy; + const float &cx = pKF1->cx; + const float &cy = pKF1->cy; + + // Camera 1 from world + cv::Mat R1w = pKF1->GetRotation(); + cv::Mat t1w = pKF1->GetTranslation(); + + //Camera 2 from world + cv::Mat R2w = pKF2->GetRotation(); + cv::Mat t2w = pKF2->GetTranslation(); + + //Transformation between cameras + cv::Mat sR12 = s12*R12; + cv::Mat sR21 = (1.0/s12)*R12.t(); + cv::Mat t21 = -sR21*t12; + + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + const int N1 = vpMapPoints1.size(); + + const vector vpMapPoints2 = pKF2->GetMapPointMatches(); + const int N2 = vpMapPoints2.size(); + + vector vbAlreadyMatched1(N1,false); + vector vbAlreadyMatched2(N2,false); + + for(int i=0; iGetIndexInKeyFrame(pKF2); + if(idx2>=0 && idx2 vnMatch1(N1,-1); + vector vnMatch2(N2,-1); + + // Transform from KF1 to KF2 and search + for(int i1=0; i1isBad()) + continue; + + cv::Mat p3Dw = pMP->GetWorldPos(); + cv::Mat p3Dc1 = R1w*p3Dw + t1w; + cv::Mat p3Dc2 = sR21*p3Dc1 + t21; + + // Depth must be positive + if(p3Dc2.at(2)<0.0) + continue; + + const float invz = 1.0/p3Dc2.at(2); + const float x = p3Dc2.at(0)*invz; + const float y = p3Dc2.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF2->IsInImage(u,v)) + continue; + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const float dist3D = cv::norm(p3Dc2); + + // Depth must be inside the scale invariance region + if(dist3DmaxDistance ) + continue; + + // Compute predicted octave + const int nPredictedLevel = pMP->PredictScale(dist3D,pKF2->mfLogScaleFactor); + + // Search in a radius + const float radius = th*pKF2->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF2->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = INT_MAX; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + const cv::KeyPoint &kp = pKF2->mvKeysUn[idx]; + + if(kp.octavenPredictedLevel) + continue; + + const cv::Mat &dKF = pKF2->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(distisBad()) + continue; + + cv::Mat p3Dw = pMP->GetWorldPos(); + cv::Mat p3Dc2 = R2w*p3Dw + t2w; + cv::Mat p3Dc1 = sR12*p3Dc2 + t12; + + // Depth must be positive + if(p3Dc1.at(2)<0.0) + continue; + + const float invz = 1.0/p3Dc1.at(2); + const float x = p3Dc1.at(0)*invz; + const float y = p3Dc1.at(1)*invz; + + const float u = fx*x+cx; + const float v = fy*y+cy; + + // Point must be inside the image + if(!pKF1->IsInImage(u,v)) + continue; + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + const float dist3D = cv::norm(p3Dc1); + + // Depth must be inside the scale pyramid of the image + if(dist3DmaxDistance) + continue; + + // Compute predicted octave + const int nPredictedLevel = pMP->PredictScale(dist3D,pKF1->mfLogScaleFactor); + + // Search in a radius of 2.5*sigma(ScaleLevel) + const float radius = th*pKF1->mvScaleFactors[nPredictedLevel]; + + const vector vIndices = pKF1->GetFeaturesInArea(u,v,radius); + + if(vIndices.empty()) + continue; + + // Match to the most similar keypoint in the radius + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = INT_MAX; + int bestIdx = -1; + for(vector::const_iterator vit=vIndices.begin(), vend=vIndices.end(); vit!=vend; vit++) + { + const size_t idx = *vit; + + const cv::KeyPoint &kp = pKF1->mvKeysUn[idx]; + + if(kp.octavenPredictedLevel) + continue; + + const cv::Mat &dKF = pKF1->mDescriptors.row(idx); + + const int dist = DescriptorDistance(dMP,dKF); + + if(dist=0) + { + int idx1 = vnMatch2[idx2]; + if(idx1==i1) + { + vpMatches12[i1] = vpMapPoints2[idx2]; + nFound++; + } + } + } + + return nFound; +} + +int ORBmatcher::SearchByProjection(Frame &CurrentFrame, const Frame &LastFrame, const float th, const bool bMono) +{ + int nmatches = 0; + + // Rotation Histogram (to check rotation consistency) + vector rotHist[HISTO_LENGTH]; + for(int i=0;i(2)>CurrentFrame.mb && !bMono; + const bool bBackward = -tlc.at(2)>CurrentFrame.mb && !bMono; + + for(int i=0; iGetWorldPos(); + cv::Mat x3Dc = Rcw*x3Dw+tcw; + + const float xc = x3Dc.at(0); + const float yc = x3Dc.at(1); + const float invzc = 1.0/x3Dc.at(2); + + if(invzc<0) + continue; + + float u = CurrentFrame.fx*xc*invzc+CurrentFrame.cx; + float v = CurrentFrame.fy*yc*invzc+CurrentFrame.cy; + + if(uCurrentFrame.mnMaxX) + continue; + if(vCurrentFrame.mnMaxY) + continue; + + int nLastOctave = LastFrame.mvKeys[i].octave; + + // Search in a window. Size depends on scale + float radius = th*CurrentFrame.mvScaleFactors[nLastOctave]; + + vector vIndices2; + + if(bForward) + vIndices2 = CurrentFrame.GetFeaturesInArea(u,v, radius, nLastOctave); + else if(bBackward) + vIndices2 = CurrentFrame.GetFeaturesInArea(u,v, radius, 0, nLastOctave); + else + vIndices2 = CurrentFrame.GetFeaturesInArea(u,v, radius, nLastOctave-1, nLastOctave+1); + + if(vIndices2.empty()) + continue; + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx2 = -1; + + for(vector::const_iterator vit=vIndices2.begin(), vend=vIndices2.end(); vit!=vend; vit++) + { + const size_t i2 = *vit; + if(CurrentFrame.mvpMapPoints[i2]) + if(CurrentFrame.mvpMapPoints[i2]->Observations()>0) + continue; + + if(CurrentFrame.mvuRight[i2]>0) + { + const float ur = u - CurrentFrame.mbf*invzc; + const float er = fabs(ur - CurrentFrame.mvuRight[i2]); + if(er>radius) + continue; + } + + const cv::Mat &d = CurrentFrame.mDescriptors.row(i2); + + const int dist = DescriptorDistance(dMP,d); + + if(dist=0 && bin(NULL); + nmatches--; + } + } + } + } + + return nmatches; +} + +int ORBmatcher::SearchByProjection(Frame &CurrentFrame, KeyFrame *pKF, const set &sAlreadyFound, const float th , const int ORBdist) +{ + int nmatches = 0; + + const cv::Mat Rcw = CurrentFrame.mTcw.rowRange(0,3).colRange(0,3); + const cv::Mat tcw = CurrentFrame.mTcw.rowRange(0,3).col(3); + const cv::Mat Ow = -Rcw.t()*tcw; + + // Rotation Histogram (to check rotation consistency) + vector rotHist[HISTO_LENGTH]; + for(int i=0;i vpMPs = pKF->GetMapPointMatches(); + + for(size_t i=0, iend=vpMPs.size(); iisBad() && !sAlreadyFound.count(pMP)) + { + //Project + cv::Mat x3Dw = pMP->GetWorldPos(); + cv::Mat x3Dc = Rcw*x3Dw+tcw; + + const float xc = x3Dc.at(0); + const float yc = x3Dc.at(1); + const float invzc = 1.0/x3Dc.at(2); + + const float u = CurrentFrame.fx*xc*invzc+CurrentFrame.cx; + const float v = CurrentFrame.fy*yc*invzc+CurrentFrame.cy; + + if(uCurrentFrame.mnMaxX) + continue; + if(vCurrentFrame.mnMaxY) + continue; + + // Compute predicted scale level + cv::Mat PO = x3Dw-Ow; + float dist3D = cv::norm(PO); + + const float maxDistance = pMP->GetMaxDistanceInvariance(); + const float minDistance = pMP->GetMinDistanceInvariance(); + + // Depth must be inside the scale pyramid of the image + if(dist3DmaxDistance) + continue; + + int nPredictedLevel = pMP->PredictScale(dist3D,CurrentFrame.mfLogScaleFactor); + + // Search in a window + const float radius = th*CurrentFrame.mvScaleFactors[nPredictedLevel]; + + const vector vIndices2 = CurrentFrame.GetFeaturesInArea(u, v, radius, nPredictedLevel-1, nPredictedLevel+1); + + if(vIndices2.empty()) + continue; + + const cv::Mat dMP = pMP->GetDescriptor(); + + int bestDist = 256; + int bestIdx2 = -1; + + for(vector::const_iterator vit=vIndices2.begin(); vit!=vIndices2.end(); vit++) + { + const size_t i2 = *vit; + if(CurrentFrame.mvpMapPoints[i2]) + continue; + + const cv::Mat &d = CurrentFrame.mDescriptors.row(i2); + + const int dist = DescriptorDistance(dMP,d); + + if(distmvKeysUn[i].angle-CurrentFrame.mvKeysUn[bestIdx2].angle; + if(rot<0.0) + rot+=360.0f; + int bin = round(rot*factor); + if(bin==HISTO_LENGTH) + bin=0; + assert(bin>=0 && bin* histo, const int L, int &ind1, int &ind2, int &ind3) +{ + int max1=0; + int max2=0; + int max3=0; + + for(int i=0; imax1) + { + max3=max2; + max2=max1; + max1=s; + ind3=ind2; + ind2=ind1; + ind1=i; + } + else if(s>max2) + { + max3=max2; + max2=s; + ind3=ind2; + ind2=i; + } + else if(s>max3) + { + max3=s; + ind3=i; + } + } + + if(max2<0.1f*(float)max1) + { + ind2=-1; + ind3=-1; + } + else if(max3<0.1f*(float)max1) + { + ind3=-1; + } +} + + +// Bit set count operation from +// http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetParallel +int ORBmatcher::DescriptorDistance(const cv::Mat &a, const cv::Mat &b) +{ + const int *pa = a.ptr(); + const int *pb = b.ptr(); + + int dist=0; + + for(int i=0; i<8; i++, pa++, pb++) + { + unsigned int v = *pa ^ *pb; + v = v - ((v >> 1) & 0x55555555); + v = (v & 0x33333333) + ((v >> 2) & 0x33333333); + dist += (((v + (v >> 4)) & 0xF0F0F0F) * 0x1010101) >> 24; + } + + return dist; +} + +} //namespace ORB_SLAM diff --git a/src/Optimizer.cc b/src/Optimizer.cc new file mode 100644 index 0000000000..83d9264546 --- /dev/null +++ b/src/Optimizer.cc @@ -0,0 +1,1244 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "Optimizer.h" + +#include "Thirdparty/g2o/g2o/core/block_solver.h" +#include "Thirdparty/g2o/g2o/core/optimization_algorithm_levenberg.h" +#include "Thirdparty/g2o/g2o/solvers/linear_solver_eigen.h" +#include "Thirdparty/g2o/g2o/types/types_six_dof_expmap.h" +#include "Thirdparty/g2o/g2o/core/robust_kernel_impl.h" +#include "Thirdparty/g2o/g2o/solvers/linear_solver_dense.h" +#include "Thirdparty/g2o/g2o/types/types_seven_dof_expmap.h" + +#include + +#include "Converter.h" + +#include + +namespace ORB_SLAM2 +{ + + +void Optimizer::GlobalBundleAdjustemnt(Map* pMap, int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust) +{ + vector vpKFs = pMap->GetAllKeyFrames(); + vector vpMP = pMap->GetAllMapPoints(); + BundleAdjustment(vpKFs,vpMP,nIterations,pbStopFlag, nLoopKF, bRobust); +} + + +void Optimizer::BundleAdjustment(const vector &vpKFs, const vector &vpMP, + int nIterations, bool* pbStopFlag, const unsigned long nLoopKF, const bool bRobust) +{ + vector vbNotIncludedMP; + vbNotIncludedMP.resize(vpMP.size()); + + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + long unsigned int maxKFid = 0; + + // Set KeyFrame vertices + for(size_t i=0; iisBad()) + continue; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKF->GetPose())); + vSE3->setId(pKF->mnId); + vSE3->setFixed(pKF->mnId==0); + optimizer.addVertex(vSE3); + if(pKF->mnId>maxKFid) + maxKFid=pKF->mnId; + } + + const float thHuber2D = sqrt(5.99); + const float thHuber3D = sqrt(7.815); + + // Set MapPoint vertices + for(size_t i=0; iisBad()) + continue; + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + const int id = pMP->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + const map observations = pMP->GetObservations(); + + int nEdges = 0; + //SET EDGES + for(map::const_iterator mit=observations.begin(); mit!=observations.end(); mit++) + { + + KeyFrame* pKF = mit->first; + if(pKF->isBad() || pKF->mnId>maxKFid) + continue; + + nEdges++; + + const cv::KeyPoint &kpUn = pKF->mvKeysUn[mit->second]; + + if(pKF->mvuRight[mit->second]<0) + { + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + g2o::EdgeSE3ProjectXYZ* e = new g2o::EdgeSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + if(bRobust) + { + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber2D); + } + + e->fx = pKF->fx; + e->fy = pKF->fy; + e->cx = pKF->cx; + e->cy = pKF->cy; + + optimizer.addEdge(e); + } + else + { + Eigen::Matrix obs; + const float kp_ur = pKF->mvuRight[mit->second]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKF->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKF->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + if(bRobust) + { + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuber3D); + } + + e->fx = pKF->fx; + e->fy = pKF->fy; + e->cx = pKF->cx; + e->cy = pKF->cy; + e->bf = pKF->mbf; + + optimizer.addEdge(e); + } + } + + if(nEdges==0) + { + optimizer.removeVertex(vPoint); + vbNotIncludedMP[i]=true; + } + else + { + vbNotIncludedMP[i]=false; + } + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(nIterations); + + // Recover optimized data + + //Keyframes + for(size_t i=0; iisBad()) + continue; + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKF->mnId)); + g2o::SE3Quat SE3quat = vSE3->estimate(); + if(nLoopKF==0) + { + pKF->SetPose(Converter::toCvMat(SE3quat)); + } + else + { + pKF->mTcwGBA.create(4,4,CV_32F); + Converter::toCvMat(SE3quat).copyTo(pKF->mTcwGBA); + pKF->mnBAGlobalForKF = nLoopKF; + } + } + + //Points + for(size_t i=0; iisBad()) + continue; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+maxKFid+1)); + + if(nLoopKF==0) + { + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } + else + { + pMP->mPosGBA.create(3,1,CV_32F); + Converter::toCvMat(vPoint->estimate()).copyTo(pMP->mPosGBA); + pMP->mnBAGlobalForKF = nLoopKF; + } + } + +} + +int Optimizer::PoseOptimization(Frame *pFrame) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + int nInitialCorrespondences=0; + + // Set Frame vertex + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pFrame->mTcw)); + vSE3->setId(0); + vSE3->setFixed(false); + optimizer.addVertex(vSE3); + + // Set MapPoint vertices + const int N = pFrame->N; + + vector vpEdgesMono; + vector vnIndexEdgeMono; + vpEdgesMono.reserve(N); + vnIndexEdgeMono.reserve(N); + + vector vpEdgesStereo; + vector vnIndexEdgeStereo; + vpEdgesStereo.reserve(N); + vnIndexEdgeStereo.reserve(N); + + const float deltaMono = sqrt(5.991); + const float deltaStereo = sqrt(7.815); + + + { + unique_lock lock(MapPoint::mGlobalMutex); + + for(int i=0; imvpMapPoints[i]; + if(pMP) + { + // Monocular observation + if(pFrame->mvuRight[i]<0) + { + nInitialCorrespondences++; + pFrame->mvbOutlier[i] = false; + + Eigen::Matrix obs; + const cv::KeyPoint &kpUn = pFrame->mvKeysUn[i]; + obs << kpUn.pt.x, kpUn.pt.y; + + g2o::EdgeSE3ProjectXYZOnlyPose* e = new g2o::EdgeSE3ProjectXYZOnlyPose(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(0))); + e->setMeasurement(obs); + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(deltaMono); + + e->fx = pFrame->fx; + e->fy = pFrame->fy; + e->cx = pFrame->cx; + e->cy = pFrame->cy; + cv::Mat Xw = pMP->GetWorldPos(); + e->Xw[0] = Xw.at(0); + e->Xw[1] = Xw.at(1); + e->Xw[2] = Xw.at(2); + + optimizer.addEdge(e); + + vpEdgesMono.push_back(e); + vnIndexEdgeMono.push_back(i); + } + else // Stereo observation + { + nInitialCorrespondences++; + pFrame->mvbOutlier[i] = false; + + //SET EDGE + Eigen::Matrix obs; + const cv::KeyPoint &kpUn = pFrame->mvKeysUn[i]; + const float &kp_ur = pFrame->mvuRight[i]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZOnlyPose* e = new g2o::EdgeStereoSE3ProjectXYZOnlyPose(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(0))); + e->setMeasurement(obs); + const float invSigma2 = pFrame->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(deltaStereo); + + e->fx = pFrame->fx; + e->fy = pFrame->fy; + e->cx = pFrame->cx; + e->cy = pFrame->cy; + e->bf = pFrame->mbf; + cv::Mat Xw = pMP->GetWorldPos(); + e->Xw[0] = Xw.at(0); + e->Xw[1] = Xw.at(1); + e->Xw[2] = Xw.at(2); + + optimizer.addEdge(e); + + vpEdgesStereo.push_back(e); + vnIndexEdgeStereo.push_back(i); + } + } + + } + } + + + if(nInitialCorrespondences<3) + return 0; + + // We perform 4 optimizations, after each optimization we classify observation as inlier/outlier + // At the next optimization, outliers are not included, but at the end they can be classified as inliers again. + const float chi2Mono[4]={5.991,5.991,5.991,5.991}; + const float chi2Stereo[4]={7.815,7.815,7.815, 7.815}; + const int its[4]={10,10,10,10}; + + int nBad=0; + for(size_t it=0; it<4; it++) + { + + vSE3->setEstimate(Converter::toSE3Quat(pFrame->mTcw)); + optimizer.initializeOptimization(0); + optimizer.optimize(its[it]); + + nBad=0; + for(size_t i=0, iend=vpEdgesMono.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Mono[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBad++; + } + else + { + pFrame->mvbOutlier[idx]=false; + e->setLevel(0); + } + + if(it==2) + e->setRobustKernel(0); + } + + for(size_t i=0, iend=vpEdgesStereo.size(); imvbOutlier[idx]) + { + e->computeError(); + } + + const float chi2 = e->chi2(); + + if(chi2>chi2Stereo[it]) + { + pFrame->mvbOutlier[idx]=true; + e->setLevel(1); + nBad++; + } + else + { + e->setLevel(0); + pFrame->mvbOutlier[idx]=false; + } + + if(it==2) + e->setRobustKernel(0); + } + + if(optimizer.edges().size()<10) + break; + } + + // Recover optimized pose and return number of inliers + g2o::VertexSE3Expmap* vSE3_recov = static_cast(optimizer.vertex(0)); + g2o::SE3Quat SE3quat_recov = vSE3_recov->estimate(); + cv::Mat pose = Converter::toCvMat(SE3quat_recov); + pFrame->SetPose(pose); + + return nInitialCorrespondences-nBad; +} + +void Optimizer::LocalBundleAdjustment(KeyFrame *pKF, bool* pbStopFlag, Map* pMap) +{ + // Local KeyFrames: First Breath Search from Current Keyframe + list lLocalKeyFrames; + + lLocalKeyFrames.push_back(pKF); + pKF->mnBALocalForKF = pKF->mnId; + + const vector vNeighKFs = pKF->GetVectorCovisibleKeyFrames(); + for(int i=0, iend=vNeighKFs.size(); imnBALocalForKF = pKF->mnId; + if(!pKFi->isBad()) + lLocalKeyFrames.push_back(pKFi); + } + + // Local MapPoints seen in Local KeyFrames + list lLocalMapPoints; + for(list::iterator lit=lLocalKeyFrames.begin() , lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + vector vpMPs = (*lit)->GetMapPointMatches(); + for(vector::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + if(!pMP->isBad()) + if(pMP->mnBALocalForKF!=pKF->mnId) + { + lLocalMapPoints.push_back(pMP); + pMP->mnBALocalForKF=pKF->mnId; + } + } + } + + // Fixed Keyframes. Keyframes that see Local MapPoints but that are not Local Keyframes + list lFixedCameras; + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + map observations = (*lit)->GetObservations(); + for(map::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(pKFi->mnBALocalForKF!=pKF->mnId && pKFi->mnBAFixedForKF!=pKF->mnId) + { + pKFi->mnBAFixedForKF=pKF->mnId; + if(!pKFi->isBad()) + lFixedCameras.push_back(pKFi); + } + } + } + + // Setup optimizer + g2o::SparseOptimizer optimizer; + g2o::BlockSolver_6_3::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverEigen(); + + g2o::BlockSolver_6_3 * solver_ptr = new g2o::BlockSolver_6_3(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + if(pbStopFlag) + optimizer.setForceStopFlag(pbStopFlag); + + unsigned long maxKFid = 0; + + // Set Local KeyFrame vertices + for(list::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(pKFi->mnId==0); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + } + + // Set Fixed KeyFrame vertices + for(list::iterator lit=lFixedCameras.begin(), lend=lFixedCameras.end(); lit!=lend; lit++) + { + KeyFrame* pKFi = *lit; + g2o::VertexSE3Expmap * vSE3 = new g2o::VertexSE3Expmap(); + vSE3->setEstimate(Converter::toSE3Quat(pKFi->GetPose())); + vSE3->setId(pKFi->mnId); + vSE3->setFixed(true); + optimizer.addVertex(vSE3); + if(pKFi->mnId>maxKFid) + maxKFid=pKFi->mnId; + } + + // Set MapPoint vertices + const int nExpectedSize = (lLocalKeyFrames.size()+lFixedCameras.size())*lLocalMapPoints.size(); + + vector vpEdgesMono; + vpEdgesMono.reserve(nExpectedSize); + + vector vpEdgeKFMono; + vpEdgeKFMono.reserve(nExpectedSize); + + vector vpMapPointEdgeMono; + vpMapPointEdgeMono.reserve(nExpectedSize); + + vector vpEdgesStereo; + vpEdgesStereo.reserve(nExpectedSize); + + vector vpEdgeKFStereo; + vpEdgeKFStereo.reserve(nExpectedSize); + + vector vpMapPointEdgeStereo; + vpMapPointEdgeStereo.reserve(nExpectedSize); + + const float thHuberMono = sqrt(5.991); + const float thHuberStereo = sqrt(7.815); + + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = new g2o::VertexSBAPointXYZ(); + vPoint->setEstimate(Converter::toVector3d(pMP->GetWorldPos())); + int id = pMP->mnId+maxKFid+1; + vPoint->setId(id); + vPoint->setMarginalized(true); + optimizer.addVertex(vPoint); + + const map observations = pMP->GetObservations(); + + //Set edges + for(map::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++) + { + KeyFrame* pKFi = mit->first; + + if(!pKFi->isBad()) + { + const cv::KeyPoint &kpUn = pKFi->mvKeysUn[mit->second]; + + // Monocular observation + if(pKFi->mvuRight[mit->second]<0) + { + Eigen::Matrix obs; + obs << kpUn.pt.x, kpUn.pt.y; + + g2o::EdgeSE3ProjectXYZ* e = new g2o::EdgeSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + e->setInformation(Eigen::Matrix2d::Identity()*invSigma2); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberMono); + + e->fx = pKFi->fx; + e->fy = pKFi->fy; + e->cx = pKFi->cx; + e->cy = pKFi->cy; + + optimizer.addEdge(e); + vpEdgesMono.push_back(e); + vpEdgeKFMono.push_back(pKFi); + vpMapPointEdgeMono.push_back(pMP); + } + else // Stereo observation + { + Eigen::Matrix obs; + const float kp_ur = pKFi->mvuRight[mit->second]; + obs << kpUn.pt.x, kpUn.pt.y, kp_ur; + + g2o::EdgeStereoSE3ProjectXYZ* e = new g2o::EdgeStereoSE3ProjectXYZ(); + + e->setVertex(0, dynamic_cast(optimizer.vertex(id))); + e->setVertex(1, dynamic_cast(optimizer.vertex(pKFi->mnId))); + e->setMeasurement(obs); + const float &invSigma2 = pKFi->mvInvLevelSigma2[kpUn.octave]; + Eigen::Matrix3d Info = Eigen::Matrix3d::Identity()*invSigma2; + e->setInformation(Info); + + g2o::RobustKernelHuber* rk = new g2o::RobustKernelHuber; + e->setRobustKernel(rk); + rk->setDelta(thHuberStereo); + + e->fx = pKFi->fx; + e->fy = pKFi->fy; + e->cx = pKFi->cx; + e->cy = pKFi->cy; + e->bf = pKFi->mbf; + + optimizer.addEdge(e); + vpEdgesStereo.push_back(e); + vpEdgeKFStereo.push_back(pKFi); + vpMapPointEdgeStereo.push_back(pMP); + } + } + } + } + + if(pbStopFlag) + if(*pbStopFlag) + return; + + optimizer.initializeOptimization(); + optimizer.optimize(5); + + bool bDoMore= true; + + if(pbStopFlag) + if(*pbStopFlag) + bDoMore = false; + + if(bDoMore) + { + + // Check inlier observations + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + e->setLevel(1); + } + + e->setRobustKernel(0); + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + e->setLevel(1); + } + + e->setRobustKernel(0); + } + + // Optimize again without the outliers + + optimizer.initializeOptimization(0); + optimizer.optimize(10); + + } + + vector > vToErase; + vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size()); + + // Check inlier observations + for(size_t i=0, iend=vpEdgesMono.size(); iisBad()) + continue; + + if(e->chi2()>5.991 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFMono[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + for(size_t i=0, iend=vpEdgesStereo.size(); iisBad()) + continue; + + if(e->chi2()>7.815 || !e->isDepthPositive()) + { + KeyFrame* pKFi = vpEdgeKFStereo[i]; + vToErase.push_back(make_pair(pKFi,pMP)); + } + } + + // Get Map Mutex + unique_lock lock(pMap->mMutexMapUpdate); + + if(!vToErase.empty()) + { + for(size_t i=0;iEraseMapPointMatch(pMPi); + pMPi->EraseObservation(pKFi); + } + } + + // Recover optimized data + + //Keyframes + for(list::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++) + { + KeyFrame* pKF = *lit; + g2o::VertexSE3Expmap* vSE3 = static_cast(optimizer.vertex(pKF->mnId)); + g2o::SE3Quat SE3quat = vSE3->estimate(); + pKF->SetPose(Converter::toCvMat(SE3quat)); + } + + //Points + for(list::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + g2o::VertexSBAPointXYZ* vPoint = static_cast(optimizer.vertex(pMP->mnId+maxKFid+1)); + pMP->SetWorldPos(Converter::toCvMat(vPoint->estimate())); + pMP->UpdateNormalAndDepth(); + } +} + + +void Optimizer::OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF, + const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, + const LoopClosing::KeyFrameAndPose &CorrectedSim3, + const map > &LoopConnections, const bool &bFixScale) +{ + // Setup optimizer + g2o::SparseOptimizer optimizer; + optimizer.setVerbose(false); + g2o::BlockSolver_7_3::LinearSolverType * linearSolver = + new g2o::LinearSolverEigen(); + g2o::BlockSolver_7_3 * solver_ptr= new g2o::BlockSolver_7_3(linearSolver); + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + + solver->setUserLambdaInit(1e-16); + optimizer.setAlgorithm(solver); + + const vector vpKFs = pMap->GetAllKeyFrames(); + const vector vpMPs = pMap->GetAllMapPoints(); + + const unsigned int nMaxKFid = pMap->GetMaxKFid(); + + vector > vScw(nMaxKFid+1); + vector > vCorrectedSwc(nMaxKFid+1); + vector vpVertices(nMaxKFid+1); + + const int minFeat = 100; + + // Set KeyFrame vertices + for(size_t i=0, iend=vpKFs.size(); iisBad()) + continue; + g2o::VertexSim3Expmap* VSim3 = new g2o::VertexSim3Expmap(); + + const int nIDi = pKF->mnId; + + LoopClosing::KeyFrameAndPose::const_iterator it = CorrectedSim3.find(pKF); + + if(it!=CorrectedSim3.end()) + { + vScw[nIDi] = it->second; + VSim3->setEstimate(it->second); + } + else + { + Eigen::Matrix Rcw = Converter::toMatrix3d(pKF->GetRotation()); + Eigen::Matrix tcw = Converter::toVector3d(pKF->GetTranslation()); + g2o::Sim3 Siw(Rcw,tcw,1.0); + vScw[nIDi] = Siw; + VSim3->setEstimate(Siw); + } + + if(pKF==pLoopKF) + VSim3->setFixed(true); + + VSim3->setId(nIDi); + VSim3->setMarginalized(false); + VSim3->_fix_scale = bFixScale; + + optimizer.addVertex(VSim3); + + vpVertices[nIDi]=VSim3; + } + + + set > sInsertedEdges; + + const Eigen::Matrix matLambda = Eigen::Matrix::Identity(); + + // Set Loop edges + for(map >::const_iterator mit = LoopConnections.begin(), mend=LoopConnections.end(); mit!=mend; mit++) + { + KeyFrame* pKF = mit->first; + const long unsigned int nIDi = pKF->mnId; + const set &spConnections = mit->second; + const g2o::Sim3 Siw = vScw[nIDi]; + const g2o::Sim3 Swi = Siw.inverse(); + + for(set::const_iterator sit=spConnections.begin(), send=spConnections.end(); sit!=send; sit++) + { + const long unsigned int nIDj = (*sit)->mnId; + if((nIDi!=pCurKF->mnId || nIDj!=pLoopKF->mnId) && pKF->GetWeight(*sit)setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + + e->information() = matLambda; + + optimizer.addEdge(e); + + sInsertedEdges.insert(make_pair(min(nIDi,nIDj),max(nIDi,nIDj))); + } + } + + // Set normal edges + for(size_t i=0, iend=vpKFs.size(); imnId; + + g2o::Sim3 Swi; + + LoopClosing::KeyFrameAndPose::const_iterator iti = NonCorrectedSim3.find(pKF); + + if(iti!=NonCorrectedSim3.end()) + Swi = (iti->second).inverse(); + else + Swi = vScw[nIDi].inverse(); + + KeyFrame* pParentKF = pKF->GetParent(); + + // Spanning tree edge + if(pParentKF) + { + int nIDj = pParentKF->mnId; + + g2o::Sim3 Sjw; + + LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(pParentKF); + + if(itj!=NonCorrectedSim3.end()) + Sjw = itj->second; + else + Sjw = vScw[nIDj]; + + g2o::Sim3 Sji = Sjw * Swi; + + g2o::EdgeSim3* e = new g2o::EdgeSim3(); + e->setVertex(1, dynamic_cast(optimizer.vertex(nIDj))); + e->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + e->setMeasurement(Sji); + + e->information() = matLambda; + optimizer.addEdge(e); + } + + // Loop edges + const set sLoopEdges = pKF->GetLoopEdges(); + for(set::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++) + { + KeyFrame* pLKF = *sit; + if(pLKF->mnIdmnId) + { + g2o::Sim3 Slw; + + LoopClosing::KeyFrameAndPose::const_iterator itl = NonCorrectedSim3.find(pLKF); + + if(itl!=NonCorrectedSim3.end()) + Slw = itl->second; + else + Slw = vScw[pLKF->mnId]; + + g2o::Sim3 Sli = Slw * Swi; + g2o::EdgeSim3* el = new g2o::EdgeSim3(); + el->setVertex(1, dynamic_cast(optimizer.vertex(pLKF->mnId))); + el->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + el->setMeasurement(Sli); + el->information() = matLambda; + optimizer.addEdge(el); + } + } + + // Covisibility graph edges + const vector vpConnectedKFs = pKF->GetCovisiblesByWeight(minFeat); + for(vector::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++) + { + KeyFrame* pKFn = *vit; + if(pKFn && pKFn!=pParentKF && !pKF->hasChild(pKFn) && !sLoopEdges.count(pKFn)) + { + if(!pKFn->isBad() && pKFn->mnIdmnId) + { + if(sInsertedEdges.count(make_pair(min(pKF->mnId,pKFn->mnId),max(pKF->mnId,pKFn->mnId)))) + continue; + + g2o::Sim3 Snw; + + LoopClosing::KeyFrameAndPose::const_iterator itn = NonCorrectedSim3.find(pKFn); + + if(itn!=NonCorrectedSim3.end()) + Snw = itn->second; + else + Snw = vScw[pKFn->mnId]; + + g2o::Sim3 Sni = Snw * Swi; + + g2o::EdgeSim3* en = new g2o::EdgeSim3(); + en->setVertex(1, dynamic_cast(optimizer.vertex(pKFn->mnId))); + en->setVertex(0, dynamic_cast(optimizer.vertex(nIDi))); + en->setMeasurement(Sni); + en->information() = matLambda; + optimizer.addEdge(en); + } + } + } + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(20); + + unique_lock lock(pMap->mMutexMapUpdate); + + // SE3 Pose Recovering. Sim3:[sR t;0 1] -> SE3:[R t/s;0 1] + for(size_t i=0;imnId; + + g2o::VertexSim3Expmap* VSim3 = static_cast(optimizer.vertex(nIDi)); + g2o::Sim3 CorrectedSiw = VSim3->estimate(); + vCorrectedSwc[nIDi]=CorrectedSiw.inverse(); + Eigen::Matrix3d eigR = CorrectedSiw.rotation().toRotationMatrix(); + Eigen::Vector3d eigt = CorrectedSiw.translation(); + double s = CorrectedSiw.scale(); + + eigt *=(1./s); //[R t/s;0 1] + + cv::Mat Tiw = Converter::toCvSE3(eigR,eigt); + + pKFi->SetPose(Tiw); + } + + // Correct points. Transform to "non-optimized" reference keyframe pose and transform back with optimized pose + for(size_t i=0, iend=vpMPs.size(); iisBad()) + continue; + + int nIDr; + if(pMP->mnCorrectedByKF==pCurKF->mnId) + { + nIDr = pMP->mnCorrectedReference; + } + else + { + KeyFrame* pRefKF = pMP->GetReferenceKeyFrame(); + nIDr = pRefKF->mnId; + } + + + g2o::Sim3 Srw = vScw[nIDr]; + g2o::Sim3 correctedSwr = vCorrectedSwc[nIDr]; + + cv::Mat P3Dw = pMP->GetWorldPos(); + Eigen::Matrix eigP3Dw = Converter::toVector3d(P3Dw); + Eigen::Matrix eigCorrectedP3Dw = correctedSwr.map(Srw.map(eigP3Dw)); + + cv::Mat cvCorrectedP3Dw = Converter::toCvMat(eigCorrectedP3Dw); + pMP->SetWorldPos(cvCorrectedP3Dw); + + pMP->UpdateNormalAndDepth(); + } +} + +int Optimizer::OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, vector &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale) +{ + g2o::SparseOptimizer optimizer; + g2o::BlockSolverX::LinearSolverType * linearSolver; + + linearSolver = new g2o::LinearSolverDense(); + + g2o::BlockSolverX * solver_ptr = new g2o::BlockSolverX(linearSolver); + + g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(solver_ptr); + optimizer.setAlgorithm(solver); + + // Calibration + const cv::Mat &K1 = pKF1->mK; + const cv::Mat &K2 = pKF2->mK; + + // Camera poses + const cv::Mat R1w = pKF1->GetRotation(); + const cv::Mat t1w = pKF1->GetTranslation(); + const cv::Mat R2w = pKF2->GetRotation(); + const cv::Mat t2w = pKF2->GetTranslation(); + + // Set Sim3 vertex + g2o::VertexSim3Expmap * vSim3 = new g2o::VertexSim3Expmap(); + vSim3->_fix_scale=bFixScale; + vSim3->setEstimate(g2oS12); + vSim3->setId(0); + vSim3->setFixed(false); + vSim3->_principle_point1[0] = K1.at(0,2); + vSim3->_principle_point1[1] = K1.at(1,2); + vSim3->_focal_length1[0] = K1.at(0,0); + vSim3->_focal_length1[1] = K1.at(1,1); + vSim3->_principle_point2[0] = K2.at(0,2); + vSim3->_principle_point2[1] = K2.at(1,2); + vSim3->_focal_length2[0] = K2.at(0,0); + vSim3->_focal_length2[1] = K2.at(1,1); + optimizer.addVertex(vSim3); + + // Set MapPoint vertices + const int N = vpMatches1.size(); + const vector vpMapPoints1 = pKF1->GetMapPointMatches(); + vector vpEdges12; + vector vpEdges21; + vector vnIndexEdge; + + vnIndexEdge.reserve(2*N); + vpEdges12.reserve(2*N); + vpEdges21.reserve(2*N); + + const float deltaHuber = sqrt(th2); + + int nCorrespondences = 0; + + for(int i=0; iGetIndexInKeyFrame(pKF2); + + if(pMP1 && pMP2) + { + if(!pMP1->isBad() && !pMP2->isBad() && i2>=0) + { + g2o::VertexSBAPointXYZ* vPoint1 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D1w = pMP1->GetWorldPos(); + cv::Mat P3D1c = R1w*P3D1w + t1w; + vPoint1->setEstimate(Converter::toVector3d(P3D1c)); + vPoint1->setId(id1); + vPoint1->setFixed(true); + optimizer.addVertex(vPoint1); + + g2o::VertexSBAPointXYZ* vPoint2 = new g2o::VertexSBAPointXYZ(); + cv::Mat P3D2w = pMP2->GetWorldPos(); + cv::Mat P3D2c = R2w*P3D2w + t2w; + vPoint2->setEstimate(Converter::toVector3d(P3D2c)); + vPoint2->setId(id2); + vPoint2->setFixed(true); + optimizer.addVertex(vPoint2); + } + else + continue; + } + else + continue; + + nCorrespondences++; + + // Set edge x1 = S12*X2 + Eigen::Matrix obs1; + const cv::KeyPoint &kpUn1 = pKF1->mvKeysUn[i]; + obs1 << kpUn1.pt.x, kpUn1.pt.y; + + g2o::EdgeSim3ProjectXYZ* e12 = new g2o::EdgeSim3ProjectXYZ(); + e12->setVertex(0, dynamic_cast(optimizer.vertex(id2))); + e12->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e12->setMeasurement(obs1); + const float &invSigmaSquare1 = pKF1->mvInvLevelSigma2[kpUn1.octave]; + e12->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare1); + + g2o::RobustKernelHuber* rk1 = new g2o::RobustKernelHuber; + e12->setRobustKernel(rk1); + rk1->setDelta(deltaHuber); + optimizer.addEdge(e12); + + // Set edge x2 = S21*X1 + Eigen::Matrix obs2; + const cv::KeyPoint &kpUn2 = pKF2->mvKeysUn[i2]; + obs2 << kpUn2.pt.x, kpUn2.pt.y; + + g2o::EdgeInverseSim3ProjectXYZ* e21 = new g2o::EdgeInverseSim3ProjectXYZ(); + + e21->setVertex(0, dynamic_cast(optimizer.vertex(id1))); + e21->setVertex(1, dynamic_cast(optimizer.vertex(0))); + e21->setMeasurement(obs2); + float invSigmaSquare2 = pKF2->mvInvLevelSigma2[kpUn2.octave]; + e21->setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare2); + + g2o::RobustKernelHuber* rk2 = new g2o::RobustKernelHuber; + e21->setRobustKernel(rk2); + rk2->setDelta(deltaHuber); + optimizer.addEdge(e21); + + vpEdges12.push_back(e12); + vpEdges21.push_back(e21); + vnIndexEdge.push_back(i); + } + + // Optimize! + optimizer.initializeOptimization(); + optimizer.optimize(5); + + // Check inliers + int nBad=0; + for(size_t i=0; ichi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + optimizer.removeEdge(e12); + optimizer.removeEdge(e21); + vpEdges12[i]=static_cast(NULL); + vpEdges21[i]=static_cast(NULL); + nBad++; + } + } + + int nMoreIterations; + if(nBad>0) + nMoreIterations=10; + else + nMoreIterations=5; + + if(nCorrespondences-nBad<10) + return 0; + + // Optimize again only with inliers + + optimizer.initializeOptimization(); + optimizer.optimize(nMoreIterations); + + int nIn = 0; + for(size_t i=0; ichi2()>th2 || e21->chi2()>th2) + { + size_t idx = vnIndexEdge[i]; + vpMatches1[idx]=static_cast(NULL); + } + else + nIn++; + } + + // Recover optimized Sim3 + g2o::VertexSim3Expmap* vSim3_recov = static_cast(optimizer.vertex(0)); + g2oS12= vSim3_recov->estimate(); + + return nIn; +} + + +} //namespace ORB_SLAM diff --git a/src/PnPsolver.cc b/src/PnPsolver.cc new file mode 100644 index 0000000000..42a2065f4f --- /dev/null +++ b/src/PnPsolver.cc @@ -0,0 +1,1022 @@ +/** +* This file is part of ORB-SLAM2. +* This file is a modified version of EPnP , see FreeBSD license below. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +/** +* Copyright (c) 2009, V. Lepetit, EPFL +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions are met: +* +* 1. Redistributions of source code must retain the above copyright notice, this +* list of conditions and the following disclaimer. +* 2. Redistributions in binary form must reproduce the above copyright notice, +* this list of conditions and the following disclaimer in the documentation +* and/or other materials provided with the distribution. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR +* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +* +* The views and conclusions contained in the software and documentation are those +* of the authors and should not be interpreted as representing official policies, +* either expressed or implied, of the FreeBSD Project +*/ + +#include + +#include "PnPsolver.h" + +#include +#include +#include +#include "Thirdparty/DBoW2/DUtils/Random.h" +#include + +using namespace std; + +namespace ORB_SLAM2 +{ + + +PnPsolver::PnPsolver(const Frame &F, const vector &vpMapPointMatches): + pws(0), us(0), alphas(0), pcs(0), maximum_number_of_correspondences(0), number_of_correspondences(0), mnInliersi(0), + mnIterations(0), mnBestInliers(0), N(0) +{ + mvpMapPointMatches = vpMapPointMatches; + mvP2D.reserve(F.mvpMapPoints.size()); + mvSigma2.reserve(F.mvpMapPoints.size()); + mvP3Dw.reserve(F.mvpMapPoints.size()); + mvKeyPointIndices.reserve(F.mvpMapPoints.size()); + mvAllIndices.reserve(F.mvpMapPoints.size()); + + int idx=0; + for(size_t i=0, iend=vpMapPointMatches.size(); iisBad()) + { + const cv::KeyPoint &kp = F.mvKeysUn[i]; + + mvP2D.push_back(kp.pt); + mvSigma2.push_back(F.mvLevelSigma2[kp.octave]); + + cv::Mat Pos = pMP->GetWorldPos(); + mvP3Dw.push_back(cv::Point3f(Pos.at(0),Pos.at(1), Pos.at(2))); + + mvKeyPointIndices.push_back(i); + mvAllIndices.push_back(idx); + + idx++; + } + } + } + + // Set camera calibration parameters + fu = F.fx; + fv = F.fy; + uc = F.cx; + vc = F.cy; + + SetRansacParameters(); +} + +PnPsolver::~PnPsolver() +{ + delete [] pws; + delete [] us; + delete [] alphas; + delete [] pcs; +} + + +void PnPsolver::SetRansacParameters(double probability, int minInliers, int maxIterations, int minSet, float epsilon, float th2) +{ + mRansacProb = probability; + mRansacMinInliers = minInliers; + mRansacMaxIts = maxIterations; + mRansacEpsilon = epsilon; + mRansacMinSet = minSet; + + N = mvP2D.size(); // number of correspondences + + mvbInliersi.resize(N); + + // Adjust Parameters according to number of correspondences + int nMinInliers = N*mRansacEpsilon; + if(nMinInliers &vbInliers, int &nInliers) +{ + bool bFlag; + return iterate(mRansacMaxIts,bFlag,vbInliers,nInliers); +} + +cv::Mat PnPsolver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers) +{ + bNoMore = false; + vbInliers.clear(); + nInliers=0; + + set_maximum_number_of_correspondences(mRansacMinSet); + + if(N vAvailableIndices; + + int nCurrentIterations = 0; + while(mnIterations=mRansacMinInliers) + { + // If it is the best solution so far, save it + if(mnInliersi>mnBestInliers) + { + mvbBestInliers = mvbInliersi; + mnBestInliers = mnInliersi; + + cv::Mat Rcw(3,3,CV_64F,mRi); + cv::Mat tcw(3,1,CV_64F,mti); + Rcw.convertTo(Rcw,CV_32F); + tcw.convertTo(tcw,CV_32F); + mBestTcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(mBestTcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(mBestTcw.rowRange(0,3).col(3)); + } + + if(Refine()) + { + nInliers = mnRefinedInliers; + vbInliers = vector(mvpMapPointMatches.size(),false); + for(int i=0; i=mRansacMaxIts) + { + bNoMore=true; + if(mnBestInliers>=mRansacMinInliers) + { + nInliers=mnBestInliers; + vbInliers = vector(mvpMapPointMatches.size(),false); + for(int i=0; i vIndices; + vIndices.reserve(mvbBestInliers.size()); + + for(size_t i=0; imRansacMinInliers) + { + cv::Mat Rcw(3,3,CV_64F,mRi); + cv::Mat tcw(3,1,CV_64F,mti); + Rcw.convertTo(Rcw,CV_32F); + tcw.convertTo(tcw,CV_32F); + mRefinedTcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(mRefinedTcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(mRefinedTcw.rowRange(0,3).col(3)); + return true; + } + + return false; +} + + +void PnPsolver::CheckInliers() +{ + mnInliersi=0; + + for(int i=0; idata.db[3 * i + j] = pws[3 * i + j] - cws[0][j]; + + cvMulTransposed(PW0, &PW0tPW0, 1); + cvSVD(&PW0tPW0, &DC, &UCt, 0, CV_SVD_MODIFY_A | CV_SVD_U_T); + + cvReleaseMat(&PW0); + + for(int i = 1; i < 4; i++) { + double k = sqrt(dc[i - 1] / number_of_correspondences); + for(int j = 0; j < 3; j++) + cws[i][j] = cws[0][j] + k * uct[3 * (i - 1) + j]; + } +} + +void PnPsolver::compute_barycentric_coordinates(void) +{ + double cc[3 * 3], cc_inv[3 * 3]; + CvMat CC = cvMat(3, 3, CV_64F, cc); + CvMat CC_inv = cvMat(3, 3, CV_64F, cc_inv); + + for(int i = 0; i < 3; i++) + for(int j = 1; j < 4; j++) + cc[3 * i + j - 1] = cws[j][i] - cws[0][i]; + + cvInvert(&CC, &CC_inv, CV_SVD); + double * ci = cc_inv; + for(int i = 0; i < number_of_correspondences; i++) { + double * pi = pws + 3 * i; + double * a = alphas + 4 * i; + + for(int j = 0; j < 3; j++) + a[1 + j] = + ci[3 * j ] * (pi[0] - cws[0][0]) + + ci[3 * j + 1] * (pi[1] - cws[0][1]) + + ci[3 * j + 2] * (pi[2] - cws[0][2]); + a[0] = 1.0f - a[1] - a[2] - a[3]; + } +} + +void PnPsolver::fill_M(CvMat * M, + const int row, const double * as, const double u, const double v) +{ + double * M1 = M->data.db + row * 12; + double * M2 = M1 + 12; + + for(int i = 0; i < 4; i++) { + M1[3 * i ] = as[i] * fu; + M1[3 * i + 1] = 0.0; + M1[3 * i + 2] = as[i] * (uc - u); + + M2[3 * i ] = 0.0; + M2[3 * i + 1] = as[i] * fv; + M2[3 * i + 2] = as[i] * (vc - v); + } +} + +void PnPsolver::compute_ccs(const double * betas, const double * ut) +{ + for(int i = 0; i < 4; i++) + ccs[i][0] = ccs[i][1] = ccs[i][2] = 0.0f; + + for(int i = 0; i < 4; i++) { + const double * v = ut + 12 * (11 - i); + for(int j = 0; j < 4; j++) + for(int k = 0; k < 3; k++) + ccs[j][k] += betas[i] * v[3 * j + k]; + } +} + +void PnPsolver::compute_pcs(void) +{ + for(int i = 0; i < number_of_correspondences; i++) { + double * a = alphas + 4 * i; + double * pc = pcs + 3 * i; + + for(int j = 0; j < 3; j++) + pc[j] = a[0] * ccs[0][j] + a[1] * ccs[1][j] + a[2] * ccs[2][j] + a[3] * ccs[3][j]; + } +} + +double PnPsolver::compute_pose(double R[3][3], double t[3]) +{ + choose_control_points(); + compute_barycentric_coordinates(); + + CvMat * M = cvCreateMat(2 * number_of_correspondences, 12, CV_64F); + + for(int i = 0; i < number_of_correspondences; i++) + fill_M(M, 2 * i, alphas + 4 * i, us[2 * i], us[2 * i + 1]); + + double mtm[12 * 12], d[12], ut[12 * 12]; + CvMat MtM = cvMat(12, 12, CV_64F, mtm); + CvMat D = cvMat(12, 1, CV_64F, d); + CvMat Ut = cvMat(12, 12, CV_64F, ut); + + cvMulTransposed(M, &MtM, 1); + cvSVD(&MtM, &D, &Ut, 0, CV_SVD_MODIFY_A | CV_SVD_U_T); + cvReleaseMat(&M); + + double l_6x10[6 * 10], rho[6]; + CvMat L_6x10 = cvMat(6, 10, CV_64F, l_6x10); + CvMat Rho = cvMat(6, 1, CV_64F, rho); + + compute_L_6x10(ut, l_6x10); + compute_rho(rho); + + double Betas[4][4], rep_errors[4]; + double Rs[4][3][3], ts[4][3]; + + find_betas_approx_1(&L_6x10, &Rho, Betas[1]); + gauss_newton(&L_6x10, &Rho, Betas[1]); + rep_errors[1] = compute_R_and_t(ut, Betas[1], Rs[1], ts[1]); + + find_betas_approx_2(&L_6x10, &Rho, Betas[2]); + gauss_newton(&L_6x10, &Rho, Betas[2]); + rep_errors[2] = compute_R_and_t(ut, Betas[2], Rs[2], ts[2]); + + find_betas_approx_3(&L_6x10, &Rho, Betas[3]); + gauss_newton(&L_6x10, &Rho, Betas[3]); + rep_errors[3] = compute_R_and_t(ut, Betas[3], Rs[3], ts[3]); + + int N = 1; + if (rep_errors[2] < rep_errors[1]) N = 2; + if (rep_errors[3] < rep_errors[N]) N = 3; + + copy_R_and_t(Rs[N], ts[N], R, t); + + return rep_errors[N]; +} + +void PnPsolver::copy_R_and_t(const double R_src[3][3], const double t_src[3], + double R_dst[3][3], double t_dst[3]) +{ + for(int i = 0; i < 3; i++) { + for(int j = 0; j < 3; j++) + R_dst[i][j] = R_src[i][j]; + t_dst[i] = t_src[i]; + } +} + +double PnPsolver::dist2(const double * p1, const double * p2) +{ + return + (p1[0] - p2[0]) * (p1[0] - p2[0]) + + (p1[1] - p2[1]) * (p1[1] - p2[1]) + + (p1[2] - p2[2]) * (p1[2] - p2[2]); +} + +double PnPsolver::dot(const double * v1, const double * v2) +{ + return v1[0] * v2[0] + v1[1] * v2[1] + v1[2] * v2[2]; +} + +double PnPsolver::reprojection_error(const double R[3][3], const double t[3]) +{ + double sum2 = 0.0; + + for(int i = 0; i < number_of_correspondences; i++) { + double * pw = pws + 3 * i; + double Xc = dot(R[0], pw) + t[0]; + double Yc = dot(R[1], pw) + t[1]; + double inv_Zc = 1.0 / (dot(R[2], pw) + t[2]); + double ue = uc + fu * Xc * inv_Zc; + double ve = vc + fv * Yc * inv_Zc; + double u = us[2 * i], v = us[2 * i + 1]; + + sum2 += sqrt( (u - ue) * (u - ue) + (v - ve) * (v - ve) ); + } + + return sum2 / number_of_correspondences; +} + +void PnPsolver::estimate_R_and_t(double R[3][3], double t[3]) +{ + double pc0[3], pw0[3]; + + pc0[0] = pc0[1] = pc0[2] = 0.0; + pw0[0] = pw0[1] = pw0[2] = 0.0; + + for(int i = 0; i < number_of_correspondences; i++) { + const double * pc = pcs + 3 * i; + const double * pw = pws + 3 * i; + + for(int j = 0; j < 3; j++) { + pc0[j] += pc[j]; + pw0[j] += pw[j]; + } + } + for(int j = 0; j < 3; j++) { + pc0[j] /= number_of_correspondences; + pw0[j] /= number_of_correspondences; + } + + double abt[3 * 3], abt_d[3], abt_u[3 * 3], abt_v[3 * 3]; + CvMat ABt = cvMat(3, 3, CV_64F, abt); + CvMat ABt_D = cvMat(3, 1, CV_64F, abt_d); + CvMat ABt_U = cvMat(3, 3, CV_64F, abt_u); + CvMat ABt_V = cvMat(3, 3, CV_64F, abt_v); + + cvSetZero(&ABt); + for(int i = 0; i < number_of_correspondences; i++) { + double * pc = pcs + 3 * i; + double * pw = pws + 3 * i; + + for(int j = 0; j < 3; j++) { + abt[3 * j ] += (pc[j] - pc0[j]) * (pw[0] - pw0[0]); + abt[3 * j + 1] += (pc[j] - pc0[j]) * (pw[1] - pw0[1]); + abt[3 * j + 2] += (pc[j] - pc0[j]) * (pw[2] - pw0[2]); + } + } + + cvSVD(&ABt, &ABt_D, &ABt_U, &ABt_V, CV_SVD_MODIFY_A); + + for(int i = 0; i < 3; i++) + for(int j = 0; j < 3; j++) + R[i][j] = dot(abt_u + 3 * i, abt_v + 3 * j); + + const double det = + R[0][0] * R[1][1] * R[2][2] + R[0][1] * R[1][2] * R[2][0] + R[0][2] * R[1][0] * R[2][1] - + R[0][2] * R[1][1] * R[2][0] - R[0][1] * R[1][0] * R[2][2] - R[0][0] * R[1][2] * R[2][1]; + + if (det < 0) { + R[2][0] = -R[2][0]; + R[2][1] = -R[2][1]; + R[2][2] = -R[2][2]; + } + + t[0] = pc0[0] - dot(R[0], pw0); + t[1] = pc0[1] - dot(R[1], pw0); + t[2] = pc0[2] - dot(R[2], pw0); +} + +void PnPsolver::print_pose(const double R[3][3], const double t[3]) +{ + cout << R[0][0] << " " << R[0][1] << " " << R[0][2] << " " << t[0] << endl; + cout << R[1][0] << " " << R[1][1] << " " << R[1][2] << " " << t[1] << endl; + cout << R[2][0] << " " << R[2][1] << " " << R[2][2] << " " << t[2] << endl; +} + +void PnPsolver::solve_for_sign(void) +{ + if (pcs[2] < 0.0) { + for(int i = 0; i < 4; i++) + for(int j = 0; j < 3; j++) + ccs[i][j] = -ccs[i][j]; + + for(int i = 0; i < number_of_correspondences; i++) { + pcs[3 * i ] = -pcs[3 * i]; + pcs[3 * i + 1] = -pcs[3 * i + 1]; + pcs[3 * i + 2] = -pcs[3 * i + 2]; + } + } +} + +double PnPsolver::compute_R_and_t(const double * ut, const double * betas, + double R[3][3], double t[3]) +{ + compute_ccs(betas, ut); + compute_pcs(); + + solve_for_sign(); + + estimate_R_and_t(R, t); + + return reprojection_error(R, t); +} + +// betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] +// betas_approx_1 = [B11 B12 B13 B14] + +void PnPsolver::find_betas_approx_1(const CvMat * L_6x10, const CvMat * Rho, + double * betas) +{ + double l_6x4[6 * 4], b4[4]; + CvMat L_6x4 = cvMat(6, 4, CV_64F, l_6x4); + CvMat B4 = cvMat(4, 1, CV_64F, b4); + + for(int i = 0; i < 6; i++) { + cvmSet(&L_6x4, i, 0, cvmGet(L_6x10, i, 0)); + cvmSet(&L_6x4, i, 1, cvmGet(L_6x10, i, 1)); + cvmSet(&L_6x4, i, 2, cvmGet(L_6x10, i, 3)); + cvmSet(&L_6x4, i, 3, cvmGet(L_6x10, i, 6)); + } + + cvSolve(&L_6x4, Rho, &B4, CV_SVD); + + if (b4[0] < 0) { + betas[0] = sqrt(-b4[0]); + betas[1] = -b4[1] / betas[0]; + betas[2] = -b4[2] / betas[0]; + betas[3] = -b4[3] / betas[0]; + } else { + betas[0] = sqrt(b4[0]); + betas[1] = b4[1] / betas[0]; + betas[2] = b4[2] / betas[0]; + betas[3] = b4[3] / betas[0]; + } +} + +// betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] +// betas_approx_2 = [B11 B12 B22 ] + +void PnPsolver::find_betas_approx_2(const CvMat * L_6x10, const CvMat * Rho, + double * betas) +{ + double l_6x3[6 * 3], b3[3]; + CvMat L_6x3 = cvMat(6, 3, CV_64F, l_6x3); + CvMat B3 = cvMat(3, 1, CV_64F, b3); + + for(int i = 0; i < 6; i++) { + cvmSet(&L_6x3, i, 0, cvmGet(L_6x10, i, 0)); + cvmSet(&L_6x3, i, 1, cvmGet(L_6x10, i, 1)); + cvmSet(&L_6x3, i, 2, cvmGet(L_6x10, i, 2)); + } + + cvSolve(&L_6x3, Rho, &B3, CV_SVD); + + if (b3[0] < 0) { + betas[0] = sqrt(-b3[0]); + betas[1] = (b3[2] < 0) ? sqrt(-b3[2]) : 0.0; + } else { + betas[0] = sqrt(b3[0]); + betas[1] = (b3[2] > 0) ? sqrt(b3[2]) : 0.0; + } + + if (b3[1] < 0) betas[0] = -betas[0]; + + betas[2] = 0.0; + betas[3] = 0.0; +} + +// betas10 = [B11 B12 B22 B13 B23 B33 B14 B24 B34 B44] +// betas_approx_3 = [B11 B12 B22 B13 B23 ] + +void PnPsolver::find_betas_approx_3(const CvMat * L_6x10, const CvMat * Rho, + double * betas) +{ + double l_6x5[6 * 5], b5[5]; + CvMat L_6x5 = cvMat(6, 5, CV_64F, l_6x5); + CvMat B5 = cvMat(5, 1, CV_64F, b5); + + for(int i = 0; i < 6; i++) { + cvmSet(&L_6x5, i, 0, cvmGet(L_6x10, i, 0)); + cvmSet(&L_6x5, i, 1, cvmGet(L_6x10, i, 1)); + cvmSet(&L_6x5, i, 2, cvmGet(L_6x10, i, 2)); + cvmSet(&L_6x5, i, 3, cvmGet(L_6x10, i, 3)); + cvmSet(&L_6x5, i, 4, cvmGet(L_6x10, i, 4)); + } + + cvSolve(&L_6x5, Rho, &B5, CV_SVD); + + if (b5[0] < 0) { + betas[0] = sqrt(-b5[0]); + betas[1] = (b5[2] < 0) ? sqrt(-b5[2]) : 0.0; + } else { + betas[0] = sqrt(b5[0]); + betas[1] = (b5[2] > 0) ? sqrt(b5[2]) : 0.0; + } + if (b5[1] < 0) betas[0] = -betas[0]; + betas[2] = b5[3] / betas[0]; + betas[3] = 0.0; +} + +void PnPsolver::compute_L_6x10(const double * ut, double * l_6x10) +{ + const double * v[4]; + + v[0] = ut + 12 * 11; + v[1] = ut + 12 * 10; + v[2] = ut + 12 * 9; + v[3] = ut + 12 * 8; + + double dv[4][6][3]; + + for(int i = 0; i < 4; i++) { + int a = 0, b = 1; + for(int j = 0; j < 6; j++) { + dv[i][j][0] = v[i][3 * a ] - v[i][3 * b]; + dv[i][j][1] = v[i][3 * a + 1] - v[i][3 * b + 1]; + dv[i][j][2] = v[i][3 * a + 2] - v[i][3 * b + 2]; + + b++; + if (b > 3) { + a++; + b = a + 1; + } + } + } + + for(int i = 0; i < 6; i++) { + double * row = l_6x10 + 10 * i; + + row[0] = dot(dv[0][i], dv[0][i]); + row[1] = 2.0f * dot(dv[0][i], dv[1][i]); + row[2] = dot(dv[1][i], dv[1][i]); + row[3] = 2.0f * dot(dv[0][i], dv[2][i]); + row[4] = 2.0f * dot(dv[1][i], dv[2][i]); + row[5] = dot(dv[2][i], dv[2][i]); + row[6] = 2.0f * dot(dv[0][i], dv[3][i]); + row[7] = 2.0f * dot(dv[1][i], dv[3][i]); + row[8] = 2.0f * dot(dv[2][i], dv[3][i]); + row[9] = dot(dv[3][i], dv[3][i]); + } +} + +void PnPsolver::compute_rho(double * rho) +{ + rho[0] = dist2(cws[0], cws[1]); + rho[1] = dist2(cws[0], cws[2]); + rho[2] = dist2(cws[0], cws[3]); + rho[3] = dist2(cws[1], cws[2]); + rho[4] = dist2(cws[1], cws[3]); + rho[5] = dist2(cws[2], cws[3]); +} + +void PnPsolver::compute_A_and_b_gauss_newton(const double * l_6x10, const double * rho, + double betas[4], CvMat * A, CvMat * b) +{ + for(int i = 0; i < 6; i++) { + const double * rowL = l_6x10 + i * 10; + double * rowA = A->data.db + i * 4; + + rowA[0] = 2 * rowL[0] * betas[0] + rowL[1] * betas[1] + rowL[3] * betas[2] + rowL[6] * betas[3]; + rowA[1] = rowL[1] * betas[0] + 2 * rowL[2] * betas[1] + rowL[4] * betas[2] + rowL[7] * betas[3]; + rowA[2] = rowL[3] * betas[0] + rowL[4] * betas[1] + 2 * rowL[5] * betas[2] + rowL[8] * betas[3]; + rowA[3] = rowL[6] * betas[0] + rowL[7] * betas[1] + rowL[8] * betas[2] + 2 * rowL[9] * betas[3]; + + cvmSet(b, i, 0, rho[i] - + ( + rowL[0] * betas[0] * betas[0] + + rowL[1] * betas[0] * betas[1] + + rowL[2] * betas[1] * betas[1] + + rowL[3] * betas[0] * betas[2] + + rowL[4] * betas[1] * betas[2] + + rowL[5] * betas[2] * betas[2] + + rowL[6] * betas[0] * betas[3] + + rowL[7] * betas[1] * betas[3] + + rowL[8] * betas[2] * betas[3] + + rowL[9] * betas[3] * betas[3] + )); + } +} + +void PnPsolver::gauss_newton(const CvMat * L_6x10, const CvMat * Rho, + double betas[4]) +{ + const int iterations_number = 5; + + double a[6*4], b[6], x[4]; + CvMat A = cvMat(6, 4, CV_64F, a); + CvMat B = cvMat(6, 1, CV_64F, b); + CvMat X = cvMat(4, 1, CV_64F, x); + + for(int k = 0; k < iterations_number; k++) { + compute_A_and_b_gauss_newton(L_6x10->data.db, Rho->data.db, + betas, &A, &B); + qr_solve(&A, &B, &X); + + for(int i = 0; i < 4; i++) + betas[i] += x[i]; + } +} + +void PnPsolver::qr_solve(CvMat * A, CvMat * b, CvMat * X) +{ + static int max_nr = 0; + static double * A1, * A2; + + const int nr = A->rows; + const int nc = A->cols; + + if (max_nr != 0 && max_nr < nr) { + delete [] A1; + delete [] A2; + } + if (max_nr < nr) { + max_nr = nr; + A1 = new double[nr]; + A2 = new double[nr]; + } + + double * pA = A->data.db, * ppAkk = pA; + for(int k = 0; k < nc; k++) { + double * ppAik = ppAkk, eta = fabs(*ppAik); + for(int i = k + 1; i < nr; i++) { + double elt = fabs(*ppAik); + if (eta < elt) eta = elt; + ppAik += nc; + } + + if (eta == 0) { + A1[k] = A2[k] = 0.0; + cerr << "God damnit, A is singular, this shouldn't happen." << endl; + return; + } else { + double * ppAik = ppAkk, sum = 0.0, inv_eta = 1. / eta; + for(int i = k; i < nr; i++) { + *ppAik *= inv_eta; + sum += *ppAik * *ppAik; + ppAik += nc; + } + double sigma = sqrt(sum); + if (*ppAkk < 0) + sigma = -sigma; + *ppAkk += sigma; + A1[k] = sigma * *ppAkk; + A2[k] = -eta * sigma; + for(int j = k + 1; j < nc; j++) { + double * ppAik = ppAkk, sum = 0; + for(int i = k; i < nr; i++) { + sum += *ppAik * ppAik[j - k]; + ppAik += nc; + } + double tau = sum / A1[k]; + ppAik = ppAkk; + for(int i = k; i < nr; i++) { + ppAik[j - k] -= tau * *ppAik; + ppAik += nc; + } + } + } + ppAkk += nc + 1; + } + + // b <- Qt b + double * ppAjj = pA, * pb = b->data.db; + for(int j = 0; j < nc; j++) { + double * ppAij = ppAjj, tau = 0; + for(int i = j; i < nr; i++) { + tau += *ppAij * pb[i]; + ppAij += nc; + } + tau /= A1[j]; + ppAij = ppAjj; + for(int i = j; i < nr; i++) { + pb[i] -= tau * *ppAij; + ppAij += nc; + } + ppAjj += nc + 1; + } + + // X = R-1 b + double * pX = X->data.db; + pX[nc - 1] = pb[nc - 1] / A2[nc - 1]; + for(int i = nc - 2; i >= 0; i--) { + double * ppAij = pA + i * nc + (i + 1), sum = 0; + + for(int j = i + 1; j < nc; j++) { + sum += *ppAij * pX[j]; + ppAij++; + } + pX[i] = (pb[i] - sum) / A2[i]; + } +} + + + +void PnPsolver::relative_error(double & rot_err, double & transl_err, + const double Rtrue[3][3], const double ttrue[3], + const double Rest[3][3], const double test[3]) +{ + double qtrue[4], qest[4]; + + mat_to_quat(Rtrue, qtrue); + mat_to_quat(Rest, qest); + + double rot_err1 = sqrt((qtrue[0] - qest[0]) * (qtrue[0] - qest[0]) + + (qtrue[1] - qest[1]) * (qtrue[1] - qest[1]) + + (qtrue[2] - qest[2]) * (qtrue[2] - qest[2]) + + (qtrue[3] - qest[3]) * (qtrue[3] - qest[3]) ) / + sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]); + + double rot_err2 = sqrt((qtrue[0] + qest[0]) * (qtrue[0] + qest[0]) + + (qtrue[1] + qest[1]) * (qtrue[1] + qest[1]) + + (qtrue[2] + qest[2]) * (qtrue[2] + qest[2]) + + (qtrue[3] + qest[3]) * (qtrue[3] + qest[3]) ) / + sqrt(qtrue[0] * qtrue[0] + qtrue[1] * qtrue[1] + qtrue[2] * qtrue[2] + qtrue[3] * qtrue[3]); + + rot_err = min(rot_err1, rot_err2); + + transl_err = + sqrt((ttrue[0] - test[0]) * (ttrue[0] - test[0]) + + (ttrue[1] - test[1]) * (ttrue[1] - test[1]) + + (ttrue[2] - test[2]) * (ttrue[2] - test[2])) / + sqrt(ttrue[0] * ttrue[0] + ttrue[1] * ttrue[1] + ttrue[2] * ttrue[2]); +} + +void PnPsolver::mat_to_quat(const double R[3][3], double q[4]) +{ + double tr = R[0][0] + R[1][1] + R[2][2]; + double n4; + + if (tr > 0.0f) { + q[0] = R[1][2] - R[2][1]; + q[1] = R[2][0] - R[0][2]; + q[2] = R[0][1] - R[1][0]; + q[3] = tr + 1.0f; + n4 = q[3]; + } else if ( (R[0][0] > R[1][1]) && (R[0][0] > R[2][2]) ) { + q[0] = 1.0f + R[0][0] - R[1][1] - R[2][2]; + q[1] = R[1][0] + R[0][1]; + q[2] = R[2][0] + R[0][2]; + q[3] = R[1][2] - R[2][1]; + n4 = q[0]; + } else if (R[1][1] > R[2][2]) { + q[0] = R[1][0] + R[0][1]; + q[1] = 1.0f + R[1][1] - R[0][0] - R[2][2]; + q[2] = R[2][1] + R[1][2]; + q[3] = R[2][0] - R[0][2]; + n4 = q[1]; + } else { + q[0] = R[2][0] + R[0][2]; + q[1] = R[2][1] + R[1][2]; + q[2] = 1.0f + R[2][2] - R[0][0] - R[1][1]; + q[3] = R[0][1] - R[1][0]; + n4 = q[2]; + } + double scale = 0.5f / double(sqrt(n4)); + + q[0] *= scale; + q[1] *= scale; + q[2] *= scale; + q[3] *= scale; +} + +} //namespace ORB_SLAM diff --git a/src/Sim3Solver.cc b/src/Sim3Solver.cc new file mode 100644 index 0000000000..bcad1df24b --- /dev/null +++ b/src/Sim3Solver.cc @@ -0,0 +1,425 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include "Sim3Solver.h" + +#include +#include +#include + +#include "KeyFrame.h" +#include "ORBmatcher.h" + +#include "Thirdparty/DBoW2/DUtils/Random.h" + +namespace ORB_SLAM2 +{ + + +Sim3Solver::Sim3Solver(KeyFrame *pKF1, KeyFrame *pKF2, const vector &vpMatched12, const bool bFixScale): + mnIterations(0), mnBestInliers(0), mbFixScale(bFixScale) +{ + mpKF1 = pKF1; + mpKF2 = pKF2; + + vector vpKeyFrameMP1 = pKF1->GetMapPointMatches(); + + mN1 = vpMatched12.size(); + + mvpMapPoints1.reserve(mN1); + mvpMapPoints2.reserve(mN1); + mvpMatches12 = vpMatched12; + mvnIndices1.reserve(mN1); + mvX3Dc1.reserve(mN1); + mvX3Dc2.reserve(mN1); + + cv::Mat Rcw1 = pKF1->GetRotation(); + cv::Mat tcw1 = pKF1->GetTranslation(); + cv::Mat Rcw2 = pKF2->GetRotation(); + cv::Mat tcw2 = pKF2->GetTranslation(); + + mvAllIndices.reserve(mN1); + + size_t idx=0; + for(int i1=0; i1isBad() || pMP2->isBad()) + continue; + + int indexKF1 = pMP1->GetIndexInKeyFrame(pKF1); + int indexKF2 = pMP2->GetIndexInKeyFrame(pKF2); + + if(indexKF1<0 || indexKF2<0) + continue; + + const cv::KeyPoint &kp1 = pKF1->mvKeysUn[indexKF1]; + const cv::KeyPoint &kp2 = pKF2->mvKeysUn[indexKF2]; + + const float sigmaSquare1 = pKF1->mvLevelSigma2[kp1.octave]; + const float sigmaSquare2 = pKF2->mvLevelSigma2[kp2.octave]; + + mvnMaxError1.push_back(9.210*sigmaSquare1); + mvnMaxError2.push_back(9.210*sigmaSquare2); + + mvpMapPoints1.push_back(pMP1); + mvpMapPoints2.push_back(pMP2); + mvnIndices1.push_back(i1); + + cv::Mat X3D1w = pMP1->GetWorldPos(); + mvX3Dc1.push_back(Rcw1*X3D1w+tcw1); + + cv::Mat X3D2w = pMP2->GetWorldPos(); + mvX3Dc2.push_back(Rcw2*X3D2w+tcw2); + + mvAllIndices.push_back(idx); + idx++; + } + } + + mK1 = pKF1->mK; + mK2 = pKF2->mK; + + FromCameraToImage(mvX3Dc1,mvP1im1,mK1); + FromCameraToImage(mvX3Dc2,mvP2im2,mK2); + + SetRansacParameters(); +} + +void Sim3Solver::SetRansacParameters(double probability, int minInliers, int maxIterations) +{ + mRansacProb = probability; + mRansacMinInliers = minInliers; + mRansacMaxIts = maxIterations; + + N = mvpMapPoints1.size(); // number of correspondences + + mvbInliersi.resize(N); + + // Adjust Parameters according to number of correspondences + float epsilon = (float)mRansacMinInliers/N; + + // Set RANSAC iterations according to probability, epsilon, and max iterations + int nIterations; + + if(mRansacMinInliers==N) + nIterations=1; + else + nIterations = ceil(log(1-mRansacProb)/log(1-pow(epsilon,3))); + + mRansacMaxIts = max(1,min(nIterations,mRansacMaxIts)); + + mnIterations = 0; +} + +cv::Mat Sim3Solver::iterate(int nIterations, bool &bNoMore, vector &vbInliers, int &nInliers) +{ + bNoMore = false; + vbInliers = vector(mN1,false); + nInliers=0; + + if(N vAvailableIndices; + + cv::Mat P3Dc1i(3,3,CV_32F); + cv::Mat P3Dc2i(3,3,CV_32F); + + int nCurrentIterations = 0; + while(mnIterations=mnBestInliers) + { + mvbBestInliers = mvbInliersi; + mnBestInliers = mnInliersi; + mBestT12 = mT12i.clone(); + mBestRotation = mR12i.clone(); + mBestTranslation = mt12i.clone(); + mBestScale = ms12i; + + if(mnInliersi>mRansacMinInliers) + { + nInliers = mnInliersi; + for(int i=0; i=mRansacMaxIts) + bNoMore=true; + + return cv::Mat(); +} + +cv::Mat Sim3Solver::find(vector &vbInliers12, int &nInliers) +{ + bool bFlag; + return iterate(mRansacMaxIts,bFlag,vbInliers12,nInliers); +} + +void Sim3Solver::ComputeCentroid(cv::Mat &P, cv::Mat &Pr, cv::Mat &C) +{ + cv::reduce(P,C,1,CV_REDUCE_SUM); + C = C/P.cols; + + for(int i=0; i(0,0)+M.at(1,1)+M.at(2,2); + N12 = M.at(1,2)-M.at(2,1); + N13 = M.at(2,0)-M.at(0,2); + N14 = M.at(0,1)-M.at(1,0); + N22 = M.at(0,0)-M.at(1,1)-M.at(2,2); + N23 = M.at(0,1)+M.at(1,0); + N24 = M.at(2,0)+M.at(0,2); + N33 = -M.at(0,0)+M.at(1,1)-M.at(2,2); + N34 = M.at(1,2)+M.at(2,1); + N44 = -M.at(0,0)-M.at(1,1)+M.at(2,2); + + N = (cv::Mat_(4,4) << N11, N12, N13, N14, + N12, N22, N23, N24, + N13, N23, N33, N34, + N14, N24, N34, N44); + + + // Step 4: Eigenvector of the highest eigenvalue + + cv::Mat eval, evec; + + cv::eigen(N,eval,evec); //evec[0] is the quaternion of the desired rotation + + cv::Mat vec(1,3,evec.type()); + (evec.row(0).colRange(1,4)).copyTo(vec); //extract imaginary part of the quaternion (sin*axis) + + // Rotation angle. sin is the norm of the imaginary part, cos is the real part + double ang=atan2(norm(vec),evec.at(0,0)); + + vec = 2*ang*vec/norm(vec); //Angle-axis representation. quaternion angle is the half + + mR12i.create(3,3,P1.type()); + + cv::Rodrigues(vec,mR12i); // computes the rotation matrix from angle-axis + + // Step 5: Rotate set 2 + + cv::Mat P3 = mR12i*Pr2; + + // Step 6: Scale + + if(!mbFixScale) + { + double nom = Pr1.dot(P3); + cv::Mat aux_P3(P3.size(),P3.type()); + aux_P3=P3; + cv::pow(P3,2,aux_P3); + double den = 0; + + for(int i=0; i(i,j); + } + } + + ms12i = nom/den; + } + else + ms12i = 1.0f; + + // Step 7: Translation + + mt12i.create(1,3,P1.type()); + mt12i = O1 - ms12i*mR12i*O2; + + // Step 8: Transformation + + // Step 8.1 T12 + mT12i = cv::Mat::eye(4,4,P1.type()); + + cv::Mat sR = ms12i*mR12i; + + sR.copyTo(mT12i.rowRange(0,3).colRange(0,3)); + mt12i.copyTo(mT12i.rowRange(0,3).col(3)); + + // Step 8.2 T21 + + mT21i = cv::Mat::eye(4,4,P1.type()); + + cv::Mat sRinv = (1.0/ms12i)*mR12i.t(); + + sRinv.copyTo(mT21i.rowRange(0,3).colRange(0,3)); + cv::Mat tinv = -sRinv*mt12i; + tinv.copyTo(mT21i.rowRange(0,3).col(3)); +} + + +void Sim3Solver::CheckInliers() +{ + vector vP1im2, vP2im1; + Project(mvX3Dc2,vP2im1,mT12i,mK1); + Project(mvX3Dc1,vP1im2,mT21i,mK2); + + mnInliersi=0; + + for(size_t i=0; i &vP3Dw, vector &vP2D, cv::Mat Tcw, cv::Mat K) +{ + cv::Mat Rcw = Tcw.rowRange(0,3).colRange(0,3); + cv::Mat tcw = Tcw.rowRange(0,3).col(3); + const float &fx = K.at(0,0); + const float &fy = K.at(1,1); + const float &cx = K.at(0,2); + const float &cy = K.at(1,2); + + vP2D.clear(); + vP2D.reserve(vP3Dw.size()); + + for(size_t i=0, iend=vP3Dw.size(); i(2)); + const float x = P3Dc.at(0)*invz; + const float y = P3Dc.at(1)*invz; + + vP2D.push_back((cv::Mat_(2,1) << fx*x+cx, fy*y+cy)); + } +} + +void Sim3Solver::FromCameraToImage(const vector &vP3Dc, vector &vP2D, cv::Mat K) +{ + const float &fx = K.at(0,0); + const float &fy = K.at(1,1); + const float &cx = K.at(0,2); + const float &cy = K.at(1,2); + + vP2D.clear(); + vP2D.reserve(vP3Dc.size()); + + for(size_t i=0, iend=vP3Dc.size(); i(2)); + const float x = vP3Dc[i].at(0)*invz; + const float y = vP3Dc[i].at(1)*invz; + + vP2D.push_back((cv::Mat_(2,1) << fx*x+cx, fy*y+cy)); + } +} + +} //namespace ORB_SLAM diff --git a/src/System.cc b/src/System.cc new file mode 100644 index 0000000000..6e0dba1ad4 --- /dev/null +++ b/src/System.cc @@ -0,0 +1,422 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + + +#include "System.h" +#include "Converter.h" +#include + +namespace ORB_SLAM2 +{ + +System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor, + const bool bUseViewer):mSensor(sensor),mbReset(false),mbActivateLocalizationMode(false), + mbDeactivateLocalizationMode(false) +{ + // Output welcome message + cout << endl << + "ORB-SLAM2 Copyright (C) 2014-2016 Raul Mur-Artal, University of Zaragoza." << endl << + "This program comes with ABSOLUTELY NO WARRANTY;" << endl << + "This is free software, and you are welcome to redistribute it" << endl << + "under certain conditions. See LICENSE.txt." << endl << endl; + + cout << "Input sensor was set to: "; + + if(mSensor==MONOCULAR) + cout << "Monocular" << endl; + else if(mSensor==STEREO) + cout << "Stereo" << endl; + else if(mSensor==RGBD) + cout << "RGB-D" << endl; + + //Check settings file + cv::FileStorage fsSettings(strSettingsFile.c_str(), cv::FileStorage::READ); + if(!fsSettings.isOpened()) + { + cerr << "Failed to open settings file at: " << strSettingsFile << endl; + exit(-1); + } + + + //Load ORB Vocabulary + cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl; + + mpVocabulary = new ORBVocabulary(); + bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile); + if(!bVocLoad) + { + cerr << "Wrong path to vocabulary. " << endl; + cerr << "Falied to open at: " << strVocFile << endl; + exit(-1); + } + cout << "Vocabulary loaded!" << endl << endl; + + //Create KeyFrame Database + mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary); + + //Create the Map + mpMap = new Map(); + + //Create Drawers. These are used by the Viewer + mpFrameDrawer = new FrameDrawer(mpMap); + mpMapDrawer = new MapDrawer(mpMap, strSettingsFile); + + //Initialize the Tracking thread + //(it will live in the main thread of execution, the one that called this constructor) + mpTracker = new Tracking(mpVocabulary, mpFrameDrawer, mpMapDrawer, + mpMap, mpKeyFrameDatabase, strSettingsFile, mSensor); + + //Initialize the Local Mapping thread and launch + mpLocalMapper = new LocalMapping(mpMap, mSensor==MONOCULAR); + mptLocalMapping = new thread(&ORB_SLAM2::LocalMapping::Run,mpLocalMapper); + + //Initialize the Loop Closing thread and launch + mpLoopCloser = new LoopClosing(mpMap, mpKeyFrameDatabase, mpVocabulary, mSensor!=MONOCULAR); + mptLoopClosing = new thread(&ORB_SLAM2::LoopClosing::Run, mpLoopCloser); + + //Initialize the Viewer thread and launch + mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile); + if(bUseViewer) + mptViewer = new thread(&Viewer::Run, mpViewer); + + mpTracker->SetViewer(mpViewer); + + //Set pointers between threads + mpTracker->SetLocalMapper(mpLocalMapper); + mpTracker->SetLoopClosing(mpLoopCloser); + + mpLocalMapper->SetTracker(mpTracker); + mpLocalMapper->SetLoopCloser(mpLoopCloser); + + mpLoopCloser->SetTracker(mpTracker); + mpLoopCloser->SetLocalMapper(mpLocalMapper); +} + +cv::Mat System::TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const double ×tamp) +{ + if(mSensor!=STEREO) + { + cerr << "ERROR: you called TrackStereo but input sensor was not set to STEREO." << endl; + exit(-1); + } + + // Check mode change + { + unique_lock lock(mMutexMode); + if(mbActivateLocalizationMode) + { + mpLocalMapper->RequestStop(); + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + mpTracker->InformOnlyTracking(true); + mbActivateLocalizationMode = false; + } + if(mbDeactivateLocalizationMode) + { + mpTracker->InformOnlyTracking(false); + mpLocalMapper->Release(); + mbDeactivateLocalizationMode = false; + } + } + + // Check reset + { + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + mbReset = false; + } + } + + return mpTracker->GrabImageStereo(imLeft,imRight,timestamp); +} + +cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double ×tamp) +{ + if(mSensor!=RGBD) + { + cerr << "ERROR: you called TrackRGBD but input sensor was not set to RGBD." << endl; + exit(-1); + } + + // Check mode change + { + unique_lock lock(mMutexMode); + if(mbActivateLocalizationMode) + { + mpLocalMapper->RequestStop(); + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + mpTracker->InformOnlyTracking(true); + mbActivateLocalizationMode = false; + } + if(mbDeactivateLocalizationMode) + { + mpTracker->InformOnlyTracking(false); + mpLocalMapper->Release(); + mbDeactivateLocalizationMode = false; + } + } + + // Check reset + { + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + mbReset = false; + } + } + + return mpTracker->GrabImageRGBD(im,depthmap,timestamp); +} + +cv::Mat System::TrackMonocular(const cv::Mat &im, const double ×tamp) +{ + if(mSensor!=MONOCULAR) + { + cerr << "ERROR: you called TrackMonocular but input sensor was not set to Monocular." << endl; + exit(-1); + } + + // Check mode change + { + unique_lock lock(mMutexMode); + if(mbActivateLocalizationMode) + { + mpLocalMapper->RequestStop(); + + // Wait until Local Mapping has effectively stopped + while(!mpLocalMapper->isStopped()) + { + usleep(1000); + } + + mpTracker->InformOnlyTracking(true); + mbActivateLocalizationMode = false; + } + if(mbDeactivateLocalizationMode) + { + mpTracker->InformOnlyTracking(false); + mpLocalMapper->Release(); + mbDeactivateLocalizationMode = false; + } + } + + // Check reset + { + unique_lock lock(mMutexReset); + if(mbReset) + { + mpTracker->Reset(); + mbReset = false; + } + } + + return mpTracker->GrabImageMonocular(im,timestamp); +} + +void System::ActivateLocalizationMode() +{ + unique_lock lock(mMutexMode); + mbActivateLocalizationMode = true; +} + +void System::DeactivateLocalizationMode() +{ + unique_lock lock(mMutexMode); + mbDeactivateLocalizationMode = true; +} + +void System::Reset() +{ + unique_lock lock(mMutexReset); + mbReset = true; +} + +void System::Shutdown() +{ + mpLocalMapper->RequestFinish(); + mpLoopCloser->RequestFinish(); + mpViewer->RequestFinish(); + + // Wait until all thread have effectively stopped + while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() || + !mpViewer->isFinished() || mpLoopCloser->isRunningGBA()) + { + usleep(5000); + } +} + +void System::SaveTrajectoryTUM(const string &filename) +{ + cout << endl << "Saving camera trajectory to " << filename << " ..." << endl; + + vector vpKFs = mpMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + cv::Mat Two = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + list::iterator lbL = mpTracker->mlbLost.begin(); + for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), + lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++, lbL++) + { + if(*lbL) + continue; + + KeyFrame* pKF = *lRit; + + cv::Mat Trw = cv::Mat::eye(4,4,CV_32F); + + // If the reference keyframe was culled, traverse the spanning tree to get a suitable keyframe. + while(pKF->isBad()) + { + Trw = Trw*pKF->mTcp; + pKF = pKF->GetParent(); + } + + Trw = Trw*pKF->GetPose()*Two; + + cv::Mat Tcw = (*lit)*Trw; + cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); + + vector q = Converter::toQuaternion(Rwc); + + f << setprecision(6) << *lT << " " << setprecision(9) << twc.at(0) << " " << twc.at(1) << " " << twc.at(2) << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + } + f.close(); + cout << endl << "trajectory saved!" << endl; +} + + +void System::SaveKeyFrameTrajectoryTUM(const string &filename) +{ + cout << endl << "Saving keyframe trajectory to " << filename << " ..." << endl; + + vector vpKFs = mpMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + //cv::Mat Two = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + f << fixed; + + for(size_t i=0; iSetPose(pKF->GetPose()*Two); + + if(pKF->isBad()) + continue; + + cv::Mat R = pKF->GetRotation().t(); + vector q = Converter::toQuaternion(R); + cv::Mat t = pKF->GetCameraCenter(); + f << setprecision(6) << pKF->mTimeStamp << setprecision(7) << " " << t.at(0) << " " << t.at(1) << " " << t.at(2) + << " " << q[0] << " " << q[1] << " " << q[2] << " " << q[3] << endl; + + } + + f.close(); + cout << endl << "trajectory saved!" << endl; +} + +void System::SaveTrajectoryKITTI(const string &filename) +{ + cout << endl << "Saving camera trajectory to " << filename << " ..." << endl; + + vector vpKFs = mpMap->GetAllKeyFrames(); + sort(vpKFs.begin(),vpKFs.end(),KeyFrame::lId); + + // Transform all keyframes so that the first keyframe is at the origin. + // After a loop closure the first keyframe might not be at the origin. + cv::Mat Two = vpKFs[0]->GetPoseInverse(); + + ofstream f; + f.open(filename.c_str()); + f << fixed; + + // Frame pose is stored relative to its reference keyframe (which is optimized by BA and pose graph). + // We need to get first the keyframe pose and then concatenate the relative transformation. + // Frames not localized (tracking failure) are not saved. + + // For each frame we have a reference keyframe (lRit), the timestamp (lT) and a flag + // which is true when tracking failed (lbL). + list::iterator lRit = mpTracker->mlpReferences.begin(); + list::iterator lT = mpTracker->mlFrameTimes.begin(); + for(list::iterator lit=mpTracker->mlRelativeFramePoses.begin(), lend=mpTracker->mlRelativeFramePoses.end();lit!=lend;lit++, lRit++, lT++) + { + ORB_SLAM2::KeyFrame* pKF = *lRit; + + cv::Mat Trw = cv::Mat::eye(4,4,CV_32F); + + while(pKF->isBad()) + { + // cout << "bad parent" << endl; + Trw = Trw*pKF->mTcp; + pKF = pKF->GetParent(); + } + + Trw = Trw*pKF->GetPose()*Two; + + cv::Mat Tcw = (*lit)*Trw; + cv::Mat Rwc = Tcw.rowRange(0,3).colRange(0,3).t(); + cv::Mat twc = -Rwc*Tcw.rowRange(0,3).col(3); + + f << setprecision(9) << Rwc.at(0,0) << " " << Rwc.at(0,1) << " " << Rwc.at(0,2) << " " << twc.at(0) << " " << + Rwc.at(1,0) << " " << Rwc.at(1,1) << " " << Rwc.at(1,2) << " " << twc.at(1) << " " << + Rwc.at(2,0) << " " << Rwc.at(2,1) << " " << Rwc.at(2,2) << " " << twc.at(2) << endl; + } + f.close(); + cout << endl << "trajectory saved!" << endl; +} + +} //namespace ORB_SLAM diff --git a/src/Tracking.cc b/src/Tracking.cc new file mode 100644 index 0000000000..fcd002eedb --- /dev/null +++ b/src/Tracking.cc @@ -0,0 +1,1601 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + + +#include "Tracking.h" + +#include +#include + +#include"ORBmatcher.h" +#include"FrameDrawer.h" +#include"Converter.h" +#include"Map.h" +#include"Initializer.h" + +#include"Optimizer.h" +#include"PnPsolver.h" + +#include + +#include + + +using namespace std; + +namespace ORB_SLAM2 +{ + +Tracking::Tracking(ORBVocabulary* pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor): + mState(NO_IMAGES_YET), mSensor(sensor), mbOnlyTracking(false), mbVO(false), mpORBVocabulary(pVoc), + mpKeyFrameDB(pKFDB), mpInitializer(static_cast(NULL)), + mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpMap(pMap), mnLastRelocFrameId(0) +{ + // Load camera parameters from settings file + + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + float fx = fSettings["Camera.fx"]; + float fy = fSettings["Camera.fy"]; + float cx = fSettings["Camera.cx"]; + float cy = fSettings["Camera.cy"]; + + cv::Mat K = cv::Mat::eye(3,3,CV_32F); + K.at(0,0) = fx; + K.at(1,1) = fy; + K.at(0,2) = cx; + K.at(1,2) = cy; + K.copyTo(mK); + + cv::Mat DistCoef(4,1,CV_32F); + DistCoef.at(0) = fSettings["Camera.k1"]; + DistCoef.at(1) = fSettings["Camera.k2"]; + DistCoef.at(2) = fSettings["Camera.p1"]; + DistCoef.at(3) = fSettings["Camera.p2"]; + const float k3 = fSettings["Camera.k3"]; + if(k3!=0) + { + DistCoef.resize(5); + DistCoef.at(4) = k3; + } + DistCoef.copyTo(mDistCoef); + + mbf = fSettings["Camera.bf"]; + + float fps = fSettings["Camera.fps"]; + if(fps==0) + fps=30; + + // Max/Min Frames to insert keyframes and to check relocalisation + mMinFrames = 0; + mMaxFrames = fps; + + cout << endl << "Camera Parameters: " << endl; + cout << "- fx: " << fx << endl; + cout << "- fy: " << fy << endl; + cout << "- cx: " << cx << endl; + cout << "- cy: " << cy << endl; + cout << "- k1: " << DistCoef.at(0) << endl; + cout << "- k2: " << DistCoef.at(1) << endl; + if(DistCoef.rows==5) + cout << "- k3: " << DistCoef.at(4) << endl; + cout << "- p1: " << DistCoef.at(2) << endl; + cout << "- p2: " << DistCoef.at(3) << endl; + cout << "- fps: " << fps << endl; + + + int nRGB = fSettings["Camera.RGB"]; + mbRGB = nRGB; + + if(mbRGB) + cout << "- color order: RGB (ignored if grayscale)" << endl; + else + cout << "- color order: BGR (ignored if grayscale)" << endl; + + // Load ORB parameters + + int nFeatures = fSettings["ORBextractor.nFeatures"]; + float fScaleFactor = fSettings["ORBextractor.scaleFactor"]; + int nLevels = fSettings["ORBextractor.nLevels"]; + int fIniThFAST = fSettings["ORBextractor.iniThFAST"]; + int fMinThFAST = fSettings["ORBextractor.minThFAST"]; + + mpORBextractorLeft = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + if(sensor==System::STEREO) + mpORBextractorRight = new ORBextractor(nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + if(sensor==System::MONOCULAR) + mpIniORBextractor = new ORBextractor(2*nFeatures,fScaleFactor,nLevels,fIniThFAST,fMinThFAST); + + cout << endl << "ORB Extractor Parameters: " << endl; + cout << "- Number of Features: " << nFeatures << endl; + cout << "- Scale Levels: " << nLevels << endl; + cout << "- Scale Factor: " << fScaleFactor << endl; + cout << "- Initial Fast Threshold: " << fIniThFAST << endl; + cout << "- Minimum Fast Threshold: " << fMinThFAST << endl; + + if(sensor==System::STEREO || sensor==System::RGBD) + { + mThDepth = mbf*(float)fSettings["ThDepth"]/fx; + cout << endl << "Depth Threshold (Close/Far Points): " << mThDepth << endl; + } + + if(sensor==System::RGBD) + { + mDepthMapFactor = fSettings["DepthMapFactor"]; + if(mDepthMapFactor==0) + mDepthMapFactor=1; + else + mDepthMapFactor = 1.0f/mDepthMapFactor; + } + +} + +void Tracking::SetLocalMapper(LocalMapping *pLocalMapper) +{ + mpLocalMapper=pLocalMapper; +} + +void Tracking::SetLoopClosing(LoopClosing *pLoopClosing) +{ + mpLoopClosing=pLoopClosing; +} + +void Tracking::SetViewer(Viewer *pViewer) +{ + mpViewer=pViewer; +} + + +cv::Mat Tracking::GrabImageStereo(const cv::Mat &imRectLeft, const cv::Mat &imRectRight, const double ×tamp) +{ + mImGray = imRectLeft; + cv::Mat imGrayRight = imRectRight; + + if(mImGray.channels()==3) + { + if(mbRGB) + { + cvtColor(mImGray,mImGray,CV_RGB2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_RGB2GRAY); + } + else + { + cvtColor(mImGray,mImGray,CV_BGR2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_BGR2GRAY); + } + } + else if(mImGray.channels()==4) + { + if(mbRGB) + { + cvtColor(mImGray,mImGray,CV_RGBA2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_RGBA2GRAY); + } + else + { + cvtColor(mImGray,mImGray,CV_BGRA2GRAY); + cvtColor(imGrayRight,imGrayRight,CV_BGRA2GRAY); + } + } + + mCurrentFrame = Frame(mImGray,imGrayRight,timestamp,mpORBextractorLeft,mpORBextractorRight,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth); + + Track(); + + return mCurrentFrame.mTcw.clone(); +} + + +cv::Mat Tracking::GrabImageRGBD(const cv::Mat &imRGB,const cv::Mat &imD, const double ×tamp) +{ + mImGray = imRGB; + cv::Mat imDepth = imD; + + if(mImGray.channels()==3) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGB2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGR2GRAY); + } + else if(mImGray.channels()==4) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGBA2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGRA2GRAY); + } + + if(mDepthMapFactor!=1 || imDepth.type()!=CV_32F); + imDepth.convertTo(imDepth,CV_32F,mDepthMapFactor); + + mCurrentFrame = Frame(mImGray,imDepth,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth); + + Track(); + + return mCurrentFrame.mTcw.clone(); +} + + +cv::Mat Tracking::GrabImageMonocular(const cv::Mat &im, const double ×tamp) +{ + mImGray = im; + + if(mImGray.channels()==3) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGB2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGR2GRAY); + } + else if(mImGray.channels()==4) + { + if(mbRGB) + cvtColor(mImGray,mImGray,CV_RGBA2GRAY); + else + cvtColor(mImGray,mImGray,CV_BGRA2GRAY); + } + + if(mState==NOT_INITIALIZED || mState==NO_IMAGES_YET) + mCurrentFrame = Frame(mImGray,timestamp,mpIniORBextractor,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth); + else + mCurrentFrame = Frame(mImGray,timestamp,mpORBextractorLeft,mpORBVocabulary,mK,mDistCoef,mbf,mThDepth); + + Track(); + + return mCurrentFrame.mTcw.clone(); +} + +void Tracking::Track() +{ + if(mState==NO_IMAGES_YET) + { + mState = NOT_INITIALIZED; + } + + mLastProcessedState=mState; + + // Get Map Mutex -> Map cannot be changed + unique_lock lock(mpMap->mMutexMapUpdate); + + if(mState==NOT_INITIALIZED) + { + if(mSensor==System::STEREO || mSensor==System::RGBD) + StereoInitialization(); + else + MonocularInitialization(); + + mpFrameDrawer->Update(this); + + if(mState!=OK) + return; + } + else + { + // System is initialized. Track Frame. + bool bOK; + + // Initial camera pose estimation using motion model or relocalization (if tracking is lost) + if(!mbOnlyTracking) + { + // Local Mapping is activated. This is the normal behaviour, unless + // you explicitly activate the "only tracking" mode. + + if(mState==OK) + { + // Local Mapping might have changed some MapPoints tracked in last frame + CheckReplacedInLastFrame(); + + if(mVelocity.empty() || mCurrentFrame.mnId vpMPsMM; + vector vbOutMM; + cv::Mat TcwMM; + if(!mVelocity.empty()) + { + bOKMM = TrackWithMotionModel(); + vpMPsMM = mCurrentFrame.mvpMapPoints; + vbOutMM = mCurrentFrame.mvbOutlier; + TcwMM = mCurrentFrame.mTcw.clone(); + } + bOKReloc = Relocalization(); + + if(bOKMM && !bOKReloc) + { + mCurrentFrame.SetPose(TcwMM); + mCurrentFrame.mvpMapPoints = vpMPsMM; + mCurrentFrame.mvbOutlier = vbOutMM; + + if(mbVO) + { + for(int i =0; iIncreaseFound(); + } + } + } + } + else if(bOKReloc) + { + mbVO = false; + } + + bOK = bOKReloc || bOKMM; + } + } + } + + mCurrentFrame.mpReferenceKF = mpReferenceKF; + + // If we have an initial estimation of the camera pose and matching. Track the local map. + if(!mbOnlyTracking) + { + if(bOK) + bOK = TrackLocalMap(); + } + else + { + // mbVO true means that there are few matches to MapPoints in the map. We cannot retrieve + // a local map and therefore we do not perform TrackLocalMap(). Once the system relocalizes + // the camera we will use the local map again. + if(bOK && !mbVO) + bOK = TrackLocalMap(); + } + + if(bOK) + mState = OK; + else + mState=LOST; + + // Update drawer + mpFrameDrawer->Update(this); + + // If tracking were good, check if we insert a keyframe + if(bOK) + { + // Update motion model + if(!mLastFrame.mTcw.empty()) + { + cv::Mat LastTwc = cv::Mat::eye(4,4,CV_32F); + mLastFrame.GetRotationInverse().copyTo(LastTwc.rowRange(0,3).colRange(0,3)); + mLastFrame.GetCameraCenter().copyTo(LastTwc.rowRange(0,3).col(3)); + mVelocity = mCurrentFrame.mTcw*LastTwc; + } + else + mVelocity = cv::Mat(); + + mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw); + + // Clean temporal point matches + for(int i=0; iObservations()<1) + { + mCurrentFrame.mvbOutlier[i] = false; + mCurrentFrame.mvpMapPoints[i]=static_cast(NULL); + } + } + + // Delete temporal MapPoints + for(list::iterator lit = mlpTemporalPoints.begin(), lend = mlpTemporalPoints.end(); lit!=lend; lit++) + { + MapPoint* pMP = *lit; + delete pMP; + } + mlpTemporalPoints.clear(); + + // Check if we need to insert a new keyframe + if(NeedNewKeyFrame()) + CreateNewKeyFrame(); + + // We allow points with high innovation (considererd outliers by the Huber Function) + // pass to the new keyframe, so that bundle adjustment will finally decide + // if they are outliers or not. We don't want next frame to estimate its position + // with those points so we discard them in the frame. + for(int i=0; i(NULL); + } + } + + // Reset if the camera get lost soon after initialization + if(mState==LOST) + { + if(mpMap->KeyFramesInMap()<=5) + { + cout << "Track lost soon after initialisation, reseting..." << endl; + Reset(); + return; + } + } + + if(!mCurrentFrame.mpReferenceKF) + mCurrentFrame.mpReferenceKF = mpReferenceKF; + + mLastFrame = Frame(mCurrentFrame); + } + + // Store frame pose information to retrieve the complete camera trajectory afterwards. + if(!mCurrentFrame.mTcw.empty()) + { + cv::Mat Tcr = mCurrentFrame.mTcw*mCurrentFrame.mpReferenceKF->GetPoseInverse(); + mlRelativeFramePoses.push_back(Tcr); + mlpReferences.push_back(mpReferenceKF); + mlFrameTimes.push_back(mCurrentFrame.mTimeStamp); + mlbLost.push_back(mState==LOST); + } + else + { + // This can happen if tracking is lost + mlRelativeFramePoses.push_back(mlRelativeFramePoses.back()); + mlpReferences.push_back(mlpReferences.back()); + mlFrameTimes.push_back(mlFrameTimes.back()); + mlbLost.push_back(mState==LOST); + } + +} + + +void Tracking::StereoInitialization() +{ + if(mCurrentFrame.N>500) + { + // Set Frame pose to the origin + mCurrentFrame.SetPose(cv::Mat::eye(4,4,CV_32F)); + + // Create KeyFrame + KeyFrame* pKFini = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); + + // Insert KeyFrame in the map + mpMap->AddKeyFrame(pKFini); + + // Create MapPoints and asscoiate to KeyFrame + for(int i=0; i0) + { + cv::Mat x3D = mCurrentFrame.UnprojectStereo(i); + MapPoint* pNewMP = new MapPoint(x3D,pKFini,mpMap); + pNewMP->AddObservation(pKFini,i); + pKFini->AddMapPoint(pNewMP,i); + pNewMP->ComputeDistinctiveDescriptors(); + pNewMP->UpdateNormalAndDepth(); + mpMap->AddMapPoint(pNewMP); + + mCurrentFrame.mvpMapPoints[i]=pNewMP; + } + } + + cout << "New map created with " << mpMap->MapPointsInMap() << " points" << endl; + + mpLocalMapper->InsertKeyFrame(pKFini); + + mLastFrame = Frame(mCurrentFrame); + mnLastKeyFrameId=mCurrentFrame.mnId; + mpLastKeyFrame = pKFini; + + mvpLocalKeyFrames.push_back(pKFini); + mvpLocalMapPoints=mpMap->GetAllMapPoints(); + mpReferenceKF = pKFini; + mCurrentFrame.mpReferenceKF = pKFini; + + mpMap->SetReferenceMapPoints(mvpLocalMapPoints); + + mpMap->mvpKeyFrameOrigins.push_back(pKFini); + + mpMapDrawer->SetCurrentCameraPose(mCurrentFrame.mTcw); + + mState=OK; + } +} + +void Tracking::MonocularInitialization() +{ + + if(!mpInitializer) + { + // Set Reference Frame + if(mCurrentFrame.mvKeys.size()>100) + { + mInitialFrame = Frame(mCurrentFrame); + mLastFrame = Frame(mCurrentFrame); + mvbPrevMatched.resize(mCurrentFrame.mvKeysUn.size()); + for(size_t i=0; i(NULL); + fill(mvIniMatches.begin(),mvIniMatches.end(),-1); + return; + } + + // Find correspondences + ORBmatcher matcher(0.9,true); + int nmatches = matcher.SearchForInitialization(mInitialFrame,mCurrentFrame,mvbPrevMatched,mvIniMatches,100); + + // Check if there are enough correspondences + if(nmatches<100) + { + delete mpInitializer; + mpInitializer = static_cast(NULL); + return; + } + + cv::Mat Rcw; // Current Camera Rotation + cv::Mat tcw; // Current Camera Translation + vector vbTriangulated; // Triangulated Correspondences (mvIniMatches) + + if(mpInitializer->Initialize(mCurrentFrame, mvIniMatches, Rcw, tcw, mvIniP3D, vbTriangulated)) + { + for(size_t i=0, iend=mvIniMatches.size(); i=0 && !vbTriangulated[i]) + { + mvIniMatches[i]=-1; + nmatches--; + } + } + + // Set Frame Poses + mInitialFrame.SetPose(cv::Mat::eye(4,4,CV_32F)); + cv::Mat Tcw = cv::Mat::eye(4,4,CV_32F); + Rcw.copyTo(Tcw.rowRange(0,3).colRange(0,3)); + tcw.copyTo(Tcw.rowRange(0,3).col(3)); + mCurrentFrame.SetPose(Tcw); + + CreateInitialMapMonocular(); + } + } +} + +void Tracking::CreateInitialMapMonocular() +{ + // Create KeyFrames + KeyFrame* pKFini = new KeyFrame(mInitialFrame,mpMap,mpKeyFrameDB); + KeyFrame* pKFcur = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); + + + pKFini->ComputeBoW(); + pKFcur->ComputeBoW(); + + // Insert KFs in the map + mpMap->AddKeyFrame(pKFini); + mpMap->AddKeyFrame(pKFcur); + + // Create MapPoints and asscoiate to keyframes + for(size_t i=0; iAddMapPoint(pMP,i); + pKFcur->AddMapPoint(pMP,mvIniMatches[i]); + + pMP->AddObservation(pKFini,i); + pMP->AddObservation(pKFcur,mvIniMatches[i]); + + pMP->ComputeDistinctiveDescriptors(); + pMP->UpdateNormalAndDepth(); + + //Fill Current Frame structure + mCurrentFrame.mvpMapPoints[mvIniMatches[i]] = pMP; + mCurrentFrame.mvbOutlier[mvIniMatches[i]] = false; + + //Add to Map + mpMap->AddMapPoint(pMP); + } + + // Update Connections + pKFini->UpdateConnections(); + pKFcur->UpdateConnections(); + + // Bundle Adjustment + cout << "New Map created with " << mpMap->MapPointsInMap() << " points" << endl; + + Optimizer::GlobalBundleAdjustemnt(mpMap,20); + + // Set median depth to 1 + float medianDepth = pKFini->ComputeSceneMedianDepth(2); + float invMedianDepth = 1.0f/medianDepth; + + if(medianDepth<0 || pKFcur->TrackedMapPoints(1)<100) + { + cout << "Wrong initialization, reseting..." << endl; + Reset(); + return; + } + + // Scale initial baseline + cv::Mat Tc2w = pKFcur->GetPose(); + Tc2w.col(3).rowRange(0,3) = Tc2w.col(3).rowRange(0,3)*invMedianDepth; + pKFcur->SetPose(Tc2w); + + // Scale points + vector vpAllMapPoints = pKFini->GetMapPointMatches(); + for(size_t iMP=0; iMPSetWorldPos(pMP->GetWorldPos()*invMedianDepth); + } + } + + mpLocalMapper->InsertKeyFrame(pKFini); + mpLocalMapper->InsertKeyFrame(pKFcur); + + mCurrentFrame.SetPose(pKFcur->GetPose()); + mnLastKeyFrameId=mCurrentFrame.mnId; + mpLastKeyFrame = pKFcur; + + mvpLocalKeyFrames.push_back(pKFcur); + mvpLocalKeyFrames.push_back(pKFini); + mvpLocalMapPoints=mpMap->GetAllMapPoints(); + mpReferenceKF = pKFcur; + mCurrentFrame.mpReferenceKF = pKFcur; + + mLastFrame = Frame(mCurrentFrame); + + mpMap->SetReferenceMapPoints(mvpLocalMapPoints); + + mpMapDrawer->SetCurrentCameraPose(pKFcur->GetPose()); + + mpMap->mvpKeyFrameOrigins.push_back(pKFini); + + mState=OK; +} + +void Tracking::CheckReplacedInLastFrame() +{ + for(int i =0; iGetReplaced(); + if(pRep) + { + mLastFrame.mvpMapPoints[i] = pRep; + } + } + } +} + + +bool Tracking::TrackReferenceKeyFrame() +{ + // Compute Bag of Words vector + mCurrentFrame.ComputeBoW(); + + // We perform first an ORB matching with the reference keyframe + // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.7,true); + vector vpMapPointMatches; + + int nmatches = matcher.SearchByBoW(mpReferenceKF,mCurrentFrame,vpMapPointMatches); + + if(nmatches<15) + return false; + + mCurrentFrame.mvpMapPoints = vpMapPointMatches; + mCurrentFrame.SetPose(mLastFrame.mTcw); + + Optimizer::PoseOptimization(&mCurrentFrame); + + // Discard outliers + int nmatchesMap = 0; + for(int i =0; i(NULL); + mCurrentFrame.mvbOutlier[i]=false; + pMP->mbTrackInView = false; + pMP->mnLastFrameSeen = mCurrentFrame.mnId; + nmatches--; + } + else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0) + nmatchesMap++; + } + } + + return nmatchesMap>=10; +} + +void Tracking::UpdateLastFrame() +{ + // Update pose according to reference keyframe + KeyFrame* pRef = mLastFrame.mpReferenceKF; + cv::Mat Tlr = mlRelativeFramePoses.back(); + + mLastFrame.SetPose(Tlr*pRef->GetPose()); + + if(mnLastKeyFrameId==mLastFrame.mnId || mSensor==System::MONOCULAR) + return; + + // Create "visual odometry" MapPoints + // We sort points according to their measured depth by the stereo/RGB-D sensor + vector > vDepthIdx; + vDepthIdx.reserve(mLastFrame.N); + for(int i=0; i0) + { + vDepthIdx.push_back(make_pair(z,i)); + } + } + + if(vDepthIdx.empty()) + return; + + sort(vDepthIdx.begin(),vDepthIdx.end()); + + // We insert all close points (depthObservations()<1) + { + bCreateNew = true; + } + + if(bCreateNew) + { + cv::Mat x3D = mLastFrame.UnprojectStereo(i); + MapPoint* pNewMP = new MapPoint(x3D,mpMap,&mLastFrame,i); + + mLastFrame.mvpMapPoints[i]=pNewMP; + + mlpTemporalPoints.push_back(pNewMP); + nPoints++; + } + else + { + nPoints++; + } + + if(vDepthIdx[j].first>mThDepth && nPoints>100) + break; + } +} + +bool Tracking::TrackWithMotionModel() +{ + ORBmatcher matcher(0.9,true); + + // Update last frame pose according to its reference keyframe + // Create "visual odometry" points + UpdateLastFrame(); + + mCurrentFrame.SetPose(mVelocity*mLastFrame.mTcw); + + fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast(NULL)); + + // Project points seen in previous frame + int th; + if(mSensor!=System::STEREO) + th=15; + else + th=7; + int nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,th,mSensor==System::MONOCULAR); + + // If few matches, uses a wider window search + if(nmatches<20) + { + fill(mCurrentFrame.mvpMapPoints.begin(),mCurrentFrame.mvpMapPoints.end(),static_cast(NULL)); + nmatches = matcher.SearchByProjection(mCurrentFrame,mLastFrame,2*th,mSensor==System::MONOCULAR); + } + + if(nmatches<20) + return false; + + // Optimize frame pose with all matches + Optimizer::PoseOptimization(&mCurrentFrame); + + // Discard outliers + int nmatchesMap = 0; + for(int i =0; i(NULL); + mCurrentFrame.mvbOutlier[i]=false; + pMP->mbTrackInView = false; + pMP->mnLastFrameSeen = mCurrentFrame.mnId; + nmatches--; + } + else if(mCurrentFrame.mvpMapPoints[i]->Observations()>0) + nmatchesMap++; + } + } + + if(mbOnlyTracking) + { + mbVO = nmatchesMap<10; + return nmatches>20; + } + + return nmatchesMap>=10; +} + +bool Tracking::TrackLocalMap() +{ + // We have an estimation of the camera pose and some map points tracked in the frame. + // We retrieve the local map and try to find matches to points in the local map. + + UpdateLocalMap(); + + SearchLocalPoints(); + + // Optimize Pose + Optimizer::PoseOptimization(&mCurrentFrame); + mnMatchesInliers = 0; + + // Update MapPoints Statistics + for(int i=0; iIncreaseFound(); + if(!mbOnlyTracking) + { + if(mCurrentFrame.mvpMapPoints[i]->Observations()>0) + mnMatchesInliers++; + } + else + mnMatchesInliers++; + } + else if(mSensor==System::STEREO) + mCurrentFrame.mvpMapPoints[i] = static_cast(NULL); + + } + } + + // Decide if the tracking was succesful + // More restrictive if there was a relocalization recently + if(mCurrentFrame.mnIdisStopped() || mpLocalMapper->stopRequested()) + return false; + + const int nKFs = mpMap->KeyFramesInMap(); + + // Do not insert keyframes if not enough frames have passed from last relocalisation + if(mCurrentFrame.mnIdmMaxFrames) + return false; + + // Tracked MapPoints in the reference keyframe + int nMinObs = 3; + if(nKFs<=2) + nMinObs=2; + int nRefMatches = mpReferenceKF->TrackedMapPoints(nMinObs); + + // Local Mapping accept keyframes? + bool bLocalMappingIdle = mpLocalMapper->AcceptKeyFrames(); + + // Stereo & RGB-D: Ratio of close "matches to map"/"total matches" + // "total matches = matches to map + visual odometry matches" + // Visual odometry matches will become MapPoints if we insert a keyframe. + // This ratio measures how many MapPoints we could create if we insert a keyframe. + int nMap = 0; + int nTotal= 0; + if(mSensor!=System::MONOCULAR) + { + for(int i =0; i0 && mCurrentFrame.mvDepth[i]Observations()>0) + nMap++; + } + } + } + else + { + // There are no visual odometry matches in the monocular case + nMap=1; + nTotal=1; + } + + const float ratioMap = (float)nMap/fmax(1.0f,nTotal); + + // Thresholds + float thRefRatio = 0.75f; + if(nKFs<2) + thRefRatio = 0.4f; + + if(mSensor==System::MONOCULAR) + thRefRatio = 0.9f; + + float thMapRatio = 0.35f; + if(mnMatchesInliers>300) + thMapRatio = 0.20f; + + // Condition 1a: More than "MaxFrames" have passed from last keyframe insertion + const bool c1a = mCurrentFrame.mnId>=mnLastKeyFrameId+mMaxFrames; + // Condition 1b: More than "MinFrames" have passed and Local Mapping is idle + const bool c1b = (mCurrentFrame.mnId>=mnLastKeyFrameId+mMinFrames && bLocalMappingIdle); + //Condition 1c: tracking is weak + const bool c1c = mSensor!=System::MONOCULAR && (mnMatchesInliers15); + + if((c1a||c1b||c1c)&&c2) + { + // If the mapping accepts keyframes, insert keyframe. + // Otherwise send a signal to interrupt BA + if(bLocalMappingIdle) + { + return true; + } + else + { + mpLocalMapper->InterruptBA(); + if(mSensor!=System::MONOCULAR) + { + if(mpLocalMapper->KeyframesInQueue()<3) + return true; + else + return false; + } + else + return false; + } + } + else + return false; +} + +void Tracking::CreateNewKeyFrame() +{ + if(!mpLocalMapper->SetNotStop(true)) + return; + + KeyFrame* pKF = new KeyFrame(mCurrentFrame,mpMap,mpKeyFrameDB); + + mpReferenceKF = pKF; + mCurrentFrame.mpReferenceKF = pKF; + + if(mSensor!=System::MONOCULAR) + { + mCurrentFrame.UpdatePoseMatrices(); + + // We sort points by the measured depth by the stereo/RGBD sensor. + // We create all those MapPoints whose depth < mThDepth. + // If there are less than 100 close points we create the 100 closest. + vector > vDepthIdx; + vDepthIdx.reserve(mCurrentFrame.N); + for(int i=0; i0) + { + vDepthIdx.push_back(make_pair(z,i)); + } + } + + if(!vDepthIdx.empty()) + { + sort(vDepthIdx.begin(),vDepthIdx.end()); + + int nPoints = 0; + for(size_t j=0; jObservations()<1) + { + bCreateNew = true; + mCurrentFrame.mvpMapPoints[i] = static_cast(NULL); + } + + if(bCreateNew) + { + cv::Mat x3D = mCurrentFrame.UnprojectStereo(i); + MapPoint* pNewMP = new MapPoint(x3D,pKF,mpMap); + pNewMP->AddObservation(pKF,i); + pKF->AddMapPoint(pNewMP,i); + pNewMP->ComputeDistinctiveDescriptors(); + pNewMP->UpdateNormalAndDepth(); + mpMap->AddMapPoint(pNewMP); + + mCurrentFrame.mvpMapPoints[i]=pNewMP; + nPoints++; + } + else + { + nPoints++; + } + + if(vDepthIdx[j].first>mThDepth && nPoints>100) + break; + } + } + } + + mpLocalMapper->InsertKeyFrame(pKF); + + mpLocalMapper->SetNotStop(false); + + mnLastKeyFrameId = mCurrentFrame.mnId; + mpLastKeyFrame = pKF; +} + +void Tracking::SearchLocalPoints() +{ + // Do not search map points already matched + for(vector::iterator vit=mCurrentFrame.mvpMapPoints.begin(), vend=mCurrentFrame.mvpMapPoints.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP) + { + if(pMP->isBad()) + { + *vit = static_cast(NULL); + } + else + { + pMP->IncreaseVisible(); + pMP->mnLastFrameSeen = mCurrentFrame.mnId; + pMP->mbTrackInView = false; + } + } + } + + int nToMatch=0; + + // Project points in frame and check its visibility + for(vector::iterator vit=mvpLocalMapPoints.begin(), vend=mvpLocalMapPoints.end(); vit!=vend; vit++) + { + MapPoint* pMP = *vit; + if(pMP->mnLastFrameSeen == mCurrentFrame.mnId) + continue; + if(pMP->isBad()) + continue; + // Project (this fills MapPoint variables for matching) + if(mCurrentFrame.isInFrustum(pMP,0.5)) + { + pMP->IncreaseVisible(); + nToMatch++; + } + } + + if(nToMatch>0) + { + ORBmatcher matcher(0.8); + int th = 1; + if(mSensor==System::RGBD) + th=3; + // If the camera has been relocalised recently, perform a coarser search + if(mCurrentFrame.mnIdSetReferenceMapPoints(mvpLocalMapPoints); + + // Update + UpdateLocalKeyFrames(); + UpdateLocalPoints(); +} + +void Tracking::UpdateLocalPoints() +{ + mvpLocalMapPoints.clear(); + + for(vector::const_iterator itKF=mvpLocalKeyFrames.begin(), itEndKF=mvpLocalKeyFrames.end(); itKF!=itEndKF; itKF++) + { + KeyFrame* pKF = *itKF; + const vector vpMPs = pKF->GetMapPointMatches(); + + for(vector::const_iterator itMP=vpMPs.begin(), itEndMP=vpMPs.end(); itMP!=itEndMP; itMP++) + { + MapPoint* pMP = *itMP; + if(!pMP) + continue; + if(pMP->mnTrackReferenceForFrame==mCurrentFrame.mnId) + continue; + if(!pMP->isBad()) + { + mvpLocalMapPoints.push_back(pMP); + pMP->mnTrackReferenceForFrame=mCurrentFrame.mnId; + } + } + } +} + + +void Tracking::UpdateLocalKeyFrames() +{ + // Each map point vote for the keyframes in which it has been observed + map keyframeCounter; + for(int i=0; iisBad()) + { + const map observations = pMP->GetObservations(); + for(map::const_iterator it=observations.begin(), itend=observations.end(); it!=itend; it++) + keyframeCounter[it->first]++; + } + else + { + mCurrentFrame.mvpMapPoints[i]=NULL; + } + } + } + + if(keyframeCounter.empty()) + return; + + int max=0; + KeyFrame* pKFmax= static_cast(NULL); + + mvpLocalKeyFrames.clear(); + mvpLocalKeyFrames.reserve(3*keyframeCounter.size()); + + // All keyframes that observe a map point are included in the local map. Also check which keyframe shares most points + for(map::const_iterator it=keyframeCounter.begin(), itEnd=keyframeCounter.end(); it!=itEnd; it++) + { + KeyFrame* pKF = it->first; + + if(pKF->isBad()) + continue; + + if(it->second>max) + { + max=it->second; + pKFmax=pKF; + } + + mvpLocalKeyFrames.push_back(it->first); + pKF->mnTrackReferenceForFrame = mCurrentFrame.mnId; + } + + + // Include also some not-already-included keyframes that are neighbors to already-included keyframes + for(vector::const_iterator itKF=mvpLocalKeyFrames.begin(), itEndKF=mvpLocalKeyFrames.end(); itKF!=itEndKF; itKF++) + { + // Limit the number of keyframes + if(mvpLocalKeyFrames.size()>80) + break; + + KeyFrame* pKF = *itKF; + + const vector vNeighs = pKF->GetBestCovisibilityKeyFrames(10); + + for(vector::const_iterator itNeighKF=vNeighs.begin(), itEndNeighKF=vNeighs.end(); itNeighKF!=itEndNeighKF; itNeighKF++) + { + KeyFrame* pNeighKF = *itNeighKF; + if(!pNeighKF->isBad()) + { + if(pNeighKF->mnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(pNeighKF); + pNeighKF->mnTrackReferenceForFrame=mCurrentFrame.mnId; + break; + } + } + } + + const set spChilds = pKF->GetChilds(); + for(set::const_iterator sit=spChilds.begin(), send=spChilds.end(); sit!=send; sit++) + { + KeyFrame* pChildKF = *sit; + if(!pChildKF->isBad()) + { + if(pChildKF->mnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(pChildKF); + pChildKF->mnTrackReferenceForFrame=mCurrentFrame.mnId; + break; + } + } + } + + KeyFrame* pParent = pKF->GetParent(); + if(pParent) + { + if(pParent->mnTrackReferenceForFrame!=mCurrentFrame.mnId) + { + mvpLocalKeyFrames.push_back(pParent); + pParent->mnTrackReferenceForFrame=mCurrentFrame.mnId; + break; + } + } + + } + + if(pKFmax) + { + mpReferenceKF = pKFmax; + mCurrentFrame.mpReferenceKF = mpReferenceKF; + } +} + +bool Tracking::Relocalization() +{ + // Compute Bag of Words Vector + mCurrentFrame.ComputeBoW(); + + // Relocalization is performed when tracking is lost + // Track Lost: Query KeyFrame Database for keyframe candidates for relocalisation + vector vpCandidateKFs = mpKeyFrameDB->DetectRelocalizationCandidates(&mCurrentFrame); + + if(vpCandidateKFs.empty()) + return false; + + const int nKFs = vpCandidateKFs.size(); + + // We perform first an ORB matching with each candidate + // If enough matches are found we setup a PnP solver + ORBmatcher matcher(0.75,true); + + vector vpPnPsolvers; + vpPnPsolvers.resize(nKFs); + + vector > vvpMapPointMatches; + vvpMapPointMatches.resize(nKFs); + + vector vbDiscarded; + vbDiscarded.resize(nKFs); + + int nCandidates=0; + + for(int i=0; iisBad()) + vbDiscarded[i] = true; + else + { + int nmatches = matcher.SearchByBoW(pKF,mCurrentFrame,vvpMapPointMatches[i]); + if(nmatches<15) + { + vbDiscarded[i] = true; + continue; + } + else + { + PnPsolver* pSolver = new PnPsolver(mCurrentFrame,vvpMapPointMatches[i]); + pSolver->SetRansacParameters(0.99,10,300,4,0.5,5.991); + vpPnPsolvers[i] = pSolver; + nCandidates++; + } + } + } + + // Alternatively perform some iterations of P4P RANSAC + // Until we found a camera pose supported by enough inliers + bool bMatch = false; + ORBmatcher matcher2(0.9,true); + + while(nCandidates>0 && !bMatch) + { + for(int i=0; i vbInliers; + int nInliers; + bool bNoMore; + + PnPsolver* pSolver = vpPnPsolvers[i]; + cv::Mat Tcw = pSolver->iterate(5,bNoMore,vbInliers,nInliers); + + // If Ransac reachs max. iterations discard keyframe + if(bNoMore) + { + vbDiscarded[i]=true; + nCandidates--; + } + + // If a Camera Pose is computed, optimize + if(!Tcw.empty()) + { + Tcw.copyTo(mCurrentFrame.mTcw); + + set sFound; + + const int np = vbInliers.size(); + + for(int j=0; j(NULL); + + // If few inliers, search by projection in a coarse window and optimize again + if(nGood<50) + { + int nadditional =matcher2.SearchByProjection(mCurrentFrame,vpCandidateKFs[i],sFound,10,100); + + if(nadditional+nGood>=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + // If many inliers but still not enough, search by projection again in a narrower window + // the camera has been already optimized with many points + if(nGood>30 && nGood<50) + { + sFound.clear(); + for(int ip =0; ip=50) + { + nGood = Optimizer::PoseOptimization(&mCurrentFrame); + + for(int io =0; io=50) + { + bMatch = true; + break; + } + } + } + } + + if(!bMatch) + { + return false; + } + else + { + mnLastRelocFrameId = mCurrentFrame.mnId; + return true; + } + +} + +void Tracking::Reset() +{ + mpViewer->RequestStop(); + + cout << "System Reseting" << endl; + while(!mpViewer->isStopped()) + usleep(3000); + + // Reset Local Mapping + cout << "Reseting Local Mapper..."; + mpLocalMapper->RequestReset(); + cout << " done" << endl; + + // Reset Loop Closing + cout << "Reseting Loop Closing..."; + mpLoopClosing->RequestReset(); + cout << " done" << endl; + + // Clear BoW Database + cout << "Reseting Database..."; + mpKeyFrameDB->clear(); + cout << " done" << endl; + + // Clear Map (this erase MapPoints and KeyFrames) + mpMap->clear(); + + KeyFrame::nNextId = 0; + Frame::nNextId = 0; + mState = NO_IMAGES_YET; + + if(mpInitializer) + { + delete mpInitializer; + mpInitializer = static_cast(NULL); + } + + mlRelativeFramePoses.clear(); + mlpReferences.clear(); + mlFrameTimes.clear(); + mlbLost.clear(); + + mpViewer->Release(); +} + +void Tracking::ChangeCalibration(const string &strSettingPath) +{ + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + float fx = fSettings["Camera.fx"]; + float fy = fSettings["Camera.fy"]; + float cx = fSettings["Camera.cx"]; + float cy = fSettings["Camera.cy"]; + + cv::Mat K = cv::Mat::eye(3,3,CV_32F); + K.at(0,0) = fx; + K.at(1,1) = fy; + K.at(0,2) = cx; + K.at(1,2) = cy; + K.copyTo(mK); + + cv::Mat DistCoef(4,1,CV_32F); + DistCoef.at(0) = fSettings["Camera.k1"]; + DistCoef.at(1) = fSettings["Camera.k2"]; + DistCoef.at(2) = fSettings["Camera.p1"]; + DistCoef.at(3) = fSettings["Camera.p2"]; + const float k3 = fSettings["Camera.k3"]; + if(k3!=0) + { + DistCoef.resize(5); + DistCoef.at(4) = k3; + } + DistCoef.copyTo(mDistCoef); + + mbf = fSettings["Camera.bf"]; + + Frame::mbInitialComputations = true; +} + +void Tracking::InformOnlyTracking(const bool &flag) +{ + mbOnlyTracking = flag; +} + + + +} //namespace ORB_SLAM diff --git a/src/Viewer.cc b/src/Viewer.cc new file mode 100644 index 0000000000..92fa8468cc --- /dev/null +++ b/src/Viewer.cc @@ -0,0 +1,231 @@ +/** +* This file is part of ORB-SLAM2. +* +* Copyright (C) 2014-2016 Raúl Mur-Artal (University of Zaragoza) +* For more information see +* +* ORB-SLAM2 is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* ORB-SLAM2 is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with ORB-SLAM2. If not, see . +*/ + +#include "Viewer.h" +#include + +#include + +namespace ORB_SLAM2 +{ + +Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath): + mpSystem(pSystem), mpFrameDrawer(pFrameDrawer),mpMapDrawer(pMapDrawer), mpTracker(pTracking), + mbFinishRequested(false), mbFinished(true), mbStopped(false), mbStopRequested(false) +{ + cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ); + + float fps = fSettings["Camera.fps"]; + if(fps<1) + fps=30; + mT = 1e3/fps; + + mImageWidth = fSettings["Camera.width"]; + mImageHeight = fSettings["Camera.height"]; + if(mImageWidth<1 || mImageHeight<1) + { + mImageWidth = 640; + mImageHeight = 480; + } + + mViewpointX = fSettings["Viewer.ViewpointX"]; + mViewpointY = fSettings["Viewer.ViewpointY"]; + mViewpointZ = fSettings["Viewer.ViewpointZ"]; + mViewpointF = fSettings["Viewer.ViewpointF"]; +} + +void Viewer::Run() +{ + mbFinished = false; + + pangolin::CreateWindowAndBind("ORB-SLAM2: Map Viewer",1024,768); + + // 3D Mouse handler requires depth testing to be enabled + glEnable(GL_DEPTH_TEST); + + // Issue specific OpenGl we might need + glEnable (GL_BLEND); + glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(175)); + pangolin::Var menuFollowCamera("menu.Follow Camera",true,true); + pangolin::Var menuShowPoints("menu.Show Points",true,true); + pangolin::Var menuShowKeyFrames("menu.Show KeyFrames",true,true); + pangolin::Var menuShowGraph("menu.Show Graph",true,true); + pangolin::Var menuLocalizationMode("menu.Localization Mode",false,true); + pangolin::Var menuReset("menu.Reset",false,false); + + // Define Camera Render Object (for view / scene browsing) + pangolin::OpenGlRenderState s_cam( + pangolin::ProjectionMatrix(1024,768,mViewpointF,mViewpointF,512,389,0.1,1000), + pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0) + ); + + // Add named OpenGL viewport to window and provide 3D Handler + pangolin::View& d_cam = pangolin::CreateDisplay() + .SetBounds(0.0, 1.0, pangolin::Attach::Pix(175), 1.0, -1024.0f/768.0f) + .SetHandler(new pangolin::Handler3D(s_cam)); + + pangolin::OpenGlMatrix Twc; + Twc.SetIdentity(); + + cv::namedWindow("ORB-SLAM2: Current Frame"); + + bool bFollow = true; + bool bLocalizationMode = false; + + while(1) + { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + mpMapDrawer->GetCurrentOpenGLCameraMatrix(Twc); + + if(menuFollowCamera && bFollow) + { + s_cam.Follow(Twc); + } + else if(menuFollowCamera && !bFollow) + { + s_cam.SetModelViewMatrix(pangolin::ModelViewLookAt(mViewpointX,mViewpointY,mViewpointZ, 0,0,0,0.0,-1.0, 0.0)); + s_cam.Follow(Twc); + bFollow = true; + } + else if(!menuFollowCamera && bFollow) + { + bFollow = false; + } + + if(menuLocalizationMode && !bLocalizationMode) + { + mpSystem->ActivateLocalizationMode(); + bLocalizationMode = true; + } + else if(!menuLocalizationMode && bLocalizationMode) + { + mpSystem->DeactivateLocalizationMode(); + bLocalizationMode = false; + } + + d_cam.Activate(s_cam); + glClearColor(1.0f,1.0f,1.0f,1.0f); + mpMapDrawer->DrawCurrentCamera(Twc); + if(menuShowKeyFrames || menuShowGraph) + mpMapDrawer->DrawKeyFrames(menuShowKeyFrames,menuShowGraph); + if(menuShowPoints) + mpMapDrawer->DrawMapPoints(); + + pangolin::FinishFrame(); + + cv::Mat im = mpFrameDrawer->DrawFrame(); + cv::imshow("ORB-SLAM2: Current Frame",im); + cv::waitKey(mT); + + if(menuReset) + { + menuShowGraph = true; + menuShowKeyFrames = true; + menuShowPoints = true; + menuLocalizationMode = false; + if(bLocalizationMode) + mpSystem->DeactivateLocalizationMode(); + bLocalizationMode = false; + bFollow = true; + menuFollowCamera = true; + mpSystem->Reset(); + menuReset = false; + } + + if(Stop()) + { + while(isStopped()) + { + usleep(3000); + } + } + + if(CheckFinish()) + break; + } + + SetFinish(); +} + +void Viewer::RequestFinish() +{ + unique_lock lock(mMutexFinish); + mbFinishRequested = true; +} + +bool Viewer::CheckFinish() +{ + unique_lock lock(mMutexFinish); + return mbFinishRequested; +} + +void Viewer::SetFinish() +{ + unique_lock lock(mMutexFinish); + mbFinished = true; +} + +bool Viewer::isFinished() +{ + unique_lock lock(mMutexFinish); + return mbFinished; +} + +void Viewer::RequestStop() +{ + unique_lock lock(mMutexStop); + if(!mbStopped) + mbStopRequested = true; +} + +bool Viewer::isStopped() +{ + unique_lock lock(mMutexStop); + return mbStopped; +} + +bool Viewer::Stop() +{ + unique_lock lock(mMutexStop); + unique_lock lock2(mMutexFinish); + + if(mbFinishRequested) + return false; + else if(mbStopRequested) + { + mbStopped = true; + mbStopRequested = false; + return true; + } + + return false; + +} + +void Viewer::Release() +{ + unique_lock lock(mMutexStop); + mbStopped = false; +} + +}