feat:添加相机参数
parent
f1a3129ce0
commit
0c3c948156
|
@ -29,9 +29,9 @@ LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
|
|||
# 要保证整个工程的opencv版本一致,包括dbow,源码以及ros相关的
|
||||
# 3 4 都可以正常运行
|
||||
find_package(OpenCV 4.2)
|
||||
if(NOT OpenCV_FOUND)
|
||||
message(FATAL_ERROR "OpenCV > 4.2 not found.")
|
||||
endif()
|
||||
if(NOT OpenCV_FOUND)
|
||||
message(FATAL_ERROR "OpenCV > 4.2 not found.")
|
||||
endif()
|
||||
|
||||
MESSAGE("OPENCV VERSION:")
|
||||
MESSAGE(${OpenCV_VERSION})
|
||||
|
|
|
@ -0,0 +1,61 @@
|
|||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Camera.type: "PinHole"
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 773.33397
|
||||
Camera.fy: 771.95162
|
||||
Camera.cx: 626.18642
|
||||
Camera.cy: 370.88181
|
||||
|
||||
Camera.k1: -0.365133
|
||||
Camera.k2: 0.116872
|
||||
Camera.p1: -0.002987
|
||||
Camera.p2: -0.001401
|
||||
|
||||
Camera.width: 1280
|
||||
Camera.height: 720
|
||||
|
||||
# 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
|
||||
|
|
@ -0,0 +1,61 @@
|
|||
%YAML:1.0
|
||||
|
||||
#--------------------------------------------------------------------------------------------
|
||||
# Camera Parameters. Adjust them!
|
||||
#--------------------------------------------------------------------------------------------
|
||||
Camera.type: "PinHole"
|
||||
|
||||
# Camera calibration and distortion parameters (OpenCV)
|
||||
Camera.fx: 1048.96097
|
||||
Camera.fy: 1049.63887
|
||||
Camera.cx: 924.39768
|
||||
Camera.cy: 548.0414
|
||||
|
||||
Camera.k1: -0.292494
|
||||
Camera.k2: 0.076845
|
||||
Camera.p1: 0.000891
|
||||
Camera.p2: 0.001507
|
||||
|
||||
Camera.width: 1920
|
||||
Camera.height: 1080
|
||||
|
||||
# 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
|
||||
|
Loading…
Reference in New Issue