From 0c3c948156882213784f0feab7026978f26bbec6 Mon Sep 17 00:00:00 2001 From: 12345qiupeng Date: Thu, 4 Jul 2024 15:33:09 +0800 Subject: [PATCH] =?UTF-8?q?feat:=E6=B7=BB=E5=8A=A0=E7=9B=B8=E6=9C=BA?= =?UTF-8?q?=E5=8F=82=E6=95=B0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- CMakeLists.txt | 6 +-- Examples/ROS/ORB_SLAM3/camera1280.yaml | 61 ++++++++++++++++++++++++++ Examples/ROS/ORB_SLAM3/camera1920.yaml | 61 ++++++++++++++++++++++++++ 3 files changed, 125 insertions(+), 3 deletions(-) create mode 100644 Examples/ROS/ORB_SLAM3/camera1280.yaml create mode 100644 Examples/ROS/ORB_SLAM3/camera1920.yaml diff --git a/CMakeLists.txt b/CMakeLists.txt index 99acd59..0238126 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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}) diff --git a/Examples/ROS/ORB_SLAM3/camera1280.yaml b/Examples/ROS/ORB_SLAM3/camera1280.yaml new file mode 100644 index 0000000..865b18d --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/camera1280.yaml @@ -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 + diff --git a/Examples/ROS/ORB_SLAM3/camera1920.yaml b/Examples/ROS/ORB_SLAM3/camera1920.yaml new file mode 100644 index 0000000..645d190 --- /dev/null +++ b/Examples/ROS/ORB_SLAM3/camera1920.yaml @@ -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 +