国产 无码 综合区,色欲AV无码国产永久播放,无码天堂亚洲国产AV,国产日韩欧美女同一区二区

ORB_SLAM3啟動(dòng)流程以stereo_inertial_realsense_D435i為例

這篇具有很好參考價(jià)值的文章主要介紹了ORB_SLAM3啟動(dòng)流程以stereo_inertial_realsense_D435i為例。希望對(duì)大家有所幫助。如果存在錯(cuò)誤或未考慮完全的地方,請(qǐng)大家不吝賜教,您也可以點(diǎn)擊"舉報(bào)違法"按鈕提交疑問。

概述

ORB-SLAM3 是第一個(gè)同時(shí)具備純視覺(visual)數(shù)據(jù)處理、視覺+慣性(visual-inertial)數(shù)據(jù)處理、和構(gòu)建多地圖(multi-map)功能,支持單目、雙目以及 RGB-D 相機(jī),同時(shí)支持針孔相機(jī)、魚眼相機(jī)模型的 SLAM 系統(tǒng)。

主要?jiǎng)?chuàng)新點(diǎn):

1.在 IMU 初始化階段引入 MAP。該初始化方法可以實(shí)時(shí)快速進(jìn)行,魯棒性上有很大的提升(在大的場(chǎng)景還是小的場(chǎng)景,不管室內(nèi)還是室外環(huán)境均有較好表現(xiàn)),并且比當(dāng)前的其他方法具有 2-5 倍的精確度的提升。
2.基于一種召回率大大提高的 place recognition(也就是做回環(huán)檢測(cè),與歷史數(shù)據(jù)建立聯(lián)系)方法實(shí)現(xiàn)了一個(gè)多子地圖(multi-maps)系統(tǒng)。ORB-SLAM3 在視覺信息缺乏的情況下更具有 long term 魯棒性,當(dāng)跟丟的時(shí)候,這個(gè)時(shí)候就會(huì)重新建一個(gè)子地圖,并且在回環(huán)的時(shí)候與之前的子地圖進(jìn)行合并。ORB-SLAM3 是第一個(gè)可以重用歷史所有算法模塊的所有信息的系統(tǒng)。

主要結(jié)論:

在所有 sensor 配置下,ORB-SLAM3 的魯棒性與現(xiàn)在的發(fā)表的各大系統(tǒng)中相近,精度上有了顯著的提高。尤其使用Stereo-Inertial SLAM,在 EuRoC 數(shù)據(jù)集的平均誤差接近 3.6 cm,在一個(gè)偏向 AR/VR 場(chǎng)景的 TUM-VI 數(shù)據(jù)集的平均誤差接近 9mm。
ORB_SLAM3系統(tǒng)框圖
啟動(dòng)slam,ORB_SLAM3,人工智能,vr,自動(dòng)駕駛,c++

ORB_SLAM3啟動(dòng)入口在Examples文件夾中,包含單目、雙目、RGB-D,及其慣性組合。本文以雙目+慣性作為例子,介紹stereo_inertial_realsense_D435i啟動(dòng)流程。

啟動(dòng)

./Examples/Stereo-Inertial/stereo_inertial_realsense_D435i ./Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/Realsense_D435i.yaml

從啟動(dòng)參數(shù)可以看到,參數(shù)個(gè)數(shù)argc = 3,參數(shù)./Examples/Stereo-Inertial/stereo_inertial_realsense_D435i 為stereo_inertial_realsense_D435i main()函數(shù)入口,./Vocabulary/ORBvoc.txt 訓(xùn)練好的ORBvoc字典,參數(shù)./Examples/Stereo-Inertial/Realsense_D435i.yaml為D435i的配置文件,可以根據(jù)自己手上的D435i進(jìn)行相機(jī)內(nèi)外參、imu數(shù)據(jù)修改,具體可以參考系列博文Realsense d435i驅(qū)動(dòng)安裝、配置及校準(zhǔn)

進(jìn)入main函數(shù)后

一、利用librealsense2 rs接口對(duì)d435i就行設(shè)備讀取,讀取得到的句柄放sensors 中。

   ...
    string file_name;

    if (argc == 4) {
        file_name = string(argv[argc - 1]);
    }

    struct sigaction sigIntHandler;

    sigIntHandler.sa_handler = exit_loop_handler;
    sigemptyset(&sigIntHandler.sa_mask);
    sigIntHandler.sa_flags = 0;

    sigaction(SIGINT, &sigIntHandler, NULL);
    b_continue_session = true;

    double offset = 0; // ms

    rs2::context ctx;
    rs2::device_list devices = ctx.query_devices();
    rs2::device selected_device;
    if (devices.size() == 0)
    {
        std::cerr << "No device connected, please connect a RealSense device" << std::endl;
        return 0;
    }
    else
        selected_device = devices[0];

    std::vector<rs2::sensor> sensors = selected_device.query_sensors();
    int index = 0;

二、根據(jù)傳感器的類型、名字進(jìn)行相應(yīng)的設(shè)置,如使能自動(dòng)曝光補(bǔ)償、曝光限制、關(guān)閉結(jié)構(gòu)光等。

for (rs2::sensor sensor : sensors)
    if (sensor.supports(RS2_CAMERA_INFO_NAME)) {
        ++index;
        if (index == 1) {
            sensor.set_option(RS2_OPTION_ENABLE_AUTO_EXPOSURE, 1);
            sensor.set_option(RS2_OPTION_AUTO_EXPOSURE_LIMIT,5000);
            sensor.set_option(RS2_OPTION_EMITTER_ENABLED, 0); // switch off emitter
        }
        
        get_sensor_option(sensor);
        if (index == 2){
            // RGB camera (not used here...)
            sensor.set_option(RS2_OPTION_EXPOSURE,100.f);
        }

        if (index == 3){
            sensor.set_option(RS2_OPTION_ENABLE_MOTION_CORRECTION,0);
        }
    }

三、此部分可以看出,設(shè)置了相機(jī)左右目的圖片大小640*480,幀率30hz,accel/gyro數(shù)據(jù)類型為float型。

// Declare RealSense pipeline, encapsulating the actual device and sensors
rs2::pipeline pipe;
// Create a configuration for configuring the pipeline with a non default profile
rs2::config cfg;
cfg.enable_stream(RS2_STREAM_INFRARED, 1, 640, 480, RS2_FORMAT_Y8, 30);
cfg.enable_stream(RS2_STREAM_INFRARED, 2, 640, 480, RS2_FORMAT_Y8, 30);
cfg.enable_stream(RS2_STREAM_ACCEL, RS2_FORMAT_MOTION_XYZ32F);
cfg.enable_stream(RS2_STREAM_GYRO, RS2_FORMAT_MOTION_XYZ32F);

四、讀取d435i傳感器數(shù)據(jù),主要包括左右目相機(jī)數(shù)據(jù)cam_left/cam_right,imu數(shù)據(jù)imu_stream左目外參Rbc/tbc,右目外參Rbc/tbc,左右目?jī)?nèi)參intrinsics_left/intrinsics_right

    auto imu_callback = [&](const rs2::frame& frame)
    {
        std::unique_lock<std::mutex> lock(imu_mutex);

        if(rs2::frameset fs = frame.as<rs2::frameset>())
        {
            count_im_buffer++;

            double new_timestamp_image = fs.get_timestamp()*1e-3;
            if(abs(timestamp_image-new_timestamp_image)<0.001){
                // cout << "Two frames with the same timeStamp!!!\n";
                count_im_buffer--;
                return;
            }

            rs2::video_frame ir_frameL = fs.get_infrared_frame(1);
            rs2::video_frame ir_frameR = fs.get_infrared_frame(2);

            imCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(ir_frameL.get_data()), cv::Mat::AUTO_STEP);
            imRightCV = cv::Mat(cv::Size(width_img, height_img), CV_8U, (void*)(ir_frameR.get_data()), cv::Mat::AUTO_STEP);

            timestamp_image = fs.get_timestamp()*1e-3;
            image_ready = true;

            while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
            {

                int index = v_accel_timestamp_sync.size();
                double target_time = v_gyro_timestamp[index];

                v_accel_data_sync.push_back(current_accel_data);
                v_accel_timestamp_sync.push_back(target_time);
            }

            lock.unlock();
            cond_image_rec.notify_all();
        }
        else if (rs2::motion_frame m_frame = frame.as<rs2::motion_frame>())
        {
            if (m_frame.get_profile().stream_name() == "Gyro")
            {
                // It runs at 200Hz
                v_gyro_data.push_back(m_frame.get_motion_data());
                v_gyro_timestamp.push_back((m_frame.get_timestamp()+offset)*1e-3);
                //rs2_vector gyro_sample = m_frame.get_motion_data();
                //std::cout << "Gyro:" << gyro_sample.x << ", " << gyro_sample.y << ", " << gyro_sample.z << std::endl;
            }
            else if (m_frame.get_profile().stream_name() == "Accel")
            {
                // It runs at 60Hz
                prev_accel_timestamp = current_accel_timestamp;
                prev_accel_data = current_accel_data;

                current_accel_data = m_frame.get_motion_data();
                current_accel_timestamp = (m_frame.get_timestamp()+offset)*1e-3;

                while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
                {
                    int index = v_accel_timestamp_sync.size();
                    double target_time = v_gyro_timestamp[index];

                    rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp,
                                                                prev_accel_data, prev_accel_timestamp);

                    v_accel_data_sync.push_back(interp_data);
                    v_accel_timestamp_sync.push_back(target_time);

                }
                // std::cout << "Accel:" << current_accel_data.x << ", " << current_accel_data.y << ", " << current_accel_data.z << std::endl;
            }
        }
    };

    rs2::pipeline_profile pipe_profile = pipe.start(cfg, imu_callback);

    vector<ORB_SLAM3::IMU::Point> vImuMeas;
    rs2::stream_profile cam_left = pipe_profile.get_stream(RS2_STREAM_INFRARED, 1);
    rs2::stream_profile cam_right = pipe_profile.get_stream(RS2_STREAM_INFRARED, 2);


    rs2::stream_profile imu_stream = pipe_profile.get_stream(RS2_STREAM_GYRO);
    float* Rbc = cam_left.get_extrinsics_to(imu_stream).rotation;
    float* tbc = cam_left.get_extrinsics_to(imu_stream).translation;
    std::cout << "Tbc (left) = " << std::endl;
    for(int i = 0; i<3; i++){
        for(int j = 0; j<3; j++)
            std::cout << Rbc[i*3 + j] << ", ";
        std::cout << tbc[i] << "\n";
    }

    float* Rlr = cam_right.get_extrinsics_to(cam_left).rotation;
    float* tlr = cam_right.get_extrinsics_to(cam_left).translation;
    std::cout << "Tlr  = " << std::endl;
    for(int i = 0; i<3; i++){
        for(int j = 0; j<3; j++)
            std::cout << Rlr[i*3 + j] << ", ";
        std::cout << tlr[i] << "\n";
    }



    rs2_intrinsics intrinsics_left = cam_left.as<rs2::video_stream_profile>().get_intrinsics();
    width_img = intrinsics_left.width;
    height_img = intrinsics_left.height;
    cout << "Left camera: \n";
    std::cout << " fx = " << intrinsics_left.fx << std::endl;
    std::cout << " fy = " << intrinsics_left.fy << std::endl;
    std::cout << " cx = " << intrinsics_left.ppx << std::endl;
    std::cout << " cy = " << intrinsics_left.ppy << std::endl;
    std::cout << " height = " << intrinsics_left.height << std::endl;
    std::cout << " width = " << intrinsics_left.width << std::endl;
    std::cout << " Coeff = " << intrinsics_left.coeffs[0] << ", " << intrinsics_left.coeffs[1] << ", " <<
        intrinsics_left.coeffs[2] << ", " << intrinsics_left.coeffs[3] << ", " << intrinsics_left.coeffs[4] << ", " << std::endl;
    std::cout << " Model = " << intrinsics_left.model << std::endl;

    rs2_intrinsics intrinsics_right = cam_right.as<rs2::video_stream_profile>().get_intrinsics();
    width_img = intrinsics_right.width;
    height_img = intrinsics_right.height;
    cout << "Right camera: \n";
    std::cout << " fx = " << intrinsics_right.fx << std::endl;
    std::cout << " fy = " << intrinsics_right.fy << std::endl;
    std::cout << " cx = " << intrinsics_right.ppx << std::endl;
    std::cout << " cy = " << intrinsics_right.ppy << std::endl;
    std::cout << " height = " << intrinsics_right.height << std::endl;
    std::cout << " width = " << intrinsics_right.width << std::endl;
    std::cout << " Coeff = " << intrinsics_right.coeffs[0] << ", " << intrinsics_right.coeffs[1] << ", " <<
        intrinsics_right.coeffs[2] << ", " << intrinsics_right.coeffs[3] << ", " << intrinsics_right.coeffs[4] << ", " << std::endl;
    std::cout << " Model = " << intrinsics_right.model << std::endl;

從一到四部分可以看出,這部分主要是和d435i的交互,主要包括對(duì)其檢測(cè)、設(shè)置、讀取數(shù)據(jù),這部分可以看做是d435i驅(qū)動(dòng)部分。

五、進(jìn)入slam系統(tǒng),主要用于初始化系統(tǒng)線程和準(zhǔn)備工作

ORB_SLAM3::System SLAM(argv[1],argv[2],ORB_SLAM3::System::IMU_STEREO, true, 0, file_name);

/**
 * @brief 系統(tǒng)的構(gòu)造函數(shù),將會(huì)啟動(dòng)其他的線程
 * @param strVocFile 詞袋文件所在路徑
 * @param strSettingsFile 配置文件所在路徑
 * @param sensor 傳感器類型
 * @param bUseViewer 是否使用可視化界面
 * @param initFr initFr表示初始化幀的id,開始設(shè)置為0
 * @param strSequence 序列名,在跟蹤線程和局部建圖線程用得到
 */
System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor,
               const bool bUseViewer, const int initFr, const string &strSequence):
1.輸出welcome信息
// Output welcome message
cout << endl <<
"ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza." << endl <<
"ORB-SLAM2 Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza." << endl <<
"This program comes with ABSOLUTELY NO WARRANTY;" << endl  <<
"This is free software, and you are welcome to redistribute it" << endl <<
"under certain conditions. See LICENSE.txt." << endl << endl;

cout << "Input sensor was set to: ";
2.讀取配置文件

讀取配置文件對(duì)應(yīng)的就是啟動(dòng)./Examples/Stereo-Inertial/Realsense_D435i.yaml文件。針對(duì)文件版本不同對(duì)于mStrLoadAtlasFromFile、mStrSaveAtlasToFile不同。

//Check settings file
cv::FileStorage fsSettings(strSettingsFile.c_str(), cv::FileStorage::READ);
// 如果打開失敗,就輸出錯(cuò)誤信息
if(!fsSettings.isOpened())
{
   cerr << "Failed to open settings file at: " << strSettingsFile << endl;
   exit(-1);
}

// 查看配置文件版本,不同版本有不同處理方法
cv::FileNode node = fsSettings["File.version"];
if(!node.empty() && node.isString() && node.string() == "1.0")
{
	settings_ = new Settings(strSettingsFile,mSensor);

	// 保存及加載地圖的名字
	mStrLoadAtlasFromFile = settings_->atlasLoadFile();
	mStrSaveAtlasToFile = settings_->atlasSaveFile();

	cout << (*settings_) << endl;
}
else
{
	settings_ = nullptr;
	cv::FileNode node = fsSettings["System.LoadAtlasFromFile"];
	if(!node.empty() && node.isString())
	{
		mStrLoadAtlasFromFile = (string)node;
	}

	node = fsSettings["System.SaveAtlasToFile"];
	if(!node.empty() && node.isString())
	{
		mStrSaveAtlasToFile = (string)node;
	}
}
3.是否激活回環(huán)
node = fsSettings["loopClosing"];
bool activeLC = true;
if(!node.empty())
{
	activeLC = static_cast<int>(fsSettings["loopClosing"]) != 0;
}
4.詞袋文件賦值給mStrVocabularyFilePath,對(duì)應(yīng)啟動(dòng)參數(shù)./Vocabulary/ORBvoc.txt
mStrVocabularyFilePath = strVocFile;
5.多地圖管理功能

根據(jù)mStrLoadAtlasFromFile文件中是否有Atlas,進(jìn)行相應(yīng)處理。

(1)若文件中存在:

建立一個(gè)新的ORB字典,讀取預(yù)訓(xùn)練好的ORB字典并返回成功/失敗標(biāo)志,創(chuàng)建關(guān)鍵幀數(shù)據(jù)庫,創(chuàng)建多地圖;
######(2)若文件中不存在:
建立一個(gè)新的ORB字典,讀取預(yù)訓(xùn)練好的ORB字典并返回成功/失敗標(biāo)志,創(chuàng)建關(guān)鍵幀數(shù)據(jù)庫,創(chuàng)建關(guān)鍵幀數(shù)據(jù)庫,導(dǎo)入Atlas地圖,創(chuàng)建新地圖。

bool loadedAtlas = false;

if(mStrLoadAtlasFromFile.empty())
{
	//Load ORB Vocabulary
	cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;

	// 建立一個(gè)新的ORB字典
	mpVocabulary = new ORBVocabulary();
	// 讀取預(yù)訓(xùn)練好的ORB字典并返回成功/失敗標(biāo)志
	bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
	// 如果加載失敗,就輸出錯(cuò)誤信息
	if(!bVocLoad)
	{
		cerr << "Wrong path to vocabulary. " << endl;
		cerr << "Falied to open at: " << strVocFile << endl;
		exit(-1);
	}
	cout << "Vocabulary loaded!" << endl << endl;

	//Create KeyFrame Database
	// Step 4 創(chuàng)建關(guān)鍵幀數(shù)據(jù)庫
	mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);

	//Create the Atlas
	// Step 5 創(chuàng)建多地圖,參數(shù)0表示初始化關(guān)鍵幀id為0
	cout << "Initialization of Atlas from scratch " << endl;
	mpAtlas = new Atlas(0);
}
else
{
	//Load ORB Vocabulary
	cout << endl << "Loading ORB Vocabulary. This could take a while..." << endl;

	mpVocabulary = new ORBVocabulary();
	bool bVocLoad = mpVocabulary->loadFromTextFile(strVocFile);
	if(!bVocLoad)
	{
		cerr << "Wrong path to vocabulary. " << endl;
		cerr << "Falied to open at: " << strVocFile << endl;
		exit(-1);
	}
	cout << "Vocabulary loaded!" << endl << endl;

	//Create KeyFrame Database
	mpKeyFrameDatabase = new KeyFrameDatabase(*mpVocabulary);

	cout << "Load File" << endl;

	// Load the file with an earlier session
	//clock_t start = clock();
	cout << "Initialization of Atlas from file: " << mStrLoadAtlasFromFile << endl;
	bool isRead = LoadAtlas(FileType::BINARY_FILE);

	if(!isRead)
	{
		cout << "Error to load the file, please try with other session file or vocabulary file" << endl;
		exit(-1);
	}

	loadedAtlas = true;

	mpAtlas->CreateNewMap();
}
6.此部分根據(jù)是否存在imu數(shù)據(jù)進(jìn)行初始化
// 如果是有imu的傳感器類型,設(shè)置mbIsInertial = true;以后的跟蹤和預(yù)積分將和這個(gè)標(biāo)志有關(guān)
if (mSensor==IMU_STEREO || mSensor==IMU_MONOCULAR || mSensor==IMU_RGBD)
	mpAtlas->SetInertialSensor();
7.依次創(chuàng)建跟蹤、局部建圖、閉環(huán)、顯示線程
(1)創(chuàng)建用于顯示幀和地圖的類,由Viewer調(diào)用
//Create Drawers. These are used by the Viewer
mpFrameDrawer = new FrameDrawer(mpAtlas);
mpMapDrawer = new MapDrawer(mpAtlas, strSettingsFile, settings_);
(2)創(chuàng)建跟蹤線程(主線程),不會(huì)立刻開啟,會(huì)在對(duì)圖像和imu預(yù)處理后在main主線程種執(zhí)行,(main)SLAM.TrackStereo()–>mpTracker->GrabImageStereo–>Track()開啟跟蹤。
//Initialize the Tracking thread
//(it will live in the main thread of execution, the one that called this constructor)
cout << "Seq. Name: " << strSequence << endl;
mpTracker = new Tracking(this, mpVocabulary, mpFrameDrawer, mpMapDrawer,					 mpAtlas, mpKeyFrameDatabase, strSettingsFile, mSensor, settings_, strSequence);
(3)創(chuàng)建并開啟local mapping 線程,線程入口LocalMapping::Run
//Initialize the Local Mapping thread and launch
mpLocalMapper = new LocalMapping(this, mpAtlas, mSensor==MONOCULAR || mSensor==IMU_MONOCULAR,
		mSensor==IMU_MONOCULAR || mSensor==IMU_STEREO || mSensor==IMU_RGBD, strSequence);
mptLocalMapping = new thread(&ORB_SLAM3::LocalMapping::Run,mpLocalMapper);
mpLocalMapper->mInitFr = initFr;
(4)設(shè)置最遠(yuǎn)3D地圖點(diǎn)的深度值,如果超過閾值,說明可能三角化不成功,丟棄
if(settings_)
	mpLocalMapper->mThFarPoints = settings_->thFarPoints();
else
	mpLocalMapper->mThFarPoints = fsSettings["thFarPoints"];
	
if(mpLocalMapper->mThFarPoints!=0)
{
	cout << "Discard points further than " << mpLocalMapper->mThFarPoints << " m from current camera" << endl;
	mpLocalMapper->mbFarPoints = true;
}
else
	mpLocalMapper->mbFarPoints = false;
(5)創(chuàng)建并開啟閉環(huán)線程,程序入口LoopCloing::Run
//Initialize the Loop Closing thread and launch
// mSensor!=MONOCULAR && mSensor!=IMU_MONOCULAR
mpLoopCloser = new LoopClosing(mpAtlas, mpKeyFrameDatabase, mpVocabulary, mSensor!=MONOCULAR, activeLC); // mSensor!=MONOCULAR);
mptLoopClosing = new thread(&ORB_SLAM3::LoopClosing::Run, mpLoopCloser);
(6)設(shè)置線程間指針
//Set pointers between threads
mpTracker->SetLocalMapper(mpLocalMapper);
mpTracker->SetLoopClosing(mpLoopCloser);

mpLocalMapper->SetTracker(mpTracker);
mpLocalMapper->SetLoopCloser(mpLoopCloser);

mpLoopCloser->SetTracker(mpTracker);
mpLoopCloser->SetLocalMapper(mpLocalMapper);	
(7)創(chuàng)建并開啟顯示線程,程序入口Viewer::Run
//Initialize the Viewer thread and launch
if(bUseViewer)
//if(false) // TODO
{
	mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile,settings_);
	mptViewer = new thread(&Viewer::Run, mpViewer);
	mpTracker->SetViewer(mpViewer);
	mpLoopCloser->mpViewer = mpViewer;
	mpViewer->both = mpFrameDrawer->both;
}
// Fix verbosity
// 打印輸出中間的信息,設(shè)置為安靜模式
Verbose::SetTh(Verbose::VERBOSITY_QUIET);

至此,Systemf完成。

6.此部分清空imu數(shù)據(jù)向量
// Clear IMU vectors
v_gyro_data.clear();
v_gyro_timestamp.clear();
v_accel_data_sync.clear();
v_accel_timestamp_sync.clear();
7.開啟while(!isShutDown())主循環(huán)
8.根據(jù)時(shí)間戳對(duì)加速度進(jìn)行插值
while(v_gyro_timestamp.size() > v_accel_timestamp_sync.size())
{
	int index = v_accel_timestamp_sync.size();
	double target_time = v_gyro_timestamp[index];

	rs2_vector interp_data = interpolateMeasure(target_time, current_accel_data, current_accel_timestamp, prev_accel_data, prev_accel_timestamp);

	v_accel_data_sync.push_back(interp_data);
	// v_accel_data_sync.push_back(current_accel_data); // 0 interpolation
	v_accel_timestamp_sync.push_back(target_time);
}

九、壓入數(shù)據(jù)放入vImuMeas

for(int i=0; i<vGyro.size(); ++i)
{
	ORB_SLAM3::IMU::Point lastPoint(vAccel[i].x, vAccel[i].y, vAccel[i].z,
						  vGyro[i].x, vGyro[i].y, vGyro[i].z,
						  vGyro_times[i]);
	vImuMeas.push_back(lastPoint);
}

十、正式開啟雙目追蹤線程

// Stereo images are already rectified.
SLAM.TrackStereo(im, imRight, timestamp, vImuMeas);

至此,stereo_inertial_realsense_D435i啟動(dòng)流程就全部完成。其中,跟蹤Track、局部建圖LocalMapping、閉環(huán)LoopCloing、顯示線程Viewer后續(xù)再分子序列詳細(xì)敘述。

參考:

1.https://blog.csdn.net/u010196944/article/details/128972333?spm=1001.2014.3001.5501
2.https://blog.csdn.net/u010196944/article/details/127240169?spm=1001.2014.3001.5501文章來源地址http://www.zghlxwxcb.cn/news/detail-533162.html

到了這里,關(guān)于ORB_SLAM3啟動(dòng)流程以stereo_inertial_realsense_D435i為例的文章就介紹完了。如果您還想了解更多內(nèi)容,請(qǐng)?jiān)谟疑辖撬阉鱐OY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!

本文來自互聯(lián)網(wǎng)用戶投稿,該文觀點(diǎn)僅代表作者本人,不代表本站立場(chǎng)。本站僅提供信息存儲(chǔ)空間服務(wù),不擁有所有權(quán),不承擔(dān)相關(guān)法律責(zé)任。如若轉(zhuǎn)載,請(qǐng)注明出處: 如若內(nèi)容造成侵權(quán)/違法違規(guī)/事實(shí)不符,請(qǐng)點(diǎn)擊違法舉報(bào)進(jìn)行投訴反饋,一經(jīng)查實(shí),立即刪除!

領(lǐng)支付寶紅包贊助服務(wù)器費(fèi)用

相關(guān)文章

  • 【ORB_SLAM2算法中逐函數(shù)講解】

    在ORB-SLAM2算法中, TrackReferenceKeyFrame() 函數(shù)主要用于根據(jù)參考關(guān)鍵幀(Reference KeyFrame)來進(jìn)行相機(jī)位姿估計(jì)。這個(gè)函數(shù)在跟蹤過程中起到關(guān)鍵作用,它使用當(dāng)前幀與參考關(guān)鍵幀之間的匹配點(diǎn)進(jìn)行位姿估計(jì),從而實(shí)現(xiàn)視覺里程計(jì)的功能。以下是這個(gè)函數(shù)中的主要操作: 計(jì)算當(dāng)前

    2023年04月25日
    瀏覽(18)
  • 在realsense D455相機(jī)上運(yùn)行orb_slam3

    參考https://blog.csdn.net/weixin_42990464/article/details/133019718?ops_request_misc=%257B%2522request%255Fid%2522%253A%2522171109916816777224423276%2522%252C%2522scm%2522%253A%252220140713.130102334.pc%255Fblog.%2522%257Drequest_id=171109916816777224423276biz_id=0utm_medium=distribute.pc_search_result.none-task-blog-2 blog first_rank_ecpm_v1~rank_v31_ecpm

    2024年03月26日
    瀏覽(30)
  • RGB-L:基于激光雷達(dá)增強(qiáng)的ORB_SLAM3(已開源)

    RGB-L:基于激光雷達(dá)增強(qiáng)的ORB_SLAM3(已開源)

    點(diǎn)云PCL免費(fèi)知識(shí)星球,點(diǎn)云論文速讀。 文章:RGB-L: Enhancing Indirect Visual SLAM using LiDAR-based Dense Depth Maps 作者:Florian Sauerbeck, Benjamin Obermeier, Martin Rudolph 編輯:點(diǎn)云PCL 代碼:https://github.com/TUMFTM/ORB_SLAM3_RGBL.git 歡迎各位加入免費(fèi)知識(shí)星球,獲取PDF論文,歡迎轉(zhuǎn)發(fā)朋友圈。文章僅

    2024年02月07日
    瀏覽(25)
  • ORB_SLAM2配置——基于Ubuntu20.04+ROS+gazebo仿真

    ORB_SLAM2配置——基于Ubuntu20.04+ROS+gazebo仿真

    一、引言 ORB-SLAM2,它是基于單目、雙目或RGB-D相機(jī)的一個(gè)完整的SLAM系統(tǒng),其中包括地圖重用、回環(huán)檢測(cè)和重定位功能。這個(gè)系統(tǒng)可以適用于多種環(huán)境,無論是室內(nèi)小型手持設(shè)備,還是工廠環(huán)境中飛行的無人機(jī)和城市中行駛的車輛,其都可以在標(biāo)準(zhǔn)CPU上實(shí)時(shí)運(yùn)行。該系統(tǒng)的后端

    2023年04月13日
    瀏覽(25)
  • ORB_SLAM3 ROS編譯及使用D435I運(yùn)行

    ORB_SLAM3 ROS編譯及使用D435I運(yùn)行

    本文介紹ORB_SLAM3編譯、運(yùn)行中遇到問題,尤其涉及到ORB_SLAM3 ROS編譯遇到的問題。最后通過使用D435I完成在室內(nèi)環(huán)境下運(yùn)行。 本文運(yùn)行環(huán)境在Ubuntu20.04 + ROS noetic。 一、ORB_SLAM3 依賴安裝 ORB_SLAM3 依賴的安裝,有同學(xué)喜歡上來就baidu,按照別人介紹的安裝,這樣做大多數(shù)時(shí)候會(huì)出現(xiàn)

    2024年02月03日
    瀏覽(37)
  • orb_slam3實(shí)現(xiàn)保存/加載地圖功能and發(fā)布位姿功能

    先說方法:在加載的相機(jī)參數(shù)文件.yaml的最前面加上下面兩行就行。 第一行表示從本地加載名為\\\"MH01_to_MH05_stereo_inertial.osa\\\"的地圖文件,第二行表示保存名為\\\"MH01_to_MH05_stereo_inertial.osa\\\"的地圖到本地。第一次運(yùn)行建圖時(shí)注釋掉第一行,只使用第二行,加載地圖重定位時(shí)反過來,

    2024年02月15日
    瀏覽(22)
  • ORB_SLAM3配置及修改——將圖像、點(diǎn)云用ROS消息發(fā)布(基于無人機(jī)仿真)

    ORB_SLAM3配置及修改——將圖像、點(diǎn)云用ROS消息發(fā)布(基于無人機(jī)仿真)

    ????????本文有點(diǎn)長(zhǎng),可以根據(jù)目錄跳轉(zhuǎn)到想看的部分。因?yàn)榉抡婧蛻?yīng)用環(huán)境不同,可能例程的運(yùn)行方式(輸入話題等)有所不同,但第三部分有關(guān)ORB_SLAM3相機(jī)仿真標(biāo)定、第四部分有關(guān)ORB_SLAM3源碼修改的部分是通用的。 目錄 一、仿真環(huán)境配置 1.雙系統(tǒng)安裝 ① 工具準(zhǔn)備 ②

    2024年04月10日
    瀏覽(167)
  • ORB_SLAM2算法中如何計(jì)算右目和左目?jī)蓚€(gè)特征點(diǎn)的是否匹配?

    在進(jìn)行特征匹配時(shí)使用的循環(huán)。 vCandidates 是

    2024年02月06日
    瀏覽(28)
  • 記錄:ubuntu20.04+ORB_SLAM2_with_pointcloud_map+ROS noetic

    記錄:ubuntu20.04+ORB_SLAM2_with_pointcloud_map+ROS noetic

    由于相機(jī)實(shí)時(shí)在線運(yùn)行需要ROS,但Ubuntu22.04只支持ROS2,于是重裝Ubuntu20.04。 上一篇文章跑通的是官方版本的ORB_SLAM2,不支持點(diǎn)云顯示。高翔修改版本支持RGB-D相機(jī)的點(diǎn)云顯示功能。 高翔修改版本ORB_SLAM2:https://github.com/gaoxiang12/ORBSLAM2_with_pointcloud_map 環(huán)境:ubunntu20.04、opencv3.4.

    2024年02月11日
    瀏覽(24)

覺得文章有用就打賞一下文章作者

支付寶掃一掃打賞

博客贊助

微信掃一掃打賞

請(qǐng)作者喝杯咖啡吧~博客贊助

支付寶掃一掃領(lǐng)取紅包,優(yōu)惠每天領(lǐng)

二維碼1

領(lǐng)取紅包

二維碼2

領(lǐng)紅包