Browse Source

Dieu Initial commit

dieu 1 year ago
parent
commit
5b32a99a3b

+ 2 - 2
CMakeLists.txt

@@ -29,8 +29,8 @@ else()
 endif()
 
 LIST(APPEND CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake_modules)
-
-find_package(OpenCV 4.2)
+set(CMAKE_PREFIX_PATH "/usr/local/include/opencv4") 
+find_package(OpenCV 4.8.1)
    if(NOT OpenCV_FOUND)
       message(FATAL_ERROR "OpenCV > 4.2 not found.")
    endif()

+ 1 - 1
Examples/Monocular/mono_euroc.cc

@@ -80,7 +80,7 @@ int main(int argc, char **argv)
     int fps = 20;
     float dT = 1.f/fps;
     // Create SLAM system. It initializes all system threads and gets ready to process frames.
-    ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, false);
+    ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::MONOCULAR, true);
     float imageScale = SLAM.GetImageScale();
 
     double t_resize = 0.f;

+ 2 - 1
Examples_old/ROS/ORB_SLAM3/CMakeLists.txt

@@ -46,9 +46,10 @@ ${PROJECT_SOURCE_DIR}
 ${PROJECT_SOURCE_DIR}/../../../
 ${PROJECT_SOURCE_DIR}/../../../include
 ${PROJECT_SOURCE_DIR}/../../../include/CameraModels
+${PROJECT_SOURCE_DIR}/../../../Thirdparty/Sophus
 ${Pangolin_INCLUDE_DIRS}
 )
-
+set(CMAKE_PREFIX_PATH "/usr/local/include/opencv4")
 set(LIBS
 ${OpenCV_LIBS}
 ${EIGEN3_LIBS}

+ 1 - 1
Thirdparty/DBoW2/CMakeLists.txt

@@ -4,7 +4,7 @@ project(DBoW2)
 if(NOT CMAKE_BUILD_TYPE)
   set(CMAKE_BUILD_TYPE Release)
 endif()
-
+set(CMAKE_PREFIX_PATH "/usr/local/include/opencv4")
 set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS}  -Wall  -O3 -march=native ")
 set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall  -O3 -march=native")
 

+ 1 - 1
Thirdparty/Sophus/sophus/common.hpp

@@ -10,7 +10,7 @@
 #include <random>
 #include <type_traits>
 
-#include <Eigen/Core>
+#include <eigen3/Eigen/Core>
 
 #if !defined(SOPHUS_DISABLE_ENSURES)
 #include "formatstring.hpp"

+ 2 - 2
Thirdparty/Sophus/sophus/rotation_matrix.hpp

@@ -4,8 +4,8 @@
 #ifndef SOPHUS_ROTATION_MATRIX_HPP
 #define SOPHUS_ROTATION_MATRIX_HPP
 
-#include <Eigen/Dense>
-#include <Eigen/SVD>
+#include <eigen3/Eigen/Dense>
+#include <eigen3/Eigen/SVD>
 
 #include "types.hpp"
 

+ 1 - 1
Thirdparty/Sophus/sophus/so2.hpp

@@ -9,7 +9,7 @@
 
 // Include only the selective set of Eigen headers that we need.
 // This helps when using Sophus with unusual compilers, like nvcc.
-#include <Eigen/LU>
+#include <eigen3/Eigen/LU>
 
 #include "rotation_matrix.hpp"
 #include "types.hpp"

+ 3 - 3
Thirdparty/Sophus/sophus/so3.hpp

@@ -10,9 +10,9 @@
 
 // Include only the selective set of Eigen headers that we need.
 // This helps when using Sophus with unusual compilers, like nvcc.
-#include <Eigen/src/Geometry/OrthoMethods.h>
-#include <Eigen/src/Geometry/Quaternion.h>
-#include <Eigen/src/Geometry/RotationBase.h>
+#include <eigen3/Eigen/src/Geometry/OrthoMethods.h>
+#include <eigen3/Eigen/src/Geometry/Quaternion.h>
+#include <eigen3/Eigen/src/Geometry/RotationBase.h>
 
 namespace Sophus {
 template <class Scalar_, int Options = 0>

+ 29 - 0
cam_slam3/CMakeLists.txt

@@ -0,0 +1,29 @@
+# CMakeLists.txt
+cmake_minimum_required(VERSION 2.8)
+project(cam_slam3)
+find_package(OpenCV 4 REQUIRED) #opencv根据版本填写版本号
+#包含头文件
+find_package(Pangolin REQUIRED)
+include_directories(${OPENCV_INCLUDE_DIRS} 
+${EIGEN3_INCLUDE_DIR}
+${Pangolin_INCLUDE_DIRS}
+#非标准头文件包含写法,根据编译报错用: sudo find / -name System.h 搜每一个缺少的头文件路径添加在下面
+~/ORB-SLAM3/include   
+~/ORB-SLAM3
+/usr/include/eigen3
+/home/dieu/Pangolin
+~/ORB-SLAM3/include/CameraModels
+)  
+#生成可执行文件
+add_executable(cam_slam3 cam_slam3.cpp)  
+#链接库文件
+target_link_libraries(cam_slam3 ${OpenCV_LIBS} 
+#非标准的链接库文件写法,根据编译报错用:sudo find / -name libpangolin.so 搜缺少的库文件
+#按绝对路径添加缺少的库文件
+/home/dieu/Pangolin/build/src/libpangolin.so
+/lib/x86_64-linux-gnu/libOpenGL.so.0
+/lib/x86_64-linux-gnu/libGLEW.so.2.2
+~/ORB-SLAM3/lib/libORB_SLAM3.so
+ 
+)
+

+ 44 - 0
cam_slam3/cam_slam3.cpp

@@ -0,0 +1,44 @@
+// cam_slam3.cpp
+// 该文件将打开你电脑的摄像头,并将图像传递给ORB-SLAM3进行定位
+ 
+// opencv
+#include <opencv2/opencv.hpp>
+ 
+// ORB-SLAM的系统接口
+#include "System.h"
+#include <string>
+#include <chrono>   // for time stamp
+#include <iostream>
+ 
+using namespace std;
+ 
+// 参数文件与字典文件
+// 如果你系统上的路径不同,请修改它
+string parameterFile = "../ost.yaml";//这个文件如果没有可以用程序里面的yaml文件代替,比如TUM1.yaml
+string vocFile = "../../Vocabulary/ORBvoc.txt";
+ 
+int main(int argc, char **argv) {
+ 
+    // 声明 ORB-SLAM2 系统
+    ORB_SLAM3::System SLAM(vocFile, parameterFile, ORB_SLAM3::System::MONOCULAR, true);
+ 
+    // 获取相机图像代码
+    cv::VideoCapture cap(0);    // change to 1 if you want to use USB camera.
+ 
+    // 分辨率设为640x480
+    cap.set(cv::CAP_PROP_FRAME_WIDTH, 640);;//设置采集视频的宽度
+    cap.set(cv::CAP_PROP_FRAME_HEIGHT, 480);//设置采集视频的高度
+ 
+    // 记录系统时间
+    auto start = chrono::system_clock::now();
+ 
+    while (1) {
+        cv::Mat frame;
+        cap >> frame;   // 读取相机数据
+        auto now = chrono::system_clock::now();
+        auto timestamp = chrono::duration_cast<chrono::milliseconds>(now - start);
+        SLAM.TrackMonocular(frame, double(timestamp.count())/1000.0);
+    }
+ 
+    return 0;
+}

+ 65 - 0
cam_slam3/ost.yaml

@@ -0,0 +1,65 @@
+%YAML:1.0
+ 
+#--------------------------------------------------------------------------------------------
+# Camera Parameters. Adjust them!
+#--------------------------------------------------------------------------------------------
+File.version: "1.0"
+ 
+Camera.type: "PinHole"
+ 
+# Camera calibration and distortion parameters (OpenCV) 
+Camera1.fx: 621.19783
+Camera1.fy: 624.29785
+Camera1.cx: 327.35984
+Camera1.cy: 238.12506
+ 
+Camera1.k1: 0.112341
+Camera1.k2: -0.170053
+Camera1.p1: -0.004971
+Camera1.p2: 0.003109
+Camera1.k3: 0.000000
+ 
+# Camera frames per second 
+Camera.fps: 30
+ 
+# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
+Camera.RGB: 1
+ 
+# Camera resolution
+Camera.width: 640
+Camera.height: 480
+ 
+#--------------------------------------------------------------------------------------------
+# 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.0
+Viewer.GraphLineWidth: 0.9
+Viewer.PointSize: 2.0
+Viewer.CameraSize: 0.08
+Viewer.CameraLineWidth: 3.0
+Viewer.ViewpointX: 0.0
+Viewer.ViewpointY: -0.7
+Viewer.ViewpointZ: -1.8
+Viewer.ViewpointF: 500.0
+

+ 3 - 3
include/ImuTypes.h

@@ -23,9 +23,9 @@
 #include <vector>
 #include <utility>
 #include <opencv2/core/core.hpp>
-#include <Eigen/Core>
-#include <Eigen/Geometry>
-#include <Eigen/Dense>
+#include <eigen3/Eigen/Core>
+#include <eigen3/Eigen/Geometry>
+#include <eigen3/Eigen/Dense>
 #include <sophus/se3.hpp>
 #include <mutex>