// cam_slam3.cpp // 该文件将打开你电脑的摄像头,并将图像传递给ORB-SLAM3进行定位 // opencv #include // ORB-SLAM的系统接口 #include "System.h" #include #include // for time stamp #include 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(now - start); SLAM.TrackMonocular(frame, double(timestamp.count())/1000.0); } return 0; }