用笔记本自带摄像头跑通ros1 ORB_SLAM3单目程序

环境:ubuntu20.4 ros1 noetic
联想think pad x230自带摄像头

没有安装好ORB_SLAM3请参考

https://fishros.org.cn/forum/topic/842/视觉slam-orb_slam3在ubuntu18-04-ubuntu20-04-安装运行测试orb_slam3 适配单目 双目 rgbd摄像头,最容易跑通的是单目,用笔记本自带的摄像头只需修改一下话题,就能启动。

ros_mono.cc //单目主程序

/**
* This file is part of ORB-SLAM3
*
* Copyright (C) 2017-2021 Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
* Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza.
*
* ORB-SLAM3 is free software: you can redistribute it and/or modify it under the terms of the GNU General Public
* License as published by the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* ORB-SLAM3 is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even
* the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with ORB-SLAM3.
* If not, see .
*/


#include
#include
#include
#include

#include
#include 

#include

#include"../../../include/System.h"

using namespace std;

class ImageGrabber
{
public:
    ImageGrabber(ORB_SLAM3::System* pSLAM):mpSLAM(pSLAM){}

    void GrabImage(const sensor_msgs::ImageConstPtr& msg);

    ORB_SLAM3::System* mpSLAM;
};

int main(int argc, char **argv)
{
    ros::init(argc, argv, "Mono");
    ros::start();

    if(argc != 3)
    {
        cerr << endl << "Usage: rosrun ORB_SLAM3 Mono path_to_vocabulary path_to_settings" << endl;        
        ros::shutdown();
        return 1;
    }    

    // 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,true);

    ImageGrabber igb(&SLAM);

    ros::NodeHandle nodeHandler;
    //ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);//原
    ros::Subscriber sub = nodeHandler.subscribe("/usb_cam/image_raw", 1, &ImageGrabber::GrabImage,&igb);
    ros::spin();

    // Stop all threads
    SLAM.Shutdown();

    // Save camera trajectory
    SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");

    ros::shutdown();

    return 0;
}

void ImageGrabber::GrabImage(const sensor_msgs::ImageConstPtr& msg)
{
    // Copy the ros image message to cv::Mat.
    cv_bridge::CvImageConstPtr cv_ptr;
    try
    {
        cv_ptr = cv_bridge::toCvShare(msg);
    }
    catch (cv_bridge::Exception& e)
    {
        ROS_ERROR("cv_bridge exception: %s", e.what());
        return;
    }

    mpSLAM->TrackMonocular(cv_ptr->image,cv_ptr->header.stamp.toSec());
}


改动的地方:
1.把主程序原来的接收topic /camera/image_raw改成 /usb_cam/image_raw笔记本摄像头发布的话题
ros::NodeHandle nodeHandler;
//ros::Subscriber sub = nodeHandler.subscribe("/camera/image_raw", 1, &ImageGrabber::GrabImage,&igb);//原
ros::Subscriber sub = nodeHandler.subscribe("/usb_cam/image_raw", 1, &ImageGrabber::GrabImage,&igb);
ros::spin();

2安装启动摄像头
sudo apt-get install ros-noetic-usb-cam //安装摄像头驱动
roscore //启动ros核心
rosrun usb_cam usb_cam_node //启动摄像头节点
3启动单目节点
摄像头配置文件先用程序自带的,目的是先跑起来,过后在标定摄像头。
cd ORB_SLAM3
rosrun ORB_SLAM3 Mono ./Vocabulary/ORBvoc.txt ./Examples/Monocular/EuRoC.yaml
如果一切顺利,就应该能启动了,只是我的笔记本有点太老了,有点卡,但是能看到程序能正常运行了。

用笔记本自带摄像头跑通ros1 ORB_SLAM3单目程序_第1张图片

参考:用笔记本自带摄像头 奥比中光深度摄像头跑通ros1单目 rgbd | 鱼香ROS

你可能感兴趣的:(机器人,自动驾驶,开源软件)