the final version
This commit is contained in:
		
							parent
							
								
									86fcb0f3e6
								
							
						
					
					
						commit
						7096c35651
					
				
							
								
								
									
										118
									
								
								CMakeLists.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										118
									
								
								CMakeLists.txt
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,118 @@ | ||||
| cmake_minimum_required(VERSION 2.8) | ||||
| project(ORB_SLAM2) | ||||
| add_definitions(-w) | ||||
| 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 "-g -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 3.0 QUIET) | ||||
| if(NOT OpenCV_FOUND) | ||||
|    find_package(OpenCV 2.4.3 QUIET) | ||||
|    if(NOT OpenCV_FOUND) | ||||
|       message(FATAL_ERROR "OpenCV > 2.4.3 not found.") | ||||
|    endif() | ||||
| endif() | ||||
| 
 | ||||
| find_package(Eigen3 3.1.0 REQUIRED) | ||||
| find_package(Pangolin REQUIRED) | ||||
| find_package(PCL REQUIRED) | ||||
| 
 | ||||
| include_directories( | ||||
| ${PROJECT_SOURCE_DIR} | ||||
| ${PROJECT_SOURCE_DIR}/include | ||||
| ${PCL_INCLUDE_DIRS} | ||||
| ${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 | ||||
| src/MapObject.cpp | ||||
| ) | ||||
| 
 | ||||
| target_link_libraries(${PROJECT_NAME} | ||||
| ${OpenCV_LIBS} | ||||
| ${EIGEN3_LIBS} | ||||
| ${PCL_LIBRARIES} | ||||
| ${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}) | ||||
| 
 | ||||
| # add_executable(stereo_euroc | ||||
| # Examples/Stereo/stereo_euroc.cc) | ||||
| # target_link_libraries(stereo_euroc ${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}) | ||||
| 
 | ||||
| # add_executable(mono_euroc | ||||
| # Examples/Monocular/mono_euroc.cc) | ||||
| # target_link_libraries(mono_euroc ${PROJECT_NAME}) | ||||
| 
 | ||||
							
								
								
									
										57
									
								
								Examples/Monocular/EuRoC.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										57
									
								
								Examples/Monocular/EuRoC.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,57 @@ | ||||
| %YAML:1.0 | ||||
| 
 | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| # Camera Parameters. Adjust them! | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| 
 | ||||
| # Camera calibration and distortion parameters (OpenCV)  | ||||
| Camera.fx: 458.654 | ||||
| Camera.fy: 457.296 | ||||
| Camera.cx: 367.215 | ||||
| Camera.cy: 248.375 | ||||
| 
 | ||||
| Camera.k1: -0.28340811 | ||||
| Camera.k2: 0.07395907 | ||||
| Camera.p1: 0.00019359 | ||||
| Camera.p2: 1.76187114e-05 | ||||
| 
 | ||||
| # Camera frames per second  | ||||
| Camera.fps: 20.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 | ||||
| 
 | ||||
							
								
								
									
										3682
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH01.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										3682
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH01.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										3040
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH02.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										3040
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH02.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2700
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH03.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2700
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH03.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2033
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH04.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2033
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH04.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2273
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH05.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2273
									
								
								Examples/Monocular/EuRoC_TimeStamps/MH05.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2912
									
								
								Examples/Monocular/EuRoC_TimeStamps/V101.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2912
									
								
								Examples/Monocular/EuRoC_TimeStamps/V101.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										1710
									
								
								Examples/Monocular/EuRoC_TimeStamps/V102.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1710
									
								
								Examples/Monocular/EuRoC_TimeStamps/V102.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2149
									
								
								Examples/Monocular/EuRoC_TimeStamps/V103.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2149
									
								
								Examples/Monocular/EuRoC_TimeStamps/V103.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2280
									
								
								Examples/Monocular/EuRoC_TimeStamps/V201.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2280
									
								
								Examples/Monocular/EuRoC_TimeStamps/V201.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2348
									
								
								Examples/Monocular/EuRoC_TimeStamps/V202.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2348
									
								
								Examples/Monocular/EuRoC_TimeStamps/V202.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										1922
									
								
								Examples/Monocular/EuRoC_TimeStamps/V203.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1922
									
								
								Examples/Monocular/EuRoC_TimeStamps/V203.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										57
									
								
								Examples/Monocular/KITTI00-02.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										57
									
								
								Examples/Monocular/KITTI00-02.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										57
									
								
								Examples/Monocular/KITTI03.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										57
									
								
								Examples/Monocular/KITTI03.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										57
									
								
								Examples/Monocular/KITTI04-12.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										57
									
								
								Examples/Monocular/KITTI04-12.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										58
									
								
								Examples/Monocular/TUM1.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										58
									
								
								Examples/Monocular/TUM1.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										58
									
								
								Examples/Monocular/TUM2.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										58
									
								
								Examples/Monocular/TUM2.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										57
									
								
								Examples/Monocular/TUM3.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										57
									
								
								Examples/Monocular/TUM3.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										155
									
								
								Examples/Monocular/mono_euroc.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										155
									
								
								Examples/Monocular/mono_euroc.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,155 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| #include <unistd.h> | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include<System.h> | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| void LoadImages(const string &strImagePath, const string &strPathTimes, | ||||
|                 vector<string> &vstrImages, vector<double> &vTimeStamps); | ||||
| 
 | ||||
| int main(int argc, char **argv) | ||||
| { | ||||
|     if(argc != 5) | ||||
|     { | ||||
|         cerr << endl << "Usage: ./mono_tum path_to_vocabulary path_to_settings path_to_image_folder path_to_times_file" << endl; | ||||
|         return 1; | ||||
|     } | ||||
| 
 | ||||
|     // Retrieve paths to images
 | ||||
|     vector<string> vstrImageFilenames; | ||||
|     vector<double> vTimestamps; | ||||
|     LoadImages(string(argv[3]), string(argv[4]), vstrImageFilenames, vTimestamps); | ||||
| 
 | ||||
|     int nImages = vstrImageFilenames.size(); | ||||
| 
 | ||||
|     if(nImages<=0) | ||||
|     { | ||||
|         cerr << "ERROR: Failed to load images" << 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::MONOCULAR,true); | ||||
| 
 | ||||
|     // Vector for tracking time statistics
 | ||||
|     vector<float> 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<nImages; ni++) | ||||
|     { | ||||
|         // Read image from file
 | ||||
|         im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
|         double tframe = vTimestamps[ni]; | ||||
| 
 | ||||
|         if(im.empty()) | ||||
|         { | ||||
|             cerr << endl << "Failed to load image at: " | ||||
|                  <<  vstrImageFilenames[ni] << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         // Pass the image to the SLAM system
 | ||||
|         SLAM.TrackMonocular(im,tframe); | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); | ||||
| 
 | ||||
|         vTimesTrack[ni]=ttrack; | ||||
| 
 | ||||
|         // Wait to load the next frame
 | ||||
|         double T=0; | ||||
|         if(ni<nImages-1) | ||||
|             T = vTimestamps[ni+1]-tframe; | ||||
|         else if(ni>0) | ||||
|             T = tframe-vTimestamps[ni-1]; | ||||
| 
 | ||||
|         if(ttrack<T) | ||||
|             usleep((T-ttrack)*1e6); | ||||
|     } | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Tracking time statistics
 | ||||
|     sort(vTimesTrack.begin(),vTimesTrack.end()); | ||||
|     float totaltime = 0; | ||||
|     for(int ni=0; ni<nImages; ni++) | ||||
|     { | ||||
|         totaltime+=vTimesTrack[ni]; | ||||
|     } | ||||
|     cout << "-------" << endl << endl; | ||||
|     cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; | ||||
|     cout << "mean tracking time: " << totaltime/nImages << endl; | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void LoadImages(const string &strImagePath, const string &strPathTimes, | ||||
|                 vector<string> &vstrImages, vector<double> &vTimeStamps) | ||||
| { | ||||
|     ifstream fTimes; | ||||
|     fTimes.open(strPathTimes.c_str()); | ||||
|     vTimeStamps.reserve(5000); | ||||
|     vstrImages.reserve(5000); | ||||
|     while(!fTimes.eof()) | ||||
|     { | ||||
|         string s; | ||||
|         getline(fTimes,s); | ||||
|         if(!s.empty()) | ||||
|         { | ||||
|             stringstream ss; | ||||
|             ss << s; | ||||
|             vstrImages.push_back(strImagePath + "/" + ss.str() + ".png"); | ||||
|             double t; | ||||
|             ss >> t; | ||||
|             vTimeStamps.push_back(t/1e9); | ||||
| 
 | ||||
|         } | ||||
|     } | ||||
| } | ||||
							
								
								
									
										157
									
								
								Examples/Monocular/mono_kitti.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										157
									
								
								Examples/Monocular/mono_kitti.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,157 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| #include<iomanip> | ||||
| #include <unistd.h> | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include"System.h" | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| void LoadImages(const string &strSequence, vector<string> &vstrImageFilenames, | ||||
|                 vector<double> &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<string> vstrImageFilenames; | ||||
|     vector<double> 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<float> 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<nImages; ni++) | ||||
|     { | ||||
|         // Read image from file
 | ||||
|         im = cv::imread(vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
|         double tframe = vTimestamps[ni]; | ||||
| 
 | ||||
|         if(im.empty()) | ||||
|         { | ||||
|             cerr << endl << "Failed to load image at: " << vstrImageFilenames[ni] << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         // Pass the image to the SLAM system
 | ||||
|         SLAM.TrackMonocular(im,tframe); | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); | ||||
| 
 | ||||
|         vTimesTrack[ni]=ttrack; | ||||
| 
 | ||||
|         // Wait to load the next frame
 | ||||
|         double T=0; | ||||
|         if(ni<nImages-1) | ||||
|             T = vTimestamps[ni+1]-tframe; | ||||
|         else if(ni>0) | ||||
|             T = tframe-vTimestamps[ni-1]; | ||||
| 
 | ||||
|         if(ttrack<T) | ||||
|             usleep((T-ttrack)*1e6); | ||||
|     } | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Tracking time statistics
 | ||||
|     sort(vTimesTrack.begin(),vTimesTrack.end()); | ||||
|     float totaltime = 0; | ||||
|     for(int ni=0; ni<nImages; ni++) | ||||
|     { | ||||
|         totaltime+=vTimesTrack[ni]; | ||||
|     } | ||||
|     cout << "-------" << endl << endl; | ||||
|     cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; | ||||
|     cout << "mean tracking time: " << totaltime/nImages << endl; | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");     | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void LoadImages(const string &strPathToSequence, vector<string> &vstrImageFilenames, vector<double> &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<nTimes; i++) | ||||
|     { | ||||
|         stringstream ss; | ||||
|         ss << setfill('0') << setw(6) << i; | ||||
|         vstrImageFilenames[i] = strPrefixLeft + ss.str() + ".png"; | ||||
|     } | ||||
| } | ||||
							
								
								
									
										155
									
								
								Examples/Monocular/mono_tum.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										155
									
								
								Examples/Monocular/mono_tum.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,155 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| #include <unistd.h> | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include<System.h> | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, | ||||
|                 vector<double> &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<string> vstrImageFilenames; | ||||
|     vector<double> 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<float> 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<nImages; ni++) | ||||
|     { | ||||
|         // Read image from file
 | ||||
|         im = cv::imread(string(argv[3])+"/"+vstrImageFilenames[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
|         double tframe = vTimestamps[ni]; | ||||
| 
 | ||||
|         if(im.empty()) | ||||
|         { | ||||
|             cerr << endl << "Failed to load image at: " | ||||
|                  << string(argv[3]) << "/" << vstrImageFilenames[ni] << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         // Pass the image to the SLAM system
 | ||||
|         SLAM.TrackMonocular(im,tframe); | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); | ||||
| 
 | ||||
|         vTimesTrack[ni]=ttrack; | ||||
| 
 | ||||
|         // Wait to load the next frame
 | ||||
|         double T=0; | ||||
|         if(ni<nImages-1) | ||||
|             T = vTimestamps[ni+1]-tframe; | ||||
|         else if(ni>0) | ||||
|             T = tframe-vTimestamps[ni-1]; | ||||
| 
 | ||||
|         if(ttrack<T) | ||||
|             usleep((T-ttrack)*1e6); | ||||
|     } | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Tracking time statistics
 | ||||
|     sort(vTimesTrack.begin(),vTimesTrack.end()); | ||||
|     float totaltime = 0; | ||||
|     for(int ni=0; ni<nImages; ni++) | ||||
|     { | ||||
|         totaltime+=vTimesTrack[ni]; | ||||
|     } | ||||
|     cout << "-------" << endl << endl; | ||||
|     cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; | ||||
|     cout << "mean tracking time: " << totaltime/nImages << endl; | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void LoadImages(const string &strFile, vector<string> &vstrImageFilenames, vector<double> &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); | ||||
|         } | ||||
|     } | ||||
| } | ||||
							
								
								
									
										70
									
								
								Examples/RGB-D/TUM1.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										70
									
								
								Examples/RGB-D/TUM1.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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: 40.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 | ||||
| 
 | ||||
							
								
								
									
										70
									
								
								Examples/RGB-D/TUM2.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										70
									
								
								Examples/RGB-D/TUM2.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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: 40.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 | ||||
| 
 | ||||
							
								
								
									
										69
									
								
								Examples/RGB-D/TUM3.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										69
									
								
								Examples/RGB-D/TUM3.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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: 40.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 | ||||
| 
 | ||||
							
								
								
									
										573
									
								
								Examples/RGB-D/associations/fr1_desk.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										573
									
								
								Examples/RGB-D/associations/fr1_desk.txt
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										620
									
								
								Examples/RGB-D/associations/fr1_desk2.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										620
									
								
								Examples/RGB-D/associations/fr1_desk2.txt
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										1352
									
								
								Examples/RGB-D/associations/fr1_room.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1352
									
								
								Examples/RGB-D/associations/fr1_room.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										792
									
								
								Examples/RGB-D/associations/fr1_xyz.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										792
									
								
								Examples/RGB-D/associations/fr1_xyz.txt
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										2893
									
								
								Examples/RGB-D/associations/fr2_desk.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2893
									
								
								Examples/RGB-D/associations/fr2_desk.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										3615
									
								
								Examples/RGB-D/associations/fr2_xyz.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										3615
									
								
								Examples/RGB-D/associations/fr2_xyz.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										1639
									
								
								Examples/RGB-D/associations/fr3_nstr_tex_near.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1639
									
								
								Examples/RGB-D/associations/fr3_nstr_tex_near.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2488
									
								
								Examples/RGB-D/associations/fr3_office.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2488
									
								
								Examples/RGB-D/associations/fr3_office.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2584
									
								
								Examples/RGB-D/associations/fr3_office_val.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2584
									
								
								Examples/RGB-D/associations/fr3_office_val.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										907
									
								
								Examples/RGB-D/associations/fr3_str_tex_far.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										907
									
								
								Examples/RGB-D/associations/fr3_str_tex_far.txt
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										1057
									
								
								Examples/RGB-D/associations/fr3_str_tex_near.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1057
									
								
								Examples/RGB-D/associations/fr3_str_tex_near.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										206
									
								
								Examples/RGB-D/rgbd_tum.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										206
									
								
								Examples/RGB-D/rgbd_tum.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,206 @@ | ||||
| /**
 | ||||
|  * This file is part of ORB-SLAM2. | ||||
|  * | ||||
|  * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
|  * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
|  * | ||||
|  * 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 <http://www.gnu.org/licenses/>.
 | ||||
|  */ | ||||
| 
 | ||||
| #include <iostream> | ||||
| #include <algorithm> | ||||
| #include <fstream> | ||||
| #include <chrono> | ||||
| #include <unistd.h> | ||||
| #include <opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include <System.h> | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB, | ||||
|                 vector<string> &vstrImageFilenamesD, vector<double> &vTimestamps); | ||||
| 
 | ||||
| void LoadLabel(const string &strLabelFilename, vector<vector<double>> &vLabel); | ||||
| 
 | ||||
| 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<string> vstrImageFilenamesRGB; | ||||
|     vector<string> vstrImageFilenamesD; | ||||
|     vector<double> 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); // argv[1]: rgbd_tum     argv[2]:ORB_voc.txt
 | ||||
| 
 | ||||
|     // Vector for tracking time statistics
 | ||||
|     vector<float> 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 < nImages; ni++) | ||||
|     { | ||||
|         vector<vector<double>> vLabel; | ||||
|         // Read image and depthmap from file
 | ||||
|         imRGB = cv::imread(string(argv[3]) + "/" + vstrImageFilenamesRGB[ni], CV_LOAD_IMAGE_UNCHANGED); // argv[3]:data/dynamic_objects/rgbd_dataset_freiburg3_walking_static
 | ||||
|         imD = cv::imread(string(argv[3]) + "/" + vstrImageFilenamesD[ni], CV_LOAD_IMAGE_UNCHANGED); | ||||
|         LoadLabel(string(argv[3]) + "/labels/" + to_string(vTimestamps[ni]) + ".txt", vLabel); | ||||
| 
 | ||||
|         double tframe = vTimestamps[ni]; | ||||
| 
 | ||||
|         if (imRGB.empty()) | ||||
|         { | ||||
|             cerr << endl | ||||
|                  << "Failed to load image at: " | ||||
|                  << string(argv[3]) << "/" << vstrImageFilenamesRGB[ni] << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         SLAM.TrackRGBD(imRGB, imD, tframe, vLabel); | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         double ttrack = std::chrono::duration_cast<std::chrono::duration<double>>(t2 - t1).count(); | ||||
| 
 | ||||
|         vTimesTrack[ni] = ttrack; | ||||
| 
 | ||||
|         // Wait to load the next frame
 | ||||
|         double T = 0; | ||||
|         if (ni < nImages - 1) | ||||
|             T = vTimestamps[ni + 1] - tframe; | ||||
|         else if (ni > 0) | ||||
|             T = tframe - vTimestamps[ni - 1]; | ||||
| 
 | ||||
|         if (ttrack < T) | ||||
|             usleep((T - ttrack) * 1e6); | ||||
|     } | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Tracking time statistics
 | ||||
|     sort(vTimesTrack.begin(), vTimesTrack.end()); | ||||
|     float totaltime = 0; | ||||
|     for (int ni = 0; ni < nImages; ni++) | ||||
|     { | ||||
|         totaltime += vTimesTrack[ni]; | ||||
|     } | ||||
|     cout << "-------" << endl | ||||
|          << endl; | ||||
|     cout << "median tracking time: " << vTimesTrack[nImages / 2] << endl; | ||||
|     cout << "mean tracking time: " << totaltime / nImages << endl; | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveTrajectoryTUM("CameraTrajectory.txt"); | ||||
|     SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt"); | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void LoadImages(const string &strAssociationFilename, vector<string> &vstrImageFilenamesRGB, | ||||
|                 vector<string> &vstrImageFilenamesD, vector<double> &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); | ||||
|         } | ||||
|     } | ||||
| } | ||||
| 
 | ||||
| void LoadLabel(const string &strLabelFilename, vector<vector<double>> &vLabel) | ||||
| { | ||||
|     ifstream fAssociation; | ||||
|     fAssociation.open(strLabelFilename.c_str()); | ||||
|     while (!fAssociation.eof()) | ||||
|     { | ||||
|         string s; | ||||
|         getline(fAssociation, s); | ||||
|         if (!s.empty()) | ||||
|         { | ||||
|             stringstream ss; | ||||
|             ss << s; | ||||
|             double cls, x, y, w, h; | ||||
|             vector<double> label; | ||||
|             ss >> cls; | ||||
|             label.push_back(cls); | ||||
|             ss >> x; | ||||
|             label.push_back(x); | ||||
|             ss >> y; | ||||
|             label.push_back(y); | ||||
|             ss >> w; | ||||
|             label.push_back(w); | ||||
|             ss >> h; | ||||
|             label.push_back(h); | ||||
|             vLabel.push_back(label); | ||||
|         } | ||||
|     } | ||||
| } | ||||
							
								
								
									
										69
									
								
								Examples/ROS/ORB_SLAM2/Asus.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										69
									
								
								Examples/ROS/ORB_SLAM2/Asus.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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: 40.0 | ||||
| 
 | ||||
| # Deptmap values factor | ||||
| DepthMapFactor: 1.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 | ||||
| 
 | ||||
							
								
								
									
										101
									
								
								Examples/ROS/ORB_SLAM2/CMakeLists.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										101
									
								
								Examples/ROS/ORB_SLAM2/CMakeLists.txt
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,101 @@ | ||||
| cmake_minimum_required(VERSION 2.4.6) | ||||
| include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake) | ||||
| add_definitions(-w) | ||||
| 
 | ||||
| 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 3.0 QUIET) | ||||
| if(NOT OpenCV_FOUND) | ||||
|    find_package(OpenCV 2.4.3 QUIET) | ||||
|    if(NOT OpenCV_FOUND) | ||||
|       message(FATAL_ERROR "OpenCV > 2.4.3 not found.") | ||||
|    endif() | ||||
| endif() | ||||
| 
 | ||||
| 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 | ||||
| ${PROJECT_SOURCE_DIR}/../../../lib/libboost_filesystem.so  | ||||
| ${PROJECT_SOURCE_DIR}/../../../lib/libboost_system.so | ||||
| -lboost_system  | ||||
| ) | ||||
| 
 | ||||
| # Node for monocular camera | ||||
| rosbuild_add_executable(Mono | ||||
| src/ros_mono.cc | ||||
| ) | ||||
| 
 | ||||
| target_link_libraries(Mono | ||||
| ${LIBS} | ||||
| ) | ||||
| 
 | ||||
| # Node for monocular camera (Augmented Reality Demo) | ||||
| rosbuild_add_executable(MonoAR | ||||
| src/AR/ros_mono_ar.cc | ||||
| src/AR/ViewerAR.h | ||||
| src/AR/ViewerAR.cc | ||||
| ) | ||||
| 
 | ||||
| target_link_libraries(MonoAR | ||||
| ${LIBS} | ||||
| ) | ||||
| 
 | ||||
| # Node for stereo camera | ||||
| rosbuild_add_executable(Stereo | ||||
| src/ros_stereo.cc | ||||
| ) | ||||
| 
 | ||||
| target_link_libraries(Stereo | ||||
| ${LIBS} | ||||
| ) | ||||
| 
 | ||||
| # Node for RGB-D camera | ||||
| rosbuild_add_executable(RGBD | ||||
| src/ros_rgbd.cc | ||||
| ) | ||||
| 
 | ||||
| target_link_libraries(RGBD | ||||
| ${LIBS} | ||||
| ) | ||||
| 
 | ||||
							
								
								
									
										19
									
								
								Examples/ROS/ORB_SLAM2/manifest.xml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										19
									
								
								Examples/ROS/ORB_SLAM2/manifest.xml
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,19 @@ | ||||
| <package> | ||||
|   <description brief="ORB_SLAM2"> | ||||
| 
 | ||||
|      ORB_SLAM2 | ||||
| 
 | ||||
|   </description> | ||||
|   <author>Raul Mur-Artal</author> | ||||
|   <license>GPLv3</license> | ||||
|   <depend package="roscpp"/> | ||||
|   <depend package="tf"/> | ||||
|   <depend package="sensor_msgs"/> | ||||
|   <depend package="image_transport"/> | ||||
|   <depend package="cv_bridge"/> | ||||
| 
 | ||||
| 
 | ||||
| </package> | ||||
| 
 | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										642
									
								
								Examples/ROS/ORB_SLAM2/src/AR/ViewerAR.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										642
									
								
								Examples/ROS/ORB_SLAM2/src/AR/ViewerAR.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,642 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| #include "ViewerAR.h" | ||||
| 
 | ||||
| #include <opencv2/highgui/highgui.hpp> | ||||
| #include <unistd.h> | ||||
| #include <mutex> | ||||
| #include <thread> | ||||
| #include <cstdlib> | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| namespace ORB_SLAM2 | ||||
| { | ||||
| 
 | ||||
| const float eps = 1e-4; | ||||
| 
 | ||||
| cv::Mat ExpSO3(const float &x, const float &y, const float &z) | ||||
| { | ||||
|     cv::Mat I = cv::Mat::eye(3,3,CV_32F); | ||||
|     const float d2 = x*x+y*y+z*z; | ||||
|     const float d = sqrt(d2); | ||||
|     cv::Mat W = (cv::Mat_<float>(3,3) << 0, -z, y, | ||||
|                  z, 0, -x, | ||||
|                  -y,  x, 0); | ||||
|     if(d<eps) | ||||
|         return (I + W + 0.5f*W*W); | ||||
|     else | ||||
|         return (I + W*sin(d)/d + W*W*(1.0f-cos(d))/d2); | ||||
| } | ||||
| 
 | ||||
| cv::Mat ExpSO3(const cv::Mat &v) | ||||
| { | ||||
|     return ExpSO3(v.at<float>(0),v.at<float>(1),v.at<float>(2)); | ||||
| } | ||||
| 
 | ||||
| ViewerAR::ViewerAR(){} | ||||
| 
 | ||||
| void ViewerAR::Run() | ||||
| { | ||||
|     int w,h,wui; | ||||
| 
 | ||||
|     cv::Mat im, Tcw; | ||||
|     int status; | ||||
|     vector<cv::KeyPoint> vKeys; | ||||
|     vector<MapPoint*> vMPs; | ||||
| 
 | ||||
|     while(1) | ||||
|     { | ||||
|         GetImagePose(im,Tcw,status,vKeys,vMPs); | ||||
|         if(im.empty()) | ||||
|             cv::waitKey(mT); | ||||
|         else | ||||
|         { | ||||
|             w = im.cols; | ||||
|             h = im.rows; | ||||
|             break; | ||||
|         } | ||||
|     } | ||||
| 
 | ||||
|     wui=200; | ||||
| 
 | ||||
|     pangolin::CreateWindowAndBind("Viewer",w+wui,h); | ||||
| 
 | ||||
|     glEnable(GL_DEPTH_TEST); | ||||
|     glEnable (GL_BLEND); | ||||
| 
 | ||||
|     pangolin::CreatePanel("menu").SetBounds(0.0,1.0,0.0,pangolin::Attach::Pix(wui)); | ||||
|     pangolin::Var<bool> menu_detectplane("menu.Insert Cube",false,false); | ||||
|     pangolin::Var<bool> menu_clear("menu.Clear All",false,false); | ||||
|     pangolin::Var<bool> menu_drawim("menu.Draw Image",true,true); | ||||
|     pangolin::Var<bool> menu_drawcube("menu.Draw Cube",true,true); | ||||
|     pangolin::Var<float> menu_cubesize("menu. Cube Size",0.05,0.01,0.3); | ||||
|     pangolin::Var<bool> menu_drawgrid("menu.Draw Grid",true,true); | ||||
|     pangolin::Var<int> menu_ngrid("menu. Grid Elements",3,1,10); | ||||
|     pangolin::Var<float> menu_sizegrid("menu. Element Size",0.05,0.01,0.3); | ||||
|     pangolin::Var<bool> menu_drawpoints("menu.Draw Points",false,true); | ||||
| 
 | ||||
|     pangolin::Var<bool> menu_LocalizationMode("menu.Localization Mode",false,true); | ||||
|     bool bLocalizationMode = false; | ||||
| 
 | ||||
|     pangolin::View& d_image = pangolin::Display("image") | ||||
|             .SetBounds(0,1.0f,pangolin::Attach::Pix(wui),1.0f,(float)w/h) | ||||
|             .SetLock(pangolin::LockLeft, pangolin::LockTop); | ||||
| 
 | ||||
|     pangolin::GlTexture imageTexture(w,h,GL_RGB,false,0,GL_RGB,GL_UNSIGNED_BYTE); | ||||
| 
 | ||||
|     pangolin::OpenGlMatrixSpec P = pangolin::ProjectionMatrixRDF_TopLeft(w,h,fx,fy,cx,cy,0.001,1000); | ||||
| 
 | ||||
|     vector<Plane*> vpPlane; | ||||
| 
 | ||||
|     while(1) | ||||
|     { | ||||
| 
 | ||||
|         if(menu_LocalizationMode && !bLocalizationMode) | ||||
|         { | ||||
|             mpSystem->ActivateLocalizationMode(); | ||||
|             bLocalizationMode = true; | ||||
|         } | ||||
|         else if(!menu_LocalizationMode && bLocalizationMode) | ||||
|         { | ||||
|             mpSystem->DeactivateLocalizationMode(); | ||||
|             bLocalizationMode = false; | ||||
|         } | ||||
| 
 | ||||
|         glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); | ||||
| 
 | ||||
|         // Activate camera view
 | ||||
|         d_image.Activate(); | ||||
|         glColor3f(1.0,1.0,1.0); | ||||
| 
 | ||||
|         // Get last image and its computed pose from SLAM
 | ||||
|         GetImagePose(im,Tcw,status,vKeys,vMPs); | ||||
| 
 | ||||
|         // Add text to image
 | ||||
|         PrintStatus(status,bLocalizationMode,im); | ||||
| 
 | ||||
|         if(menu_drawpoints) | ||||
|             DrawTrackedPoints(vKeys,vMPs,im); | ||||
| 
 | ||||
|         // Draw image
 | ||||
|         if(menu_drawim) | ||||
|             DrawImageTexture(imageTexture,im); | ||||
| 
 | ||||
|         glClear(GL_DEPTH_BUFFER_BIT); | ||||
| 
 | ||||
|         // Load camera projection
 | ||||
|         glMatrixMode(GL_PROJECTION); | ||||
|         P.Load(); | ||||
| 
 | ||||
|         glMatrixMode(GL_MODELVIEW); | ||||
| 
 | ||||
|         // Load camera pose
 | ||||
|         LoadCameraPose(Tcw); | ||||
| 
 | ||||
|         // Draw virtual things
 | ||||
|         if(status==2) | ||||
|         { | ||||
|             if(menu_clear) | ||||
|             { | ||||
|                 if(!vpPlane.empty()) | ||||
|                 { | ||||
|                     for(size_t i=0; i<vpPlane.size(); i++) | ||||
|                     { | ||||
|                         delete vpPlane[i]; | ||||
|                     } | ||||
|                     vpPlane.clear(); | ||||
|                     cout << "All cubes erased!" << endl; | ||||
|                 } | ||||
|                 menu_clear = false; | ||||
|             } | ||||
|             if(menu_detectplane) | ||||
|             { | ||||
|                 Plane* pPlane = DetectPlane(Tcw,vMPs,50); | ||||
|                 if(pPlane) | ||||
|                 { | ||||
|                     cout << "New virtual cube inserted!" << endl; | ||||
|                     vpPlane.push_back(pPlane); | ||||
|                 } | ||||
|                 else | ||||
|                 { | ||||
|                     cout << "No plane detected. Point the camera to a planar region." << endl; | ||||
|                 } | ||||
|                 menu_detectplane = false; | ||||
|             } | ||||
| 
 | ||||
|             if(!vpPlane.empty()) | ||||
|             { | ||||
|                 // Recompute plane if there has been a loop closure or global BA
 | ||||
|                 // In localization mode, map is not updated so we do not need to recompute
 | ||||
|                 bool bRecompute = false; | ||||
|                 if(!bLocalizationMode) | ||||
|                 { | ||||
|                     if(mpSystem->MapChanged()) | ||||
|                     { | ||||
|                         cout << "Map changed. All virtual elements are recomputed!" << endl; | ||||
|                         bRecompute = true; | ||||
|                     } | ||||
|                 } | ||||
| 
 | ||||
|                 for(size_t i=0; i<vpPlane.size(); i++) | ||||
|                 { | ||||
|                     Plane* pPlane = vpPlane[i]; | ||||
| 
 | ||||
|                     if(pPlane) | ||||
|                     { | ||||
|                         if(bRecompute) | ||||
|                         { | ||||
|                             pPlane->Recompute(); | ||||
|                         } | ||||
|                         glPushMatrix(); | ||||
|                         pPlane->glTpw.Multiply(); | ||||
| 
 | ||||
|                         // Draw cube
 | ||||
|                         if(menu_drawcube) | ||||
|                         { | ||||
|                             DrawCube(menu_cubesize); | ||||
|                         } | ||||
| 
 | ||||
|                         // Draw grid plane
 | ||||
|                         if(menu_drawgrid) | ||||
|                         { | ||||
|                             DrawPlane(menu_ngrid,menu_sizegrid); | ||||
|                         } | ||||
| 
 | ||||
|                         glPopMatrix(); | ||||
|                     } | ||||
|                 } | ||||
|             } | ||||
| 
 | ||||
| 
 | ||||
|         } | ||||
| 
 | ||||
|         pangolin::FinishFrame(); | ||||
|         usleep(mT*1000); | ||||
|     } | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::SetImagePose(const cv::Mat &im, const cv::Mat &Tcw, const int &status, const vector<cv::KeyPoint> &vKeys, const vector<ORB_SLAM2::MapPoint*> &vMPs) | ||||
| { | ||||
|     unique_lock<mutex> lock(mMutexPoseImage); | ||||
|     mImage = im.clone(); | ||||
|     mTcw = Tcw.clone(); | ||||
|     mStatus = status; | ||||
|     mvKeys = vKeys; | ||||
|     mvMPs = vMPs; | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::GetImagePose(cv::Mat &im, cv::Mat &Tcw, int &status, std::vector<cv::KeyPoint> &vKeys,  std::vector<MapPoint*> &vMPs) | ||||
| { | ||||
|     unique_lock<mutex> lock(mMutexPoseImage); | ||||
|     im = mImage.clone(); | ||||
|     Tcw = mTcw.clone(); | ||||
|     status = mStatus; | ||||
|     vKeys = mvKeys; | ||||
|     vMPs = mvMPs; | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::LoadCameraPose(const cv::Mat &Tcw) | ||||
| { | ||||
|     if(!Tcw.empty()) | ||||
|     { | ||||
|         pangolin::OpenGlMatrix M; | ||||
| 
 | ||||
|         M.m[0] = Tcw.at<float>(0,0); | ||||
|         M.m[1] = Tcw.at<float>(1,0); | ||||
|         M.m[2] = Tcw.at<float>(2,0); | ||||
|         M.m[3]  = 0.0; | ||||
| 
 | ||||
|         M.m[4] = Tcw.at<float>(0,1); | ||||
|         M.m[5] = Tcw.at<float>(1,1); | ||||
|         M.m[6] = Tcw.at<float>(2,1); | ||||
|         M.m[7]  = 0.0; | ||||
| 
 | ||||
|         M.m[8] = Tcw.at<float>(0,2); | ||||
|         M.m[9] = Tcw.at<float>(1,2); | ||||
|         M.m[10] = Tcw.at<float>(2,2); | ||||
|         M.m[11]  = 0.0; | ||||
| 
 | ||||
|         M.m[12] = Tcw.at<float>(0,3); | ||||
|         M.m[13] = Tcw.at<float>(1,3); | ||||
|         M.m[14] = Tcw.at<float>(2,3); | ||||
|         M.m[15]  = 1.0; | ||||
| 
 | ||||
|         M.Load(); | ||||
|     } | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::PrintStatus(const int &status, const bool &bLocMode, cv::Mat &im) | ||||
| { | ||||
|     if(!bLocMode) | ||||
|     { | ||||
|         switch(status) | ||||
|         { | ||||
|         case 1:  {AddTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;} | ||||
|         case 2:  {AddTextToImage("SLAM ON",im,0,255,0); break;} | ||||
|         case 3:  {AddTextToImage("SLAM LOST",im,255,0,0); break;} | ||||
|         } | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|         switch(status) | ||||
|         { | ||||
|         case 1:  {AddTextToImage("SLAM NOT INITIALIZED",im,255,0,0); break;} | ||||
|         case 2:  {AddTextToImage("LOCALIZATION ON",im,0,255,0); break;} | ||||
|         case 3:  {AddTextToImage("LOCALIZATION LOST",im,255,0,0); break;} | ||||
|         } | ||||
|     } | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::AddTextToImage(const string &s, cv::Mat &im, const int r, const int g, const int b) | ||||
| { | ||||
|     int l = 10; | ||||
|     //imText.rowRange(im.rows-imText.rows,imText.rows) = cv::Mat::zeros(textSize.height+10,im.cols,im.type());
 | ||||
|     cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l-1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l+1,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l-1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l+1,im.rows-(l-1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l-1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
|     cv::putText(im,s,cv::Point(l+1,im.rows-(l+1)),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(255,255,255),2,8); | ||||
| 
 | ||||
|     cv::putText(im,s,cv::Point(l,im.rows-l),cv::FONT_HERSHEY_PLAIN,1.5,cv::Scalar(r,g,b),2,8); | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::DrawImageTexture(pangolin::GlTexture &imageTexture, cv::Mat &im) | ||||
| { | ||||
|     if(!im.empty()) | ||||
|     { | ||||
|         imageTexture.Upload(im.data,GL_RGB,GL_UNSIGNED_BYTE); | ||||
|         imageTexture.RenderToViewportFlipY(); | ||||
|     } | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::DrawCube(const float &size,const float x, const float y, const float z) | ||||
| { | ||||
|     pangolin::OpenGlMatrix M = pangolin::OpenGlMatrix::Translate(-x,-size-y,-z); | ||||
|     glPushMatrix(); | ||||
|     M.Multiply(); | ||||
|     pangolin::glDrawColouredCube(-size,size); | ||||
|     glPopMatrix(); | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::DrawPlane(Plane *pPlane, int ndivs, float ndivsize) | ||||
| { | ||||
|     glPushMatrix(); | ||||
|     pPlane->glTpw.Multiply(); | ||||
|     DrawPlane(ndivs,ndivsize); | ||||
|     glPopMatrix(); | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::DrawPlane(int ndivs, float ndivsize) | ||||
| { | ||||
|     // Plane parallel to x-z at origin with normal -y
 | ||||
|     const float minx = -ndivs*ndivsize; | ||||
|     const float minz = -ndivs*ndivsize; | ||||
|     const float maxx = ndivs*ndivsize; | ||||
|     const float maxz = ndivs*ndivsize; | ||||
| 
 | ||||
| 
 | ||||
|     glLineWidth(2); | ||||
|     glColor3f(0.7f,0.7f,1.0f); | ||||
|     glBegin(GL_LINES); | ||||
| 
 | ||||
|     for(int n = 0; n<=2*ndivs; n++) | ||||
|     { | ||||
|         glVertex3f(minx+ndivsize*n,0,minz); | ||||
|         glVertex3f(minx+ndivsize*n,0,maxz); | ||||
|         glVertex3f(minx,0,minz+ndivsize*n); | ||||
|         glVertex3f(maxx,0,minz+ndivsize*n); | ||||
|     } | ||||
| 
 | ||||
|     glEnd(); | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| void ViewerAR::DrawTrackedPoints(const std::vector<cv::KeyPoint> &vKeys, const std::vector<MapPoint *> &vMPs, cv::Mat &im) | ||||
| { | ||||
|     const int N = vKeys.size(); | ||||
| 
 | ||||
| 
 | ||||
|     for(int i=0; i<N; i++) | ||||
|     { | ||||
|         if(vMPs[i]) | ||||
|         { | ||||
|             cv::circle(im,vKeys[i].pt,1,cv::Scalar(0,255,0),-1); | ||||
|         } | ||||
|     } | ||||
| } | ||||
| 
 | ||||
| Plane* ViewerAR::DetectPlane(const cv::Mat Tcw, const std::vector<MapPoint*> &vMPs, const int iterations) | ||||
| { | ||||
|     // Retrieve 3D points
 | ||||
|     vector<cv::Mat> vPoints; | ||||
|     vPoints.reserve(vMPs.size()); | ||||
|     vector<MapPoint*> vPointMP; | ||||
|     vPointMP.reserve(vMPs.size()); | ||||
| 
 | ||||
|     for(size_t i=0; i<vMPs.size(); i++) | ||||
|     { | ||||
|         MapPoint* pMP=vMPs[i]; | ||||
|         if(pMP) | ||||
|         { | ||||
|             if(pMP->Observations()>5) | ||||
|             { | ||||
|                 vPoints.push_back(pMP->GetWorldPos()); | ||||
|                 vPointMP.push_back(pMP); | ||||
|             } | ||||
|         } | ||||
|     } | ||||
| 
 | ||||
|     const int N = vPoints.size(); | ||||
| 
 | ||||
|     if(N<50) | ||||
|         return NULL; | ||||
| 
 | ||||
| 
 | ||||
|     // Indices for minimum set selection
 | ||||
|     vector<size_t> vAllIndices; | ||||
|     vAllIndices.reserve(N); | ||||
|     vector<size_t> vAvailableIndices; | ||||
| 
 | ||||
|     for(int i=0; i<N; i++) | ||||
|     { | ||||
|         vAllIndices.push_back(i); | ||||
|     } | ||||
| 
 | ||||
|     float bestDist = 1e10; | ||||
|     vector<float> bestvDist; | ||||
| 
 | ||||
|     //RANSAC
 | ||||
|     for(int n=0; n<iterations; n++) | ||||
|     { | ||||
|         vAvailableIndices = vAllIndices; | ||||
| 
 | ||||
|         cv::Mat A(3,4,CV_32F); | ||||
|         A.col(3) = cv::Mat::ones(3,1,CV_32F); | ||||
| 
 | ||||
|         // Get min set of points
 | ||||
|         for(short i = 0; i < 3; ++i) | ||||
|         { | ||||
|             int randi = DUtils::Random::RandomInt(0, vAvailableIndices.size()-1); | ||||
| 
 | ||||
|             int idx = vAvailableIndices[randi]; | ||||
| 
 | ||||
|             A.row(i).colRange(0,3) = vPoints[idx].t(); | ||||
| 
 | ||||
|             vAvailableIndices[randi] = vAvailableIndices.back(); | ||||
|             vAvailableIndices.pop_back(); | ||||
|         } | ||||
| 
 | ||||
|         cv::Mat u,w,vt; | ||||
|         cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); | ||||
| 
 | ||||
|         const float a = vt.at<float>(3,0); | ||||
|         const float b = vt.at<float>(3,1); | ||||
|         const float c = vt.at<float>(3,2); | ||||
|         const float d = vt.at<float>(3,3); | ||||
| 
 | ||||
|         vector<float> vDistances(N,0); | ||||
| 
 | ||||
|         const float f = 1.0f/sqrt(a*a+b*b+c*c+d*d); | ||||
| 
 | ||||
|         for(int i=0; i<N; i++) | ||||
|         { | ||||
|             vDistances[i] = fabs(vPoints[i].at<float>(0)*a+vPoints[i].at<float>(1)*b+vPoints[i].at<float>(2)*c+d)*f; | ||||
|         } | ||||
| 
 | ||||
|         vector<float> vSorted = vDistances; | ||||
|         sort(vSorted.begin(),vSorted.end()); | ||||
| 
 | ||||
|         int nth = max((int)(0.2*N),20); | ||||
|         const float medianDist = vSorted[nth]; | ||||
| 
 | ||||
|         if(medianDist<bestDist) | ||||
|         { | ||||
|             bestDist = medianDist; | ||||
|             bestvDist = vDistances; | ||||
|         } | ||||
|     } | ||||
| 
 | ||||
|     // Compute threshold inlier/outlier
 | ||||
|     const float th = 1.4*bestDist; | ||||
|     vector<bool> vbInliers(N,false); | ||||
|     int nInliers = 0; | ||||
|     for(int i=0; i<N; i++) | ||||
|     { | ||||
|         if(bestvDist[i]<th) | ||||
|         { | ||||
|             nInliers++; | ||||
|             vbInliers[i]=true; | ||||
|         } | ||||
|     } | ||||
| 
 | ||||
|     vector<MapPoint*> vInlierMPs(nInliers,NULL); | ||||
|     int nin = 0; | ||||
|     for(int i=0; i<N; i++) | ||||
|     { | ||||
|         if(vbInliers[i]) | ||||
|         { | ||||
|             vInlierMPs[nin] = vPointMP[i]; | ||||
|             nin++; | ||||
|         } | ||||
|     } | ||||
| 
 | ||||
|     return new Plane(vInlierMPs,Tcw); | ||||
| } | ||||
| 
 | ||||
| Plane::Plane(const std::vector<MapPoint *> &vMPs, const cv::Mat &Tcw):mvMPs(vMPs),mTcw(Tcw.clone()) | ||||
| { | ||||
|     rang = -3.14f/2+((float)rand()/RAND_MAX)*3.14f; | ||||
|     Recompute(); | ||||
| } | ||||
| 
 | ||||
| void Plane::Recompute() | ||||
| { | ||||
|     const int N = mvMPs.size(); | ||||
| 
 | ||||
|     // Recompute plane with all points
 | ||||
|     cv::Mat A = cv::Mat(N,4,CV_32F); | ||||
|     A.col(3) = cv::Mat::ones(N,1,CV_32F); | ||||
| 
 | ||||
|     o = cv::Mat::zeros(3,1,CV_32F); | ||||
| 
 | ||||
|     int nPoints = 0; | ||||
|     for(int i=0; i<N; i++) | ||||
|     { | ||||
|         MapPoint* pMP = mvMPs[i]; | ||||
|         if(!pMP->isBad()) | ||||
|         { | ||||
|             cv::Mat Xw = pMP->GetWorldPos(); | ||||
|             o+=Xw; | ||||
|             A.row(nPoints).colRange(0,3) = Xw.t(); | ||||
|             nPoints++; | ||||
|         } | ||||
|     } | ||||
|     A.resize(nPoints); | ||||
| 
 | ||||
|     cv::Mat u,w,vt; | ||||
|     cv::SVDecomp(A,w,u,vt,cv::SVD::MODIFY_A | cv::SVD::FULL_UV); | ||||
| 
 | ||||
|     float a = vt.at<float>(3,0); | ||||
|     float b = vt.at<float>(3,1); | ||||
|     float c = vt.at<float>(3,2); | ||||
| 
 | ||||
|     o = o*(1.0f/nPoints); | ||||
|     const float f = 1.0f/sqrt(a*a+b*b+c*c); | ||||
| 
 | ||||
|     // Compute XC just the first time
 | ||||
|     if(XC.empty()) | ||||
|     { | ||||
|         cv::Mat Oc = -mTcw.colRange(0,3).rowRange(0,3).t()*mTcw.rowRange(0,3).col(3); | ||||
|         XC = Oc-o; | ||||
|     } | ||||
| 
 | ||||
|     if((XC.at<float>(0)*a+XC.at<float>(1)*b+XC.at<float>(2)*c)>0) | ||||
|     { | ||||
|         a=-a; | ||||
|         b=-b; | ||||
|         c=-c; | ||||
|     } | ||||
| 
 | ||||
|     const float nx = a*f; | ||||
|     const float ny = b*f; | ||||
|     const float nz = c*f; | ||||
| 
 | ||||
|     n = (cv::Mat_<float>(3,1)<<nx,ny,nz); | ||||
| 
 | ||||
|     cv::Mat up = (cv::Mat_<float>(3,1) << 0.0f, 1.0f, 0.0f); | ||||
| 
 | ||||
|     cv::Mat v = up.cross(n); | ||||
|     const float sa = cv::norm(v); | ||||
|     const float ca = up.dot(n); | ||||
|     const float ang = atan2(sa,ca); | ||||
|     Tpw = cv::Mat::eye(4,4,CV_32F); | ||||
| 
 | ||||
| 
 | ||||
|     Tpw.rowRange(0,3).colRange(0,3) = ExpSO3(v*ang/sa)*ExpSO3(up*rang); | ||||
|     o.copyTo(Tpw.col(3).rowRange(0,3)); | ||||
| 
 | ||||
|     glTpw.m[0] = Tpw.at<float>(0,0); | ||||
|     glTpw.m[1] = Tpw.at<float>(1,0); | ||||
|     glTpw.m[2] = Tpw.at<float>(2,0); | ||||
|     glTpw.m[3]  = 0.0; | ||||
| 
 | ||||
|     glTpw.m[4] = Tpw.at<float>(0,1); | ||||
|     glTpw.m[5] = Tpw.at<float>(1,1); | ||||
|     glTpw.m[6] = Tpw.at<float>(2,1); | ||||
|     glTpw.m[7]  = 0.0; | ||||
| 
 | ||||
|     glTpw.m[8] = Tpw.at<float>(0,2); | ||||
|     glTpw.m[9] = Tpw.at<float>(1,2); | ||||
|     glTpw.m[10] = Tpw.at<float>(2,2); | ||||
|     glTpw.m[11]  = 0.0; | ||||
| 
 | ||||
|     glTpw.m[12] = Tpw.at<float>(0,3); | ||||
|     glTpw.m[13] = Tpw.at<float>(1,3); | ||||
|     glTpw.m[14] = Tpw.at<float>(2,3); | ||||
|     glTpw.m[15]  = 1.0; | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| Plane::Plane(const float &nx, const float &ny, const float &nz, const float &ox, const float &oy, const float &oz) | ||||
| { | ||||
|     n = (cv::Mat_<float>(3,1)<<nx,ny,nz); | ||||
|     o = (cv::Mat_<float>(3,1)<<ox,oy,oz); | ||||
| 
 | ||||
|     cv::Mat up = (cv::Mat_<float>(3,1) << 0.0f, 1.0f, 0.0f); | ||||
| 
 | ||||
|     cv::Mat v = up.cross(n); | ||||
|     const float s = cv::norm(v); | ||||
|     const float c = up.dot(n); | ||||
|     const float a = atan2(s,c); | ||||
|     Tpw = cv::Mat::eye(4,4,CV_32F); | ||||
|     const float rang = -3.14f/2+((float)rand()/RAND_MAX)*3.14f; | ||||
|     cout << rang; | ||||
|     Tpw.rowRange(0,3).colRange(0,3) = ExpSO3(v*a/s)*ExpSO3(up*rang); | ||||
|     o.copyTo(Tpw.col(3).rowRange(0,3)); | ||||
| 
 | ||||
|     glTpw.m[0] = Tpw.at<float>(0,0); | ||||
|     glTpw.m[1] = Tpw.at<float>(1,0); | ||||
|     glTpw.m[2] = Tpw.at<float>(2,0); | ||||
|     glTpw.m[3]  = 0.0; | ||||
| 
 | ||||
|     glTpw.m[4] = Tpw.at<float>(0,1); | ||||
|     glTpw.m[5] = Tpw.at<float>(1,1); | ||||
|     glTpw.m[6] = Tpw.at<float>(2,1); | ||||
|     glTpw.m[7]  = 0.0; | ||||
| 
 | ||||
|     glTpw.m[8] = Tpw.at<float>(0,2); | ||||
|     glTpw.m[9] = Tpw.at<float>(1,2); | ||||
|     glTpw.m[10] = Tpw.at<float>(2,2); | ||||
|     glTpw.m[11]  = 0.0; | ||||
| 
 | ||||
|     glTpw.m[12] = Tpw.at<float>(0,3); | ||||
|     glTpw.m[13] = Tpw.at<float>(1,3); | ||||
|     glTpw.m[14] = Tpw.at<float>(2,3); | ||||
|     glTpw.m[15]  = 1.0; | ||||
| } | ||||
| 
 | ||||
| } | ||||
							
								
								
									
										120
									
								
								Examples/ROS/ORB_SLAM2/src/AR/ViewerAR.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										120
									
								
								Examples/ROS/ORB_SLAM2/src/AR/ViewerAR.h
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,120 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #ifndef VIEWERAR_H | ||||
| #define VIEWERAR_H | ||||
| 
 | ||||
| #include <mutex> | ||||
| #include <opencv2/core/core.hpp> | ||||
| #include <pangolin/pangolin.h> | ||||
| #include <string> | ||||
| #include"../../../include/System.h" | ||||
| 
 | ||||
| namespace ORB_SLAM2 | ||||
| { | ||||
| 
 | ||||
| class Plane | ||||
| { | ||||
| public: | ||||
|     Plane(const std::vector<MapPoint*> &vMPs, const cv::Mat &Tcw); | ||||
|     Plane(const float &nx, const float &ny, const float &nz, const float &ox, const float &oy, const float &oz); | ||||
| 
 | ||||
|     void Recompute(); | ||||
| 
 | ||||
|     //normal
 | ||||
|     cv::Mat n; | ||||
|     //origin
 | ||||
|     cv::Mat o; | ||||
|     //arbitrary orientation along normal
 | ||||
|     float rang; | ||||
|     //transformation from world to the plane
 | ||||
|     cv::Mat Tpw; | ||||
|     pangolin::OpenGlMatrix glTpw; | ||||
|     //MapPoints that define the plane
 | ||||
|     std::vector<MapPoint*> mvMPs; | ||||
|     //camera pose when the plane was first observed (to compute normal direction)
 | ||||
|     cv::Mat mTcw, XC; | ||||
| }; | ||||
| 
 | ||||
| class ViewerAR | ||||
| { | ||||
| public: | ||||
|     ViewerAR(); | ||||
| 
 | ||||
|     void SetFPS(const float fps){ | ||||
|         mFPS = fps; | ||||
|         mT=1e3/fps; | ||||
|     } | ||||
| 
 | ||||
|     void SetSLAM(ORB_SLAM2::System* pSystem){ | ||||
|         mpSystem = pSystem; | ||||
|     } | ||||
| 
 | ||||
|     // Main thread function. 
 | ||||
|     void Run(); | ||||
| 
 | ||||
|     void SetCameraCalibration(const float &fx_, const float &fy_, const float &cx_, const float &cy_){ | ||||
|         fx = fx_; fy = fy_; cx = cx_; cy = cy_; | ||||
|     } | ||||
| 
 | ||||
|     void SetImagePose(const cv::Mat &im, const cv::Mat &Tcw, const int &status, | ||||
|                       const std::vector<cv::KeyPoint> &vKeys, const std::vector<MapPoint*> &vMPs); | ||||
| 
 | ||||
|     void GetImagePose(cv::Mat &im, cv::Mat &Tcw, int &status, | ||||
|                       std::vector<cv::KeyPoint> &vKeys,  std::vector<MapPoint*> &vMPs); | ||||
| 
 | ||||
| private: | ||||
| 
 | ||||
|     //SLAM
 | ||||
|     ORB_SLAM2::System* mpSystem; | ||||
| 
 | ||||
|     void PrintStatus(const int &status, const bool &bLocMode, cv::Mat &im); | ||||
|     void AddTextToImage(const std::string &s, cv::Mat &im, const int r=0, const int g=0, const int b=0); | ||||
|     void LoadCameraPose(const cv::Mat &Tcw); | ||||
|     void DrawImageTexture(pangolin::GlTexture &imageTexture, cv::Mat &im); | ||||
|     void DrawCube(const float &size, const float x=0, const float y=0, const float z=0); | ||||
|     void DrawPlane(int ndivs, float ndivsize); | ||||
|     void DrawPlane(Plane* pPlane, int ndivs, float ndivsize); | ||||
|     void DrawTrackedPoints(const std::vector<cv::KeyPoint> &vKeys, const std::vector<MapPoint*> &vMPs, cv::Mat &im); | ||||
| 
 | ||||
|     Plane* DetectPlane(const cv::Mat Tcw, const std::vector<MapPoint*> &vMPs, const int iterations=50); | ||||
| 
 | ||||
|     // frame rate
 | ||||
|     float mFPS, mT; | ||||
|     float fx,fy,cx,cy; | ||||
| 
 | ||||
|     // Last processed image and computed pose by the SLAM
 | ||||
|     std::mutex mMutexPoseImage; | ||||
|     cv::Mat mTcw; | ||||
|     cv::Mat mImage; | ||||
|     int mStatus; | ||||
|     std::vector<cv::KeyPoint> mvKeys; | ||||
|     std::vector<MapPoint*> mvMPs; | ||||
| 
 | ||||
| }; | ||||
| 
 | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| #endif // VIEWERAR_H
 | ||||
| 	 | ||||
| 
 | ||||
							
								
								
									
										169
									
								
								Examples/ROS/ORB_SLAM2/src/AR/ros_mono_ar.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										169
									
								
								Examples/ROS/ORB_SLAM2/src/AR/ros_mono_ar.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,169 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| 
 | ||||
| #include<ros/ros.h> | ||||
| #include <cv_bridge/cv_bridge.h> | ||||
| 
 | ||||
| #include<opencv2/core/core.hpp> | ||||
| #include<opencv2/imgproc/imgproc.hpp> | ||||
| 
 | ||||
| #include"../../../include/System.h" | ||||
| 
 | ||||
| #include"ViewerAR.h" | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| 
 | ||||
| ORB_SLAM2::ViewerAR viewerAR; | ||||
| bool bRGB = true; | ||||
| 
 | ||||
| cv::Mat K; | ||||
| cv::Mat DistCoef; | ||||
| 
 | ||||
| 
 | ||||
| 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,false); | ||||
| 
 | ||||
| 
 | ||||
|     cout << endl << endl; | ||||
|     cout << "-----------------------" << endl; | ||||
|     cout << "Augmented Reality Demo" << endl; | ||||
|     cout << "1) Translate the camera to initialize SLAM." << endl; | ||||
|     cout << "2) Look at a planar region and translate the camera." << endl; | ||||
|     cout << "3) Press Insert Cube to place a virtual cube in the plane. " << endl; | ||||
|     cout << endl; | ||||
|     cout << "You can place several cubes in different planes." << endl; | ||||
|     cout << "-----------------------" << endl; | ||||
|     cout << endl; | ||||
| 
 | ||||
| 
 | ||||
|     viewerAR.SetSLAM(&SLAM); | ||||
| 
 | ||||
|     ImageGrabber igb(&SLAM); | ||||
| 
 | ||||
|     ros::NodeHandle nodeHandler; | ||||
|     ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb); | ||||
| 
 | ||||
| 
 | ||||
|     cv::FileStorage fSettings(argv[2], cv::FileStorage::READ); | ||||
|     bRGB = static_cast<bool>((int)fSettings["Camera.RGB"]); | ||||
|     float fps = fSettings["Camera.fps"]; | ||||
|     viewerAR.SetFPS(fps); | ||||
| 
 | ||||
|     float fx = fSettings["Camera.fx"]; | ||||
|     float fy = fSettings["Camera.fy"]; | ||||
|     float cx = fSettings["Camera.cx"]; | ||||
|     float cy = fSettings["Camera.cy"]; | ||||
| 
 | ||||
|     viewerAR.SetCameraCalibration(fx,fy,cx,cy); | ||||
| 
 | ||||
|     K = cv::Mat::eye(3,3,CV_32F); | ||||
|     K.at<float>(0,0) = fx; | ||||
|     K.at<float>(1,1) = fy; | ||||
|     K.at<float>(0,2) = cx; | ||||
|     K.at<float>(1,2) = cy; | ||||
| 
 | ||||
|     DistCoef = cv::Mat::zeros(4,1,CV_32F); | ||||
|     DistCoef.at<float>(0) = fSettings["Camera.k1"]; | ||||
|     DistCoef.at<float>(1) = fSettings["Camera.k2"]; | ||||
|     DistCoef.at<float>(2) = fSettings["Camera.p1"]; | ||||
|     DistCoef.at<float>(3) = fSettings["Camera.p2"]; | ||||
|     const float k3 = fSettings["Camera.k3"]; | ||||
|     if(k3!=0) | ||||
|     { | ||||
|         DistCoef.resize(5); | ||||
|         DistCoef.at<float>(4) = k3; | ||||
|     } | ||||
| 
 | ||||
|     thread tViewer = thread(&ORB_SLAM2::ViewerAR::Run,&viewerAR); | ||||
| 
 | ||||
|     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; | ||||
|     } | ||||
|     cv::Mat im = cv_ptr->image.clone(); | ||||
|     cv::Mat imu; | ||||
|     cv::Mat Tcw = mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec()); | ||||
|     int state = mpSLAM->GetTrackingState(); | ||||
|     vector<ORB_SLAM2::MapPoint*> vMPs = mpSLAM->GetTrackedMapPoints(); | ||||
|     vector<cv::KeyPoint> vKeys = mpSLAM->GetTrackedKeyPointsUn(); | ||||
| 
 | ||||
|     cv::undistort(im,imu,K,DistCoef); | ||||
| 
 | ||||
|     if(bRGB) | ||||
|         viewerAR.SetImagePose(imu,Tcw,state,vKeys,vMPs); | ||||
|     else | ||||
|     { | ||||
|         cv::cvtColor(imu,imu,CV_RGB2BGR); | ||||
|         viewerAR.SetImagePose(imu,Tcw,state,vKeys,vMPs); | ||||
|     }     | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										96
									
								
								Examples/ROS/ORB_SLAM2/src/ros_mono.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										96
									
								
								Examples/ROS/ORB_SLAM2/src/ros_mono.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,96 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| 
 | ||||
| #include<ros/ros.h> | ||||
| #include <cv_bridge/cv_bridge.h> | ||||
| 
 | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #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()); | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										115
									
								
								Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										115
									
								
								Examples/ROS/ORB_SLAM2/src/ros_rgbd.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,115 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| 
 | ||||
| #include<ros/ros.h> | ||||
| #include <cv_bridge/cv_bridge.h> | ||||
| #include <message_filters/subscriber.h> | ||||
| #include <message_filters/time_synchronizer.h> | ||||
| #include <message_filters/sync_policies/approximate_time.h> | ||||
| 
 | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #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<sensor_msgs::Image> rgb_sub(nh, "/camera/rgb/image_raw", 1); | ||||
|     message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "camera/depth_registered/image_raw", 1); | ||||
|     typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol; | ||||
|     message_filters::Synchronizer<sync_pol> 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; | ||||
|     } | ||||
| 
 | ||||
|     mpSLAM->TrackRGBD(cv_ptrRGB->image,cv_ptrD->image,cv_ptrRGB->header.stamp.toSec()); | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										172
									
								
								Examples/ROS/ORB_SLAM2/src/ros_stereo.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										172
									
								
								Examples/ROS/ORB_SLAM2/src/ros_stereo.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,172 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<chrono> | ||||
| 
 | ||||
| #include<ros/ros.h> | ||||
| #include <cv_bridge/cv_bridge.h> | ||||
| #include <message_filters/subscriber.h> | ||||
| #include <message_filters/time_synchronizer.h> | ||||
| #include <message_filters/sync_policies/approximate_time.h> | ||||
| 
 | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include"../../../include/System.h" | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| class ImageGrabber | ||||
| { | ||||
| public: | ||||
|     ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){} | ||||
| 
 | ||||
|     void GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight); | ||||
| 
 | ||||
|     ORB_SLAM2::System* mpSLAM; | ||||
|     bool do_rectify; | ||||
|     cv::Mat M1l,M2l,M1r,M2r; | ||||
| }; | ||||
| 
 | ||||
| int main(int argc, char **argv) | ||||
| { | ||||
|     ros::init(argc, argv, "RGBD"); | ||||
|     ros::start(); | ||||
| 
 | ||||
|     if(argc != 4) | ||||
|     { | ||||
|         cerr << endl << "Usage: rosrun ORB_SLAM2 Stereo path_to_vocabulary path_to_settings do_rectify" << 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::STEREO,true); | ||||
| 
 | ||||
|     ImageGrabber igb(&SLAM); | ||||
| 
 | ||||
|     stringstream ss(argv[3]); | ||||
| 	ss >> boolalpha >> igb.do_rectify; | ||||
| 
 | ||||
|     if(igb.do_rectify) | ||||
|     {       | ||||
|         // Load settings related to stereo calibration
 | ||||
|         cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ); | ||||
|         if(!fsSettings.isOpened()) | ||||
|         { | ||||
|             cerr << "ERROR: Wrong path to settings" << endl; | ||||
|             return -1; | ||||
|         } | ||||
| 
 | ||||
|         cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; | ||||
|         fsSettings["LEFT.K"] >> K_l; | ||||
|         fsSettings["RIGHT.K"] >> K_r; | ||||
| 
 | ||||
|         fsSettings["LEFT.P"] >> P_l; | ||||
|         fsSettings["RIGHT.P"] >> P_r; | ||||
| 
 | ||||
|         fsSettings["LEFT.R"] >> R_l; | ||||
|         fsSettings["RIGHT.R"] >> R_r; | ||||
| 
 | ||||
|         fsSettings["LEFT.D"] >> D_l; | ||||
|         fsSettings["RIGHT.D"] >> D_r; | ||||
| 
 | ||||
|         int rows_l = fsSettings["LEFT.height"]; | ||||
|         int cols_l = fsSettings["LEFT.width"]; | ||||
|         int rows_r = fsSettings["RIGHT.height"]; | ||||
|         int cols_r = fsSettings["RIGHT.width"]; | ||||
| 
 | ||||
|         if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() || | ||||
|                 rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0) | ||||
|         { | ||||
|             cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl; | ||||
|             return -1; | ||||
|         } | ||||
| 
 | ||||
|         cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,igb.M1l,igb.M2l); | ||||
|         cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,igb.M1r,igb.M2r); | ||||
|     } | ||||
| 
 | ||||
|     ros::NodeHandle nh; | ||||
| 
 | ||||
|     message_filters::Subscriber<sensor_msgs::Image> left_sub(nh, "/camera/left/image_raw", 1); | ||||
|     message_filters::Subscriber<sensor_msgs::Image> right_sub(nh, "camera/right/image_raw", 1); | ||||
|     typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol; | ||||
|     message_filters::Synchronizer<sync_pol> sync(sync_pol(10), left_sub,right_sub); | ||||
|     sync.registerCallback(boost::bind(&ImageGrabber::GrabStereo,&igb,_1,_2)); | ||||
| 
 | ||||
|     ros::spin(); | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory_TUM_Format.txt"); | ||||
|     SLAM.SaveTrajectoryTUM("FrameTrajectory_TUM_Format.txt"); | ||||
|     SLAM.SaveTrajectoryKITTI("FrameTrajectory_KITTI_Format.txt"); | ||||
| 
 | ||||
|     ros::shutdown(); | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void ImageGrabber::GrabStereo(const sensor_msgs::ImageConstPtr& msgLeft,const sensor_msgs::ImageConstPtr& msgRight) | ||||
| { | ||||
|     // Copy the ros image message to cv::Mat.
 | ||||
|     cv_bridge::CvImageConstPtr cv_ptrLeft; | ||||
|     try | ||||
|     { | ||||
|         cv_ptrLeft = cv_bridge::toCvShare(msgLeft); | ||||
|     } | ||||
|     catch (cv_bridge::Exception& e) | ||||
|     { | ||||
|         ROS_ERROR("cv_bridge exception: %s", e.what()); | ||||
|         return; | ||||
|     } | ||||
| 
 | ||||
|     cv_bridge::CvImageConstPtr cv_ptrRight; | ||||
|     try | ||||
|     { | ||||
|         cv_ptrRight = cv_bridge::toCvShare(msgRight); | ||||
|     } | ||||
|     catch (cv_bridge::Exception& e) | ||||
|     { | ||||
|         ROS_ERROR("cv_bridge exception: %s", e.what()); | ||||
|         return; | ||||
|     } | ||||
| 
 | ||||
|     if(do_rectify) | ||||
|     { | ||||
|         cv::Mat imLeft, imRight; | ||||
|         cv::remap(cv_ptrLeft->image,imLeft,M1l,M2l,cv::INTER_LINEAR); | ||||
|         cv::remap(cv_ptrRight->image,imRight,M1r,M2r,cv::INTER_LINEAR); | ||||
|         mpSLAM->TrackStereo(imLeft,imRight,cv_ptrLeft->header.stamp.toSec()); | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|         mpSLAM->TrackStereo(cv_ptrLeft->image,cv_ptrRight->image,cv_ptrLeft->header.stamp.toSec()); | ||||
|     } | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										116
									
								
								Examples/Stereo/EuRoC.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										116
									
								
								Examples/Stereo/EuRoC.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,116 @@ | ||||
| %YAML:1.0 | ||||
| 
 | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| # Camera Parameters. Adjust them! | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| 
 | ||||
| # Camera calibration and distortion parameters (OpenCV)  | ||||
| Camera.fx: 435.2046959714599 | ||||
| Camera.fy: 435.2046959714599 | ||||
| Camera.cx: 367.4517211914062 | ||||
| Camera.cy: 252.2008514404297 | ||||
| 
 | ||||
| Camera.k1: 0.0 | ||||
| Camera.k2: 0.0 | ||||
| Camera.p1: 0.0 | ||||
| Camera.p2: 0.0 | ||||
| 
 | ||||
| Camera.width: 752 | ||||
| Camera.height: 480 | ||||
| 
 | ||||
| # Camera frames per second  | ||||
| Camera.fps: 20.0 | ||||
| 
 | ||||
| # stereo baseline times fx | ||||
| Camera.bf: 47.90639384423901 | ||||
| 
 | ||||
| # 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 | ||||
| 
 | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| # Stereo Rectification. Only if you need to pre-rectify the images. | ||||
| # Camera.fx, .fy, etc must be the same as in LEFT.P | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| LEFT.height: 480 | ||||
| LEFT.width: 752 | ||||
| LEFT.D: !!opencv-matrix | ||||
|    rows: 1 | ||||
|    cols: 5 | ||||
|    dt: d | ||||
|    data:[-0.28340811, 0.07395907, 0.00019359, 1.76187114e-05, 0.0] | ||||
| LEFT.K: !!opencv-matrix | ||||
|    rows: 3 | ||||
|    cols: 3 | ||||
|    dt: d | ||||
|    data: [458.654, 0.0, 367.215, 0.0, 457.296, 248.375, 0.0, 0.0, 1.0] | ||||
| LEFT.R:  !!opencv-matrix | ||||
|    rows: 3 | ||||
|    cols: 3 | ||||
|    dt: d | ||||
|    data: [0.999966347530033, -0.001422739138722922, 0.008079580483432283, 0.001365741834644127, 0.9999741760894847, 0.007055629199258132, -0.008089410156878961, -0.007044357138835809, 0.9999424675829176] | ||||
| LEFT.P:  !!opencv-matrix | ||||
|    rows: 3 | ||||
|    cols: 4 | ||||
|    dt: d | ||||
|    data: [435.2046959714599, 0, 367.4517211914062, 0,  0, 435.2046959714599, 252.2008514404297, 0,  0, 0, 1, 0] | ||||
| 
 | ||||
| RIGHT.height: 480 | ||||
| RIGHT.width: 752 | ||||
| RIGHT.D: !!opencv-matrix | ||||
|    rows: 1 | ||||
|    cols: 5 | ||||
|    dt: d | ||||
|    data:[-0.28368365, 0.07451284, -0.00010473, -3.555907e-05, 0.0] | ||||
| RIGHT.K: !!opencv-matrix | ||||
|    rows: 3 | ||||
|    cols: 3 | ||||
|    dt: d | ||||
|    data: [457.587, 0.0, 379.999, 0.0, 456.134, 255.238, 0.0, 0.0, 1] | ||||
| RIGHT.R:  !!opencv-matrix | ||||
|    rows: 3 | ||||
|    cols: 3 | ||||
|    dt: d | ||||
|    data: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644] | ||||
| RIGHT.P:  !!opencv-matrix | ||||
|    rows: 3 | ||||
|    cols: 4 | ||||
|    dt: d | ||||
|    data: [435.2046959714599, 0, 367.4517211914062, -47.90639384423901, 0, 435.2046959714599, 252.2008514404297, 0, 0, 0, 1, 0] | ||||
| 
 | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| # ORB Parameters | ||||
| #-------------------------------------------------------------------------------------------- | ||||
| 
 | ||||
| # ORB Extractor: Number of features per image | ||||
| ORBextractor.nFeatures: 1200 | ||||
| 
 | ||||
| # 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 | ||||
| 
 | ||||
							
								
								
									
										3682
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH01.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										3682
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH01.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										3040
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH02.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										3040
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH02.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2700
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH03.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2700
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH03.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2032
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH04.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2032
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH04.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2273
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH05.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2273
									
								
								Examples/Stereo/EuRoC_TimeStamps/MH05.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2912
									
								
								Examples/Stereo/EuRoC_TimeStamps/V101.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2912
									
								
								Examples/Stereo/EuRoC_TimeStamps/V101.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										1710
									
								
								Examples/Stereo/EuRoC_TimeStamps/V102.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1710
									
								
								Examples/Stereo/EuRoC_TimeStamps/V102.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2149
									
								
								Examples/Stereo/EuRoC_TimeStamps/V103.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2149
									
								
								Examples/Stereo/EuRoC_TimeStamps/V103.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2280
									
								
								Examples/Stereo/EuRoC_TimeStamps/V201.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2280
									
								
								Examples/Stereo/EuRoC_TimeStamps/V201.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										2348
									
								
								Examples/Stereo/EuRoC_TimeStamps/V202.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										2348
									
								
								Examples/Stereo/EuRoC_TimeStamps/V202.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										1921
									
								
								Examples/Stereo/EuRoC_TimeStamps/V203.txt
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										1921
									
								
								Examples/Stereo/EuRoC_TimeStamps/V203.txt
									
									
									
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										66
									
								
								Examples/Stereo/KITTI00-02.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										66
									
								
								Examples/Stereo/KITTI00-02.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										66
									
								
								Examples/Stereo/KITTI03.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										66
									
								
								Examples/Stereo/KITTI03.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										66
									
								
								Examples/Stereo/KITTI04-12.yaml
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										66
									
								
								Examples/Stereo/KITTI04-12.yaml
									
									
									
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										216
									
								
								Examples/Stereo/stereo_euroc.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										216
									
								
								Examples/Stereo/stereo_euroc.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,216 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<iomanip> | ||||
| #include<chrono> | ||||
| #include <unistd.h> | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include<System.h> | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes, | ||||
|                 vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps); | ||||
| 
 | ||||
| int main(int argc, char **argv) | ||||
| { | ||||
|     if(argc != 6) | ||||
|     { | ||||
|         cerr << endl << "Usage: ./stereo_euroc path_to_vocabulary path_to_settings path_to_left_folder path_to_right_folder path_to_times_file" << endl; | ||||
|         return 1; | ||||
|     } | ||||
| 
 | ||||
|     // Retrieve paths to images
 | ||||
|     vector<string> vstrImageLeft; | ||||
|     vector<string> vstrImageRight; | ||||
|     vector<double> vTimeStamp; | ||||
|     LoadImages(string(argv[3]), string(argv[4]), string(argv[5]), vstrImageLeft, vstrImageRight, vTimeStamp); | ||||
| 
 | ||||
|     if(vstrImageLeft.empty() || vstrImageRight.empty()) | ||||
|     { | ||||
|         cerr << "ERROR: No images in provided path." << endl; | ||||
|         return 1; | ||||
|     } | ||||
| 
 | ||||
|     if(vstrImageLeft.size()!=vstrImageRight.size()) | ||||
|     { | ||||
|         cerr << "ERROR: Different number of left and right images." << endl; | ||||
|         return 1; | ||||
|     } | ||||
| 
 | ||||
|     // Read rectification parameters
 | ||||
|     cv::FileStorage fsSettings(argv[2], cv::FileStorage::READ); | ||||
|     if(!fsSettings.isOpened()) | ||||
|     { | ||||
|         cerr << "ERROR: Wrong path to settings" << endl; | ||||
|         return -1; | ||||
|     } | ||||
| 
 | ||||
|     cv::Mat K_l, K_r, P_l, P_r, R_l, R_r, D_l, D_r; | ||||
|     fsSettings["LEFT.K"] >> K_l; | ||||
|     fsSettings["RIGHT.K"] >> K_r; | ||||
| 
 | ||||
|     fsSettings["LEFT.P"] >> P_l; | ||||
|     fsSettings["RIGHT.P"] >> P_r; | ||||
| 
 | ||||
|     fsSettings["LEFT.R"] >> R_l; | ||||
|     fsSettings["RIGHT.R"] >> R_r; | ||||
| 
 | ||||
|     fsSettings["LEFT.D"] >> D_l; | ||||
|     fsSettings["RIGHT.D"] >> D_r; | ||||
| 
 | ||||
|     int rows_l = fsSettings["LEFT.height"]; | ||||
|     int cols_l = fsSettings["LEFT.width"]; | ||||
|     int rows_r = fsSettings["RIGHT.height"]; | ||||
|     int cols_r = fsSettings["RIGHT.width"]; | ||||
| 
 | ||||
|     if(K_l.empty() || K_r.empty() || P_l.empty() || P_r.empty() || R_l.empty() || R_r.empty() || D_l.empty() || D_r.empty() || | ||||
|             rows_l==0 || rows_r==0 || cols_l==0 || cols_r==0) | ||||
|     { | ||||
|         cerr << "ERROR: Calibration parameters to rectify stereo are missing!" << endl; | ||||
|         return -1; | ||||
|     } | ||||
| 
 | ||||
|     cv::Mat M1l,M2l,M1r,M2r; | ||||
|     cv::initUndistortRectifyMap(K_l,D_l,R_l,P_l.rowRange(0,3).colRange(0,3),cv::Size(cols_l,rows_l),CV_32F,M1l,M2l); | ||||
|     cv::initUndistortRectifyMap(K_r,D_r,R_r,P_r.rowRange(0,3).colRange(0,3),cv::Size(cols_r,rows_r),CV_32F,M1r,M2r); | ||||
| 
 | ||||
| 
 | ||||
|     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<float> 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, imLeftRect, imRightRect; | ||||
|     for(int ni=0; ni<nImages; ni++) | ||||
|     { | ||||
|         // Read left and right images from file
 | ||||
|         imLeft = cv::imread(vstrImageLeft[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
|         imRight = cv::imread(vstrImageRight[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
| 
 | ||||
|         if(imLeft.empty()) | ||||
|         { | ||||
|             cerr << endl << "Failed to load image at: " | ||||
|                  << string(vstrImageLeft[ni]) << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
|         if(imRight.empty()) | ||||
|         { | ||||
|             cerr << endl << "Failed to load image at: " | ||||
|                  << string(vstrImageRight[ni]) << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
|         cv::remap(imLeft,imLeftRect,M1l,M2l,cv::INTER_LINEAR); | ||||
|         cv::remap(imRight,imRightRect,M1r,M2r,cv::INTER_LINEAR); | ||||
| 
 | ||||
|         double tframe = vTimeStamp[ni]; | ||||
| 
 | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         // Pass the images to the SLAM system
 | ||||
|         SLAM.TrackStereo(imLeftRect,imRightRect,tframe); | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); | ||||
| 
 | ||||
|         vTimesTrack[ni]=ttrack; | ||||
| 
 | ||||
|         // Wait to load the next frame
 | ||||
|         double T=0; | ||||
|         if(ni<nImages-1) | ||||
|             T = vTimeStamp[ni+1]-tframe; | ||||
|         else if(ni>0) | ||||
|             T = tframe-vTimeStamp[ni-1]; | ||||
| 
 | ||||
|         if(ttrack<T) | ||||
|             usleep((T-ttrack)*1e6); | ||||
|     } | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Tracking time statistics
 | ||||
|     sort(vTimesTrack.begin(),vTimesTrack.end()); | ||||
|     float totaltime = 0; | ||||
|     for(int ni=0; ni<nImages; ni++) | ||||
|     { | ||||
|         totaltime+=vTimesTrack[ni]; | ||||
|     } | ||||
|     cout << "-------" << endl << endl; | ||||
|     cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; | ||||
|     cout << "mean tracking time: " << totaltime/nImages << endl; | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveTrajectoryTUM("CameraTrajectory.txt"); | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void LoadImages(const string &strPathLeft, const string &strPathRight, const string &strPathTimes, | ||||
|                 vector<string> &vstrImageLeft, vector<string> &vstrImageRight, vector<double> &vTimeStamps) | ||||
| { | ||||
|     ifstream fTimes; | ||||
|     fTimes.open(strPathTimes.c_str()); | ||||
|     vTimeStamps.reserve(5000); | ||||
|     vstrImageLeft.reserve(5000); | ||||
|     vstrImageRight.reserve(5000); | ||||
|     while(!fTimes.eof()) | ||||
|     { | ||||
|         string s; | ||||
|         getline(fTimes,s); | ||||
|         if(!s.empty()) | ||||
|         { | ||||
|             stringstream ss; | ||||
|             ss << s; | ||||
|             vstrImageLeft.push_back(strPathLeft + "/" + ss.str() + ".png"); | ||||
|             vstrImageRight.push_back(strPathRight + "/" + ss.str() + ".png"); | ||||
|             double t; | ||||
|             ss >> t; | ||||
|             vTimeStamps.push_back(t/1e9); | ||||
| 
 | ||||
|         } | ||||
|     } | ||||
| } | ||||
							
								
								
									
										164
									
								
								Examples/Stereo/stereo_kitti.cc
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										164
									
								
								Examples/Stereo/stereo_kitti.cc
									
									
									
									
									
										Normal file
									
								
							| @ -0,0 +1,164 @@ | ||||
| /**
 | ||||
| * This file is part of ORB-SLAM2. | ||||
| * | ||||
| * Copyright (C) 2014-2016 Raúl Mur-Artal <raulmur at unizar dot es> (University of Zaragoza) | ||||
| * For more information see <https://github.com/raulmur/ORB_SLAM2>
 | ||||
| * | ||||
| * 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 <http://www.gnu.org/licenses/>.
 | ||||
| */ | ||||
| 
 | ||||
| 
 | ||||
| #include<iostream> | ||||
| #include<algorithm> | ||||
| #include<fstream> | ||||
| #include<iomanip> | ||||
| #include<chrono> | ||||
| #include <unistd.h> | ||||
| #include<opencv2/core/core.hpp> | ||||
| 
 | ||||
| #include<System.h> | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| void LoadImages(const string &strPathToSequence, vector<string> &vstrImageLeft, | ||||
|                 vector<string> &vstrImageRight, vector<double> &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<string> vstrImageLeft; | ||||
|     vector<string> vstrImageRight; | ||||
|     vector<double> 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<float> 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<nImages; ni++) | ||||
|     { | ||||
|         // Read left and right images from file
 | ||||
|         imLeft = cv::imread(vstrImageLeft[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
|         imRight = cv::imread(vstrImageRight[ni],CV_LOAD_IMAGE_UNCHANGED); | ||||
|         double tframe = vTimestamps[ni]; | ||||
| 
 | ||||
|         if(imLeft.empty()) | ||||
|         { | ||||
|             cerr << endl << "Failed to load image at: " | ||||
|                  << string(vstrImageLeft[ni]) << endl; | ||||
|             return 1; | ||||
|         } | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t1 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t1 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         // Pass the images to the SLAM system
 | ||||
|         SLAM.TrackStereo(imLeft,imRight,tframe); | ||||
| 
 | ||||
| #ifdef COMPILEDWITHC11 | ||||
|         std::chrono::steady_clock::time_point t2 = std::chrono::steady_clock::now(); | ||||
| #else | ||||
|         std::chrono::monotonic_clock::time_point t2 = std::chrono::monotonic_clock::now(); | ||||
| #endif | ||||
| 
 | ||||
|         double ttrack= std::chrono::duration_cast<std::chrono::duration<double> >(t2 - t1).count(); | ||||
| 
 | ||||
|         vTimesTrack[ni]=ttrack; | ||||
| 
 | ||||
|         // Wait to load the next frame
 | ||||
|         double T=0; | ||||
|         if(ni<nImages-1) | ||||
|             T = vTimestamps[ni+1]-tframe; | ||||
|         else if(ni>0) | ||||
|             T = tframe-vTimestamps[ni-1]; | ||||
| 
 | ||||
|         if(ttrack<T) | ||||
|             usleep((T-ttrack)*1e6); | ||||
|     } | ||||
| 
 | ||||
|     // Stop all threads
 | ||||
|     SLAM.Shutdown(); | ||||
| 
 | ||||
|     // Tracking time statistics
 | ||||
|     sort(vTimesTrack.begin(),vTimesTrack.end()); | ||||
|     float totaltime = 0; | ||||
|     for(int ni=0; ni<nImages; ni++) | ||||
|     { | ||||
|         totaltime+=vTimesTrack[ni]; | ||||
|     } | ||||
|     cout << "-------" << endl << endl; | ||||
|     cout << "median tracking time: " << vTimesTrack[nImages/2] << endl; | ||||
|     cout << "mean tracking time: " << totaltime/nImages << endl; | ||||
| 
 | ||||
|     // Save camera trajectory
 | ||||
|     SLAM.SaveTrajectoryKITTI("CameraTrajectory.txt"); | ||||
| 
 | ||||
|     return 0; | ||||
| } | ||||
| 
 | ||||
| void LoadImages(const string &strPathToSequence, vector<string> &vstrImageLeft, | ||||
|                 vector<string> &vstrImageRight, vector<double> &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<nTimes; i++) | ||||
|     { | ||||
|         stringstream ss; | ||||
|         ss << setfill('0') << setw(6) << i; | ||||
|         vstrImageLeft[i] = strPrefixLeft + ss.str() + ".png"; | ||||
|         vstrImageRight[i] = strPrefixRight + ss.str() + ".png"; | ||||
|     } | ||||
| } | ||||
							
								
								
									
										40
									
								
								Thirdparty/DBoW2/CMakeLists.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										40
									
								
								Thirdparty/DBoW2/CMakeLists.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -0,0 +1,40 @@ | ||||
| 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 3.0 QUIET) | ||||
| if(NOT OpenCV_FOUND) | ||||
|    find_package(OpenCV 2.4.3 QUIET) | ||||
|    if(NOT OpenCV_FOUND) | ||||
|       message(FATAL_ERROR "OpenCV > 2.4.3 not found.") | ||||
|    endif() | ||||
| endif() | ||||
| 
 | ||||
| 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}) | ||||
| 
 | ||||
							
								
								
									
										130
									
								
								Thirdparty/DBoW2/DBoW2/BowVector.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										130
									
								
								Thirdparty/DBoW2/DBoW2/BowVector.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <fstream> | ||||
| #include <vector> | ||||
| #include <algorithm> | ||||
| #include <cmath> | ||||
| 
 | ||||
| #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<unsigned int>::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
 | ||||
| 
 | ||||
							
								
								
									
										109
									
								
								Thirdparty/DBoW2/DBoW2/BowVector.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										109
									
								
								Thirdparty/DBoW2/DBoW2/BowVector.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <map> | ||||
| #include <vector> | ||||
| 
 | ||||
| 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<WordId, WordValue> | ||||
| { | ||||
| 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 | ||||
							
								
								
									
										71
									
								
								Thirdparty/DBoW2/DBoW2/FClass.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										71
									
								
								Thirdparty/DBoW2/DBoW2/FClass.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <opencv2/core/core.hpp> | ||||
| #include <vector> | ||||
| #include <string> | ||||
| 
 | ||||
| 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<pDescriptor> &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<TDescriptor> &descriptors,  | ||||
|     cv::Mat &mat); | ||||
| }; | ||||
| 
 | ||||
| } // namespace DBoW2
 | ||||
| 
 | ||||
| #endif | ||||
							
								
								
									
										193
									
								
								Thirdparty/DBoW2/DBoW2/FORB.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										193
									
								
								Thirdparty/DBoW2/DBoW2/FORB.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <vector> | ||||
| #include <string> | ||||
| #include <sstream> | ||||
| #include <stdint-gcc.h> | ||||
| 
 | ||||
| #include "FORB.h" | ||||
| 
 | ||||
| using namespace std; | ||||
| 
 | ||||
| namespace DBoW2 { | ||||
| 
 | ||||
| // --------------------------------------------------------------------------
 | ||||
| 
 | ||||
| const int FORB::L=32; | ||||
| 
 | ||||
| void FORB::meanValue(const std::vector<FORB::pDescriptor> &descriptors,  | ||||
|   FORB::TDescriptor &mean) | ||||
| { | ||||
|   if(descriptors.empty()) | ||||
|   { | ||||
|     mean.release(); | ||||
|     return; | ||||
|   } | ||||
|   else if(descriptors.size() == 1) | ||||
|   { | ||||
|     mean = descriptors[0]->clone(); | ||||
|   } | ||||
|   else | ||||
|   { | ||||
|     vector<int> 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<unsigned char>(); | ||||
|        | ||||
|       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<unsigned char>(); | ||||
|      | ||||
|     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<int32_t>(); | ||||
|   const int *pb = b.ptr<int32_t>(); | ||||
| 
 | ||||
|   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<unsigned char>(); | ||||
|    | ||||
|   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<unsigned char>(); | ||||
|    | ||||
|   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<TDescriptor> &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<float>(); | ||||
|    | ||||
|   for(size_t i = 0; i < N; ++i) | ||||
|   { | ||||
|     const int C = descriptors[i].cols; | ||||
|     const unsigned char *desc = descriptors[i].ptr<unsigned char>(); | ||||
|      | ||||
|     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<TDescriptor> &descriptors,  | ||||
|   cv::Mat &mat) | ||||
| { | ||||
|   mat.create(descriptors.size(), 32, CV_8U); | ||||
|    | ||||
|   unsigned char *p = mat.ptr<unsigned char>(); | ||||
|    | ||||
|   for(size_t i = 0; i < descriptors.size(); ++i, p += 32) | ||||
|   { | ||||
|     const unsigned char *d = descriptors[i].ptr<unsigned char>(); | ||||
|     std::copy(d, d+32, p); | ||||
|   } | ||||
|    | ||||
| } | ||||
| 
 | ||||
| // --------------------------------------------------------------------------
 | ||||
| 
 | ||||
| } // namespace DBoW2
 | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										79
									
								
								Thirdparty/DBoW2/DBoW2/FORB.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										79
									
								
								Thirdparty/DBoW2/DBoW2/FORB.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <opencv2/core/core.hpp> | ||||
| #include <vector> | ||||
| #include <string> | ||||
| 
 | ||||
| #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<pDescriptor> &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<TDescriptor> &descriptors, | ||||
|     cv::Mat &mat); | ||||
| 
 | ||||
|   static void toMat8U(const std::vector<TDescriptor> &descriptors, | ||||
|     cv::Mat &mat); | ||||
| 
 | ||||
| }; | ||||
| 
 | ||||
| } // namespace DBoW2
 | ||||
| 
 | ||||
| #endif | ||||
| 
 | ||||
							
								
								
									
										85
									
								
								Thirdparty/DBoW2/DBoW2/FeatureVector.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										85
									
								
								Thirdparty/DBoW2/DBoW2/FeatureVector.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <map> | ||||
| #include <vector> | ||||
| #include <iostream> | ||||
| 
 | ||||
| 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<unsigned int>() )); | ||||
|     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<unsigned int>* 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
 | ||||
							
								
								
									
										56
									
								
								Thirdparty/DBoW2/DBoW2/FeatureVector.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										56
									
								
								Thirdparty/DBoW2/DBoW2/FeatureVector.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <map> | ||||
| #include <vector> | ||||
| #include <iostream> | ||||
| 
 | ||||
| namespace DBoW2 { | ||||
| 
 | ||||
| /// Vector of nodes with indexes of local features
 | ||||
| class FeatureVector:  | ||||
|   public std::map<NodeId, std::vector<unsigned int> > | ||||
| { | ||||
| 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 | ||||
| 
 | ||||
							
								
								
									
										315
									
								
								Thirdparty/DBoW2/DBoW2/ScoringObject.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										315
									
								
								Thirdparty/DBoW2/DBoW2/ScoringObject.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <cfloat> | ||||
| #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
 | ||||
| } | ||||
| 
 | ||||
| // ---------------------------------------------------------------------------
 | ||||
| // ---------------------------------------------------------------------------
 | ||||
| 
 | ||||
							
								
								
									
										96
									
								
								Thirdparty/DBoW2/DBoW2/ScoringObject.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										96
									
								
								Thirdparty/DBoW2/DBoW2/ScoringObject.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 | ||||
| 
 | ||||
							
								
								
									
										1665
									
								
								Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										1665
									
								
								Thirdparty/DBoW2/DBoW2/TemplatedVocabulary.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										129
									
								
								Thirdparty/DBoW2/DUtils/Random.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										129
									
								
								Thirdparty/DBoW2/DUtils/Random.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <cstdlib> | ||||
| 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; | ||||
| } | ||||
| 
 | ||||
| // ---------------------------------------------------------------------------
 | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										184
									
								
								Thirdparty/DBoW2/DUtils/Random.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										184
									
								
								Thirdparty/DBoW2/DUtils/Random.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <cstdlib> | ||||
| #include <vector> | ||||
| 
 | ||||
| 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 <class T> | ||||
| 	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 <class T> | ||||
| 	static T RandomValue(T min, T max){ | ||||
| 		return Random::RandomValue<T>() * (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 <class T> | ||||
| 	static T RandomGaussianValue(T mean, T sigma) | ||||
| 	{ | ||||
|     // Box-Muller transformation
 | ||||
|     T x1, x2, w, y1; | ||||
| 
 | ||||
|     do { | ||||
|       x1 = (T)2. * RandomValue<T>() - (T)1.; | ||||
|       x2 = (T)2. * RandomValue<T>() - (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<int> m_values; | ||||
| 
 | ||||
| }; | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| #endif | ||||
| 
 | ||||
							
								
								
									
										246
									
								
								Thirdparty/DBoW2/DUtils/Timestamp.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										246
									
								
								Thirdparty/DBoW2/DUtils/Timestamp.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <cstdio> | ||||
| #include <cstdlib> | ||||
| #include <ctime> | ||||
| #include <cmath> | ||||
| #include <sstream> | ||||
| #include <iomanip> | ||||
| 
 | ||||
| #ifdef _WIN32 | ||||
| #ifndef WIN32 | ||||
| #define WIN32 | ||||
| #endif | ||||
| #endif | ||||
| 
 | ||||
| #ifdef WIN32 | ||||
| #include <sys/timeb.h> | ||||
| #define sprintf sprintf_s | ||||
| #else | ||||
| #include <sys/time.h> | ||||
| #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(); | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
							
								
								
									
										204
									
								
								Thirdparty/DBoW2/DUtils/Timestamp.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										204
									
								
								Thirdparty/DBoW2/DUtils/Timestamp.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| 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 | ||||
| 
 | ||||
							
								
								
									
										44
									
								
								Thirdparty/DBoW2/LICENSE.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										44
									
								
								Thirdparty/DBoW2/LICENSE.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -0,0 +1,44 @@ | ||||
| DBoW2: bag-of-words library for C++ with generic descriptors | ||||
| 
 | ||||
| Copyright (c) 2015 Dorian Galvez-Lopez <http://doriangalvez.com> (Universidad de Zaragoza) | ||||
| All rights reserved. | ||||
| 
 | ||||
| Redistribution and use in source and binary forms, with or without | ||||
| modification, are permitted provided that the following conditions | ||||
| are met: | ||||
| 1. Redistributions of source code must retain the above copyright | ||||
|    notice, this list of conditions and the following disclaimer. | ||||
| 2. Redistributions in binary form must reproduce the above copyright | ||||
|    notice, this list of conditions and the following disclaimer in the | ||||
|    documentation and/or other materials provided with the distribution. | ||||
| 3. Neither the name of 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} | ||||
|   } | ||||
| 
 | ||||
							
								
								
									
										7
									
								
								Thirdparty/DBoW2/README.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										7
									
								
								Thirdparty/DBoW2/README.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										174
									
								
								Thirdparty/g2o/CMakeLists.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										174
									
								
								Thirdparty/g2o/CMakeLists.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -0,0 +1,174 @@ | ||||
| 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) | ||||
| 
 | ||||
| # 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        | ||||
| ) | ||||
							
								
								
									
										3
									
								
								Thirdparty/g2o/README.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										3
									
								
								Thirdparty/g2o/README.txt
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										419
									
								
								Thirdparty/g2o/cmake_modules/FindBLAS.cmake
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										419
									
								
								Thirdparty/g2o/cmake_modules/FindBLAS.cmake
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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) | ||||
							
								
								
									
										87
									
								
								Thirdparty/g2o/cmake_modules/FindEigen3.cmake
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										87
									
								
								Thirdparty/g2o/cmake_modules/FindEigen3.cmake
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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, <montel@kde.org> | ||||
| # Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael@free.fr> | ||||
| # Copyright (c) 2009 Benoit Jacob <jacob.benoit.1@gmail.com> | ||||
| # 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) | ||||
| 
 | ||||
							
								
								
									
										273
									
								
								Thirdparty/g2o/cmake_modules/FindLAPACK.cmake
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										273
									
								
								Thirdparty/g2o/cmake_modules/FindLAPACK.cmake
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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) | ||||
							
								
								
									
										13
									
								
								Thirdparty/g2o/config.h.in
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										13
									
								
								Thirdparty/g2o/config.h.in
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 | ||||
							
								
								
									
										119
									
								
								Thirdparty/g2o/g2o/core/base_binary_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										119
									
								
								Thirdparty/g2o/g2o/core/base_binary_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <limits> | ||||
| 
 | ||||
| #include "base_edge.h" | ||||
| #include "robust_kernel.h" | ||||
| #include "../../config.h" | ||||
| 
 | ||||
| namespace g2o { | ||||
| 
 | ||||
|   using namespace Eigen; | ||||
| 
 | ||||
|   template <int D, typename E, typename VertexXi, typename VertexXj> | ||||
|   class BaseBinaryEdge : public BaseEdge<D, E> | ||||
|   { | ||||
|     public: | ||||
| 
 | ||||
|       typedef VertexXi VertexXiType; | ||||
|       typedef VertexXj VertexXjType; | ||||
| 
 | ||||
|       static const int Di = VertexXiType::Dimension; | ||||
|       static const int Dj = VertexXjType::Dimension; | ||||
| 
 | ||||
|       static const int Dimension = BaseEdge<D, E>::Dimension; | ||||
|       typedef typename BaseEdge<D,E>::Measurement Measurement; | ||||
|       typedef typename Matrix<double, D, Di>::AlignedMapType JacobianXiOplusType; | ||||
|       typedef typename Matrix<double, D, Dj>::AlignedMapType JacobianXjOplusType; | ||||
|       typedef typename BaseEdge<D,E>::ErrorVector ErrorVector; | ||||
|       typedef typename BaseEdge<D,E>::InformationType InformationType; | ||||
| 
 | ||||
|       typedef Eigen::Map<Matrix<double, Di, Dj>, Matrix<double, Di, Dj>::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType; | ||||
|       typedef Eigen::Map<Matrix<double, Dj, Di>, Matrix<double, Dj, Di>::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockTransposedType; | ||||
| 
 | ||||
|       BaseBinaryEdge() : BaseEdge<D,E>(), | ||||
|       _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<D,E>::resize; | ||||
|       using BaseEdge<D,E>::computeError; | ||||
| 
 | ||||
|     protected: | ||||
|       using BaseEdge<D,E>::_measurement; | ||||
|       using BaseEdge<D,E>::_information; | ||||
|       using BaseEdge<D,E>::_error; | ||||
|       using BaseEdge<D,E>::_vertices; | ||||
|       using BaseEdge<D,E>::_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 | ||||
							
								
								
									
										218
									
								
								Thirdparty/g2o/g2o/core/base_binary_edge.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										218
									
								
								Thirdparty/g2o/g2o/core/base_binary_edge.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| OptimizableGraph::Vertex* BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::createFrom(){ | ||||
|   return new VertexXiType(); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| OptimizableGraph::Vertex* BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::createTo(){ | ||||
|   return new VertexXjType(); | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| void BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::resize(size_t size) | ||||
| { | ||||
|   if (size != 2) { | ||||
|     std::cerr << "WARNING, attempting to resize binary edge " << BaseEdge<D, E>::id() << " to " << size << std::endl; | ||||
|   } | ||||
|   BaseEdge<D, E>::resize(size); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| bool BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::allVerticesFixed() const | ||||
| { | ||||
|   return (static_cast<const VertexXiType*> (_vertices[0])->fixed() && | ||||
|           static_cast<const VertexXjType*> (_vertices[1])->fixed()); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| void BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::constructQuadraticForm() | ||||
| { | ||||
|   VertexXiType* from = static_cast<VertexXiType*>(_vertices[0]); | ||||
|   VertexXjType* to   = static_cast<VertexXjType*>(_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<double, D, 1> omega_r = - omega * _error; | ||||
|     if (this->robustKernel() == 0) { | ||||
|       if (fromNotFixed) { | ||||
|         Matrix<double, VertexXiType::Dimension, D> 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 <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| void BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::linearizeOplus(JacobianWorkspace& jacobianWorkspace) | ||||
| { | ||||
|   new (&_jacobianOplusXi) JacobianXiOplusType(jacobianWorkspace.workspaceForVertex(0), D, Di); | ||||
|   new (&_jacobianOplusXj) JacobianXjOplusType(jacobianWorkspace.workspaceForVertex(1), D, Dj); | ||||
|   linearizeOplus(); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| void BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::linearizeOplus() | ||||
| { | ||||
|   VertexXiType* vi = static_cast<VertexXiType*>(_vertices[0]); | ||||
|   VertexXjType* vj = static_cast<VertexXjType*>(_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 <int D, typename E, typename VertexXiType, typename VertexXjType> | ||||
| void BaseBinaryEdge<D, E, VertexXiType, VertexXjType>::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; | ||||
| } | ||||
							
								
								
									
										110
									
								
								Thirdparty/g2o/g2o/core/base_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										110
									
								
								Thirdparty/g2o/g2o/core/base_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <limits> | ||||
| 
 | ||||
| #include <Eigen/Core> | ||||
| 
 | ||||
| #include "optimizable_graph.h" | ||||
| 
 | ||||
| namespace g2o { | ||||
| 
 | ||||
|   using namespace Eigen; | ||||
| 
 | ||||
|   template <int D, typename E> | ||||
|   class BaseEdge : public OptimizableGraph::Edge | ||||
|   { | ||||
|     public: | ||||
| 
 | ||||
|       static const int Dimension = D; | ||||
|       typedef E Measurement; | ||||
|       typedef Matrix<double, D, 1> ErrorVector; | ||||
|       typedef Matrix<double, D, D> 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 | ||||
							
								
								
									
										113
									
								
								Thirdparty/g2o/g2o/core/base_multi_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										113
									
								
								Thirdparty/g2o/g2o/core/base_multi_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <iomanip> | ||||
| #include <limits> | ||||
| 
 | ||||
| #include <Eigen/StdVector> | ||||
| 
 | ||||
| #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 <int D, typename E> | ||||
|   class BaseMultiEdge : public BaseEdge<D,E> | ||||
|   { | ||||
|     public: | ||||
|       /**
 | ||||
|        * \brief helper for mapping the Hessian memory of the upper triangular block | ||||
|        */ | ||||
|       struct HessianHelper { | ||||
|         Eigen::Map<MatrixXd> 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<D,E>::Dimension; | ||||
|       typedef typename BaseEdge<D,E>::Measurement Measurement; | ||||
|       typedef MatrixXd::MapType JacobianType; | ||||
|       typedef typename BaseEdge<D,E>::ErrorVector ErrorVector; | ||||
|       typedef typename BaseEdge<D,E>::InformationType InformationType; | ||||
|       typedef Eigen::Map<MatrixXd, MatrixXd::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType; | ||||
| 
 | ||||
|       BaseMultiEdge() : BaseEdge<D,E>() | ||||
|       { | ||||
|       } | ||||
|        | ||||
|       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<D,E>::computeError; | ||||
| 
 | ||||
|     protected: | ||||
|       using BaseEdge<D,E>::_measurement; | ||||
|       using BaseEdge<D,E>::_information; | ||||
|       using BaseEdge<D,E>::_error; | ||||
|       using BaseEdge<D,E>::_vertices; | ||||
|       using BaseEdge<D,E>::_dimension; | ||||
| 
 | ||||
|       std::vector<HessianHelper> _hessian; | ||||
|       std::vector<JacobianType, aligned_allocator<JacobianType> > _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 | ||||
							
								
								
									
										222
									
								
								Thirdparty/g2o/g2o/core/base_multi_edge.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										222
									
								
								Thirdparty/g2o/g2o/core/base_multi_edge.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <int D, typename E> | ||||
| void BaseMultiEdge<D, E>::constructQuadraticForm() | ||||
| { | ||||
|   if (this->robustKernel()) { | ||||
|     double error = this->chi2(); | ||||
|     Eigen::Vector3d rho; | ||||
|     this->robustKernel()->robustify(error, rho); | ||||
|     Matrix<double, D, 1> omega_r = - _information * _error; | ||||
|     omega_r *= rho[1]; | ||||
|     computeQuadraticForm(this->robustInformation(rho), omega_r); | ||||
|   } else { | ||||
|     computeQuadraticForm(_information, - _information * _error); | ||||
|   } | ||||
| } | ||||
| 
 | ||||
| 
 | ||||
| template <int D, typename E> | ||||
| void BaseMultiEdge<D, E>::linearizeOplus(JacobianWorkspace& jacobianWorkspace) | ||||
| { | ||||
|   for (size_t i = 0; i < _vertices.size(); ++i) { | ||||
|     OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(_vertices[i]); | ||||
|     assert(v->dimension() >= 0); | ||||
|     new (&_jacobianOplus[i]) JacobianType(jacobianWorkspace.workspaceForVertex(i), D, v->dimension()); | ||||
|   } | ||||
|   linearizeOplus(); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E> | ||||
| void BaseMultiEdge<D, E>::linearizeOplus() | ||||
| { | ||||
| #ifdef G2O_OPENMP | ||||
|   for (size_t i = 0; i < _vertices.size(); ++i) { | ||||
|     OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(_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<OptimizableGraph::Vertex*>(_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<OptimizableGraph::Vertex*>(_vertices[i]); | ||||
|     v->unlockQuadraticForm(); | ||||
|   } | ||||
| #endif | ||||
| 
 | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E> | ||||
| void BaseMultiEdge<D, E>::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<OptimizableGraph::Vertex*>(HyperGraph::Edge::vertex(i)); | ||||
|   OptimizableGraph::Vertex* vj = static_cast<OptimizableGraph::Vertex*>(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 <int D, typename E> | ||||
| void BaseMultiEdge<D, E>::resize(size_t size) | ||||
| { | ||||
|   BaseEdge<D,E>::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 <int D, typename E> | ||||
| bool BaseMultiEdge<D, E>::allVerticesFixed() const | ||||
| { | ||||
|   for (size_t i = 0; i < _vertices.size(); ++i) { | ||||
|     if (!static_cast<const OptimizableGraph::Vertex*> (_vertices[i])->fixed()) { | ||||
|       return false; | ||||
|     } | ||||
|   } | ||||
|   return true; | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E> | ||||
| void BaseMultiEdge<D, E>::computeQuadraticForm(const InformationType& omega, const ErrorVector& weightedError) | ||||
| { | ||||
|   for (size_t i = 0; i < _vertices.size(); ++i) { | ||||
|     OptimizableGraph::Vertex* from = static_cast<OptimizableGraph::Vertex*>(_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<MatrixXd> fromMap(from->hessianData(), fromDim, fromDim); | ||||
|       Eigen::Map<VectorXd> 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<OptimizableGraph::Vertex*>(_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 | ||||
|     } | ||||
| 
 | ||||
|   } | ||||
| } | ||||
							
								
								
									
										100
									
								
								Thirdparty/g2o/g2o/core/base_unary_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										100
									
								
								Thirdparty/g2o/g2o/core/base_unary_edge.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <cassert> | ||||
| #include <limits> | ||||
| 
 | ||||
| #include "base_edge.h" | ||||
| #include "robust_kernel.h" | ||||
| #include "../../config.h" | ||||
| 
 | ||||
| namespace g2o { | ||||
| 
 | ||||
|   using namespace Eigen; | ||||
| 
 | ||||
|   template <int D, typename E, typename VertexXi> | ||||
|   class BaseUnaryEdge : public BaseEdge<D,E> | ||||
|   { | ||||
|     public: | ||||
|       static const int Dimension = BaseEdge<D, E>::Dimension; | ||||
|       typedef typename BaseEdge<D,E>::Measurement Measurement; | ||||
|       typedef VertexXi VertexXiType; | ||||
|       typedef typename Matrix<double, D, VertexXiType::Dimension>::AlignedMapType JacobianXiOplusType; | ||||
|       typedef typename BaseEdge<D,E>::ErrorVector ErrorVector; | ||||
|       typedef typename BaseEdge<D,E>::InformationType InformationType; | ||||
| 
 | ||||
|       BaseUnaryEdge() : BaseEdge<D,E>(), | ||||
|         _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<D,E>::resize; | ||||
|       using BaseEdge<D,E>::computeError; | ||||
| 
 | ||||
|     protected: | ||||
|       using BaseEdge<D,E>::_measurement; | ||||
|       using BaseEdge<D,E>::_information; | ||||
|       using BaseEdge<D,E>::_error; | ||||
|       using BaseEdge<D,E>::_vertices; | ||||
|       using BaseEdge<D,E>::_dimension; | ||||
| 
 | ||||
|       JacobianXiOplusType _jacobianOplusXi; | ||||
| 
 | ||||
|     public: | ||||
|       EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||||
|   }; | ||||
| 
 | ||||
| #include "base_unary_edge.hpp" | ||||
| 
 | ||||
| } // end namespace g2o
 | ||||
| 
 | ||||
| #endif | ||||
							
								
								
									
										129
									
								
								Thirdparty/g2o/g2o/core/base_unary_edge.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										129
									
								
								Thirdparty/g2o/g2o/core/base_unary_edge.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <int D, typename E, typename VertexXiType> | ||||
| void BaseUnaryEdge<D, E, VertexXiType>::resize(size_t size) | ||||
| { | ||||
|   if (size != 1) { | ||||
|     std::cerr << "WARNING, attempting to resize unary edge " << BaseEdge<D, E>::id() << " to " << size << std::endl; | ||||
|   } | ||||
|   BaseEdge<D, E>::resize(size); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType> | ||||
| bool BaseUnaryEdge<D, E, VertexXiType>::allVerticesFixed() const | ||||
| { | ||||
|   return static_cast<const VertexXiType*> (_vertices[0])->fixed(); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType> | ||||
| void BaseUnaryEdge<D, E, VertexXiType>::constructQuadraticForm() | ||||
| { | ||||
|   VertexXiType* from=static_cast<VertexXiType*>(_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 <int D, typename E, typename VertexXiType> | ||||
| void BaseUnaryEdge<D, E, VertexXiType>::linearizeOplus(JacobianWorkspace& jacobianWorkspace) | ||||
| { | ||||
|   new (&_jacobianOplusXi) JacobianXiOplusType(jacobianWorkspace.workspaceForVertex(0), D, VertexXiType::Dimension); | ||||
|   linearizeOplus(); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename E, typename VertexXiType> | ||||
| void BaseUnaryEdge<D, E, VertexXiType>::linearizeOplus() | ||||
| { | ||||
|   //Xi - estimate the jacobian numerically
 | ||||
|   VertexXiType* vi = static_cast<VertexXiType*>(_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 <int D, typename E, typename VertexXiType> | ||||
| void BaseUnaryEdge<D, E, VertexXiType>::initialEstimate(const OptimizableGraph::VertexSet&, OptimizableGraph::Vertex*) | ||||
| { | ||||
|   std::cerr << __PRETTY_FUNCTION__ << " is not implemented, please give implementation in your derived class" << std::endl; | ||||
| } | ||||
							
								
								
									
										120
									
								
								Thirdparty/g2o/g2o/core/base_vertex.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										120
									
								
								Thirdparty/g2o/g2o/core/base_vertex.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <Eigen/Core> | ||||
| #include <Eigen/Dense> | ||||
| #include <Eigen/Cholesky> | ||||
| #include <Eigen/StdVector> | ||||
| #include <stack> | ||||
| 
 | ||||
| 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 <int D, typename T> | ||||
|   class BaseVertex : public OptimizableGraph::Vertex { | ||||
|     public: | ||||
|     typedef T EstimateType; | ||||
|     typedef std::stack<EstimateType,  | ||||
|                        std::vector<EstimateType,  Eigen::aligned_allocator<EstimateType> > > | ||||
|     BackupStackType; | ||||
| 
 | ||||
|     static const int Dimension = D;           ///< dimension of the estimate (minimal) in the manifold space
 | ||||
| 
 | ||||
|     typedef Eigen::Map<Matrix<double, D, D>, Matrix<double,D,D>::Flags & AlignedBit ? Aligned : Unaligned >  HessianBlockType; | ||||
| 
 | ||||
|   public: | ||||
|     BaseVertex(); | ||||
| 
 | ||||
|     virtual const double& hessian(int i, int j) const { assert(i<D && j<D); return _hessian(i,j);} | ||||
|     virtual double& hessian(int i, int j)  { assert(i<D && j<D); return _hessian(i,j);} | ||||
|     virtual double hessianDeterminant() const {return _hessian.determinant();} | ||||
|     virtual double* hessianData() { return const_cast<double*>(_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<double, D, 1>& b() { return _b;} | ||||
|     const Matrix<double, D, 1>& 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<double, D, 1> _b; | ||||
|     EstimateType _estimate; | ||||
|     BackupStackType _backup; | ||||
|   public: | ||||
|     EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ||||
| }; | ||||
| 
 | ||||
| #include "base_vertex.hpp" | ||||
| 
 | ||||
| } // end namespace g2o
 | ||||
| 
 | ||||
| 
 | ||||
| #endif | ||||
							
								
								
									
										55
									
								
								Thirdparty/g2o/g2o/core/base_vertex.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										55
									
								
								Thirdparty/g2o/g2o/core/base_vertex.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <int D, typename T> | ||||
| BaseVertex<D, T>::BaseVertex() : | ||||
|   OptimizableGraph::Vertex(), | ||||
|   _hessian(0, D, D) | ||||
| { | ||||
|   _dimension = D; | ||||
| } | ||||
| 
 | ||||
| template <int D, typename T> | ||||
| double BaseVertex<D, T>::solveDirect(double lambda) { | ||||
|   Matrix <double, D, D> tempA=_hessian + Matrix <double, D, D>::Identity()*lambda; | ||||
|   double det=tempA.determinant(); | ||||
|   if (g2o_isnan(det) || det < std::numeric_limits<double>::epsilon()) | ||||
|     return det; | ||||
|   Matrix <double, D, 1> dx=tempA.llt().solve(_b); | ||||
|   oplus(&dx[0]); | ||||
|   return det; | ||||
| } | ||||
| 
 | ||||
| template <int D, typename T> | ||||
| void BaseVertex<D, T>::clearQuadraticForm() { | ||||
|   _b.setZero(); | ||||
| } | ||||
| 
 | ||||
| template <int D, typename T> | ||||
| void BaseVertex<D, T>::mapHessianMemory(double* d) | ||||
| { | ||||
|   new (&_hessian) HessianBlockType(d, D, D); | ||||
| } | ||||
							
								
								
									
										90
									
								
								Thirdparty/g2o/g2o/core/batch_stats.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										90
									
								
								Thirdparty/g2o/g2o/core/batch_stats.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <cstring> | ||||
| 
 | ||||
| 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
 | ||||
							
								
								
									
										83
									
								
								Thirdparty/g2o/g2o/core/batch_stats.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										83
									
								
								Thirdparty/g2o/g2o/core/batch_stats.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| #include <vector> | ||||
| 
 | ||||
| 
 | ||||
| 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<G2OBatchStatistics> BatchStatisticsContainer; | ||||
| } | ||||
| 
 | ||||
| #endif | ||||
							
								
								
									
										193
									
								
								Thirdparty/g2o/g2o/core/block_solver.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										193
									
								
								Thirdparty/g2o/g2o/core/block_solver.h
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <Eigen/Core> | ||||
| #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 <int _PoseDim, int _LandmarkDim> | ||||
|   struct BlockSolverTraits | ||||
|   { | ||||
|     static const int PoseDim = _PoseDim; | ||||
|     static const int LandmarkDim = _LandmarkDim; | ||||
|     typedef Matrix<double, PoseDim, PoseDim> PoseMatrixType; | ||||
|     typedef Matrix<double, LandmarkDim, LandmarkDim> LandmarkMatrixType; | ||||
|     typedef Matrix<double, PoseDim, LandmarkDim> PoseLandmarkMatrixType; | ||||
|     typedef Matrix<double, PoseDim, 1> PoseVectorType; | ||||
|     typedef Matrix<double, LandmarkDim, 1> LandmarkVectorType; | ||||
| 
 | ||||
|     typedef SparseBlockMatrix<PoseMatrixType> PoseHessianType; | ||||
|     typedef SparseBlockMatrix<LandmarkMatrixType> LandmarkHessianType; | ||||
|     typedef SparseBlockMatrix<PoseLandmarkMatrixType> PoseLandmarkHessianType; | ||||
|     typedef LinearSolver<PoseMatrixType> LinearSolverType; | ||||
|   }; | ||||
| 
 | ||||
|   /**
 | ||||
|    * \brief traits to summarize the properties of the dynamic size optimization problem | ||||
|    */ | ||||
|   template <> | ||||
|   struct BlockSolverTraits<Eigen::Dynamic, Eigen::Dynamic> | ||||
|   { | ||||
|     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<PoseMatrixType> PoseHessianType; | ||||
|     typedef SparseBlockMatrix<LandmarkMatrixType> LandmarkHessianType; | ||||
|     typedef SparseBlockMatrix<PoseLandmarkMatrixType> PoseLandmarkHessianType; | ||||
|     typedef LinearSolver<PoseMatrixType> 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 <typename Traits> | ||||
|   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<HyperGraph::Vertex*>& vset, const HyperGraph::EdgeSet& edges); | ||||
|       virtual bool buildSystem(); | ||||
|       virtual bool solve(); | ||||
|       virtual bool computeMarginals(SparseBlockMatrix<MatrixXd>& spinv, const std::vector<std::pair<int, int> >& 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<PoseMatrixType>* 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<PoseMatrixType>* _Hpp; | ||||
|       SparseBlockMatrix<LandmarkMatrixType>* _Hll; | ||||
|       SparseBlockMatrix<PoseLandmarkMatrixType>* _Hpl; | ||||
| 
 | ||||
|       SparseBlockMatrix<PoseMatrixType>* _Hschur; | ||||
|       SparseBlockMatrixDiagonal<LandmarkMatrixType>* _DInvSchur; | ||||
| 
 | ||||
|       SparseBlockMatrixCCS<PoseLandmarkMatrixType>* _HplCCS; | ||||
|       SparseBlockMatrixCCS<PoseMatrixType>* _HschurTransposedCCS; | ||||
| 
 | ||||
|       LinearSolver<PoseMatrixType>* _linearSolver; | ||||
| 
 | ||||
|       std::vector<PoseVectorType, Eigen::aligned_allocator<PoseVectorType> > _diagonalBackupPose; | ||||
|       std::vector<LandmarkVectorType, Eigen::aligned_allocator<LandmarkVectorType> > _diagonalBackupLandmark; | ||||
| 
 | ||||
| #    ifdef G2O_OPENMP | ||||
|       std::vector<OpenMPMutex> _coefficientsMutex; | ||||
| #    endif | ||||
| 
 | ||||
|       bool _doSchur; | ||||
| 
 | ||||
|       double* _coefficients; | ||||
|       double* _bschur; | ||||
| 
 | ||||
|       int _numPoses, _numLandmarks; | ||||
|       int _sizePoses, _sizeLandmarks; | ||||
|   }; | ||||
| 
 | ||||
| 
 | ||||
|   //variable size solver
 | ||||
|   typedef BlockSolver< BlockSolverTraits<Eigen::Dynamic, Eigen::Dynamic> > 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 | ||||
							
								
								
									
										634
									
								
								Thirdparty/g2o/g2o/core/block_solver.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										634
									
								
								Thirdparty/g2o/g2o/core/block_solver.hpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <Eigen/LU> | ||||
| #include <fstream> | ||||
| #include <iomanip> | ||||
| 
 | ||||
| #include "../stuff/timeutil.h" | ||||
| #include "../stuff/macros.h" | ||||
| #include "../stuff/misc.h" | ||||
| 
 | ||||
| namespace g2o { | ||||
| 
 | ||||
| using namespace std; | ||||
| using namespace Eigen; | ||||
| 
 | ||||
| template <typename Traits> | ||||
| BlockSolver<Traits>::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 <typename Traits> | ||||
| void BlockSolver<Traits>::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<LandmarkMatrixType>(_Hll->colBlockIndices()); | ||||
|     _Hpl=new PoseLandmarkHessianType(blockPoseIndices, blockLandmarkIndices, numPoseBlocks, numLandmarkBlocks); | ||||
|     _HplCCS = new SparseBlockMatrixCCS<PoseLandmarkMatrixType>(_Hpl->rowBlockIndices(), _Hpl->colBlockIndices()); | ||||
|     _HschurTransposedCCS = new SparseBlockMatrixCCS<PoseMatrixType>(_Hschur->colBlockIndices(), _Hschur->rowBlockIndices()); | ||||
| #ifdef G2O_OPENMP | ||||
|     _coefficientsMutex.resize(numPoseBlocks); | ||||
| #endif | ||||
|   } | ||||
| } | ||||
| 
 | ||||
| template <typename Traits> | ||||
| void BlockSolver<Traits>::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 <typename Traits> | ||||
| BlockSolver<Traits>::~BlockSolver() | ||||
| { | ||||
|   delete _linearSolver; | ||||
|   deallocate(); | ||||
| } | ||||
| 
 | ||||
| template <typename Traits> | ||||
| bool BlockSolver<Traits>::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<PoseMatrixType>* schurMatrixLookup = 0; | ||||
|   if (_doSchur) { | ||||
|     schurMatrixLookup = new SparseBlockMatrixHashMap<PoseMatrixType>(_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 <typename Traits> | ||||
| bool BlockSolver<Traits>::updateStructure(const std::vector<HyperGraph::Vertex*>& vset, const HyperGraph::EdgeSet& edges) | ||||
| { | ||||
|   for (std::vector<HyperGraph::Vertex*>::const_iterator vit = vset.begin(); vit != vset.end(); ++vit) { | ||||
|     OptimizableGraph::Vertex* v = static_cast<OptimizableGraph::Vertex*>(*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<PoseMatrixType>::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<OptimizableGraph::Edge*>(*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 <typename Traits> | ||||
| bool BlockSolver<Traits>::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<int>(_Hll->blockCols().size()); ++landmarkIndex) { | ||||
|     const typename SparseBlockMatrix<LandmarkMatrixType>::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; j<D->rows(); ++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<PoseLandmarkMatrixType>::SparseColumn& landmarkColumn = _HplCCS->blockCols()[landmarkIndex]; | ||||
| 
 | ||||
|     for (typename SparseBlockMatrixCCS<PoseLandmarkMatrixType>::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<int>(_HschurTransposedCCS->blockCols().size()) && "Index out of bounds"); | ||||
|       typename SparseBlockMatrixCCS<PoseMatrixType>::SparseColumn::iterator targetColumnIt = _HschurTransposedCCS->blockCols()[i1].begin(); | ||||
| 
 | ||||
|       typename SparseBlockMatrixCCS<PoseLandmarkMatrixType>::RowBlock aux(i1, 0); | ||||
|       typename SparseBlockMatrixCCS<PoseLandmarkMatrixType>::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 <typename Traits> | ||||
| bool BlockSolver<Traits>::computeMarginals(SparseBlockMatrix<MatrixXd>& spinv, const std::vector<std::pair<int, int> >& 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 <typename Traits> | ||||
| bool BlockSolver<Traits>::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<int>(_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<int>(_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<const OptimizableGraph::Vertex*>(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<int>(_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 <typename Traits> | ||||
| bool BlockSolver<Traits>::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 <typename Traits> | ||||
| void BlockSolver<Traits>::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 <typename Traits> | ||||
| bool BlockSolver<Traits>::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 <typename Traits> | ||||
| void BlockSolver<Traits>::setWriteDebug(bool writeDebug) | ||||
| { | ||||
|   _linearSolver->setWriteDebug(writeDebug); | ||||
| } | ||||
| 
 | ||||
| template <typename Traits> | ||||
| bool BlockSolver<Traits>::saveHessian(const std::string& fileName) const | ||||
| { | ||||
|   return _Hpp->writeOctave(fileName.c_str(), true); | ||||
| } | ||||
| 
 | ||||
| } // end namespace
 | ||||
							
								
								
									
										183
									
								
								Thirdparty/g2o/g2o/core/cache.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							
							
						
						
									
										183
									
								
								Thirdparty/g2o/g2o/core/cache.cpp
									
									
									
									
										vendored
									
									
										Normal file
									
								
							| @ -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 <iostream> | ||||
| 
 | ||||
| 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<Cache*>::iterator it=_parentCaches.begin(); it!=_parentCaches.end(); it++){ | ||||
|       (*it)->update(); | ||||
|     } | ||||
|     updateImpl(); | ||||
|     _updateNeeded=false; | ||||
|   } | ||||
| 
 | ||||
|   Cache* Cache::installDependency(const std::string& type_, const std::vector<int>& parameterIndices){ | ||||
|     ParameterVector pv(parameterIndices.size()); | ||||
|     for (size_t i=0; i<parameterIndices.size(); i++){ | ||||
|       if (parameterIndices[i]<0 || parameterIndices[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<Cache*>(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
 | ||||
Some files were not shown because too many files have changed in this diff Show More
		Loading…
	
	
			
			x
			
			
		
	
		Reference in New Issue
	
	Block a user