ROS调用USB双目摄像头模组

本篇文章内容大多来自古月居的
ROS&OpenCV下单目和双目摄像头的标定与使用
但这篇文章代码漏洞太多,严重影响正常实现,故把自己跑通的过程及代码写在下面:

双目摄像头

首先得确认你的双目摄像头属于独立的还是合成的

独立图像的双目摄像头:使用的双目摄像头在计算机中是按两个独立的设备呈现的。这种比较简单,分别作为一个ros_node发布即可。

合成图像的双目摄像头:使用的双目摄像头在计算机上是一个设备,即将两个摄像头的图像合成为了一副图像,此时需要先将一幅图分割为左右两幅,再分别作为一个ros_node发布。
ROS调用USB双目摄像头模组

我的是合成图形的双目摄像头(市场上好像大多也都是这种),所以下面只有合成图像双目的解决方案

安装usb_cam包

sudo apt install ros-melodic-usb-cam*

该包将摄像头的图像通过sensor_msgs::Image消息发布。

安装好usb_cam包后,在/opt/ros/melodic/share/usb_cam/launch中会存在一个usb_cam-test.launch文件,在该文件中启动两个ROS节点,usb_cam_node和image_view。在文件里就可以为usb_cam_node配置参数。
ROS调用USB双目摄像头模组
我们主要改的就是方框中的三个参数。

使用下面的命令查看你的摄像头设备号(把usb相机插拔前后看看哪个设备号变化了):

ls /dev/video*

ROS调用USB双目摄像头模组

可以看到我有两个video文件,不过只有给video_device设置成**/dev/video0才可以正常使用。而合成图像的双目理论上本不应该出现的/dev/video1会报错(我的电脑没有自带摄像头),不知道/dev/video1**存在的意义是什么?如果有大神路过的话跪求解答一下!!!

然后是另两个参数,也就算图像分辨率。一个摄像头图像的分辨率是1280*720,这里因为自动把两个摄像头图像合到一起去了,所以最终得到的是2560*720的分辨率。
(当然你也可以设置成1280*720,只不过待会儿只显示一幅图像并且没办法分割后变成了半副就是了【手动狗头】)

打开双目

roscore
rosrun usb_cam usb_cam_node

ROS调用USB双目摄像头模组
ROS调用USB双目摄像头模组
可以看一下rostopic:
ROS调用USB双目摄像头模组

ROS工程 – 分割双目图像

1.创建工作空间并初始化

mkdir -p catkin_ws/src 
cd catkin_ws 
catkin_make

2.进入 src 创建 ros 包并添加依赖

cd src
catkin_create_pkg camera_split cv_bridge image_transport roscpp sensor_msgs std_msgs camera_info_manager

3.修改camera_split包的CMakeLists.txt文件#修改include_directories:

find_package(OpenCV REQUIRED)
#修改include_directories:
include_directories (
    ${catkin_INCLUDE_DIRS}
    ${OpenCV_INCLUDE_DIRS}
)
#添加可执行文件
add_executable(camera_split_node src/camera_splid.cpp )
#指定链接库
target_link_libraries(camera_splid_node
    ${catkin_LIBRARIES}
    ${OpenCV_LIBRARIES}
)

4.创建源代码文件

//
// Created by daybeha on 2022/1/27.
//

#include <ros/ros.h>
#include <iostream>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <camera_info_manager/camera_info_manager.h>

#include <opencv2/opencv.hpp>
//#include <opencv2/imgproc/imgproc.hpp>
//#include <opencv2/highgui/highgui.hpp>

using namespace std;

class CameraSplitter
{
public:
    CameraSplitter():nh_("~"),it_(nh_)
    {
        image_sub_ = it_.subscribe("/usb_cam/image_raw", 1, &CameraSplitter::imageCallback, this);
        image_pub_left_ = it_.advertiseCamera("/left_cam/image_raw", 1);
        image_pub_right_ = it_.advertiseCamera("/right_cam/image_raw", 1);
        cinfo_ =boost::shared_ptr<camera_info_manager::CameraInfoManager>(new camera_info_manager::CameraInfoManager(nh_));

        //读取参数服务器参数,得到左右相机参数文件的位置
        string left_cal_file = nh_.param<std::string>("left_cam_file", "");
        string right_cal_file = nh_.param<std::string>("right_cam_file", "");
        if(!left_cal_file.empty())
        {
            if(cinfo_->validateURL(left_cal_file)) {
                cout<<"Load left camera info file: "<<left_cal_file<<endl;
                cinfo_->loadCameraInfo(left_cal_file);
                ci_left_ = sensor_msgs::CameraInfoPtr(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
            }
            else {
                cout<<"Can't load left camera info file: "<<left_cal_file<<endl;
                ros::shutdown();
            }
        }
        else {
            cout<<"Did not specify left camera info file." <<endl;
            ci_left_=sensor_msgs::CameraInfoPtr(new sensor_msgs::CameraInfo());
        }
        if(!right_cal_file.empty())
        {
            if(cinfo_->validateURL(right_cal_file)) {
                cout<<"Load right camera info file: "<<right_cal_file<<endl;
                cinfo_->loadCameraInfo(right_cal_file);
                ci_right_ = sensor_msgs::CameraInfoPtr(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
            }
            else {
                cout<<"Can't load right camera info file: "<<left_cal_file<<endl;
                ros::shutdown();
            }
        }
        else {
            cout<<"Did not specify right camera info file." <<endl;
            ci_right_=sensor_msgs::CameraInfoPtr(new sensor_msgs::CameraInfo());
        }
    }

    void imageCallback(const sensor_msgs::ImageConstPtr& msg)
    {
        cv_bridge::CvImageConstPtr cv_ptr;
        namespace enc= sensor_msgs::image_encodings;
        cv_ptr= cv_bridge::toCvShare(msg, enc::BGR8);
        //截取ROI(Region Of Interest),即左右图像,会将原图像数据拷贝出来。
        leftImgROI_=cv_ptr->image(cv::Rect(0,0,cv_ptr->image.cols/2, cv_ptr->image.rows));
        rightImgROI_=cv_ptr->image(cv::Rect(cv_ptr->image.cols/2,0, cv_ptr->image.cols/2, cv_ptr->image.rows ));
        //创建两个CvImage, 用于存放原始图像的左右部分。CvImage创建时是对Mat进行引用的,不会进行数据拷贝
        leftImgPtr_=cv_bridge::CvImagePtr(new cv_bridge::CvImage(cv_ptr->header, cv_ptr->encoding,leftImgROI_) );
        rightImgPtr_=cv_bridge::CvImagePtr(new cv_bridge::CvImage(cv_ptr->header, cv_ptr->encoding,rightImgROI_) );

        //发布到/left_cam/image_raw和/right_cam/image_raw
        ci_left_->header = cv_ptr->header; 	//很重要,不然会提示不同步导致无法去畸变
        ci_right_->header = cv_ptr->header;
        sensor_msgs::ImagePtr leftPtr =leftImgPtr_->toImageMsg();
        sensor_msgs::ImagePtr rightPtr =rightImgPtr_->toImageMsg();
        leftPtr->header=msg->header; 		//很重要,不然输出的图象没有时间戳
        rightPtr->header=msg->header;
        image_pub_left_.publish(leftPtr,ci_left_);
        image_pub_right_.publish(rightPtr,ci_right_);
    }

private:
    ros::NodeHandle nh_;
    image_transport::ImageTransport it_;
    image_transport::Subscriber image_sub_;
    image_transport::CameraPublisher image_pub_left_;
    image_transport::CameraPublisher image_pub_right_;
    boost::shared_ptr<camera_info_manager::CameraInfoManager> cinfo_;
    sensor_msgs::CameraInfoPtr ci_left_;
    sensor_msgs::CameraInfoPtr ci_right_;

    cv::Mat leftImgROI_;
    cv::Mat rightImgROI_;
    cv_bridge::CvImagePtr leftImgPtr_=NULL;
    cv_bridge::CvImagePtr rightImgPtr_=NULL;
};

int main(int argc,char** argv)
{
    ros::init(argc,argv, "camera_split");
    CameraSplitter cameraSplitter;
    ros::spin();
    return 0;
}

5.创建launch文件

camera_split_no_calibration.launch

<launch>
    <node pkg="camera_split" type="camera_split_node" name="camera_split_node" output="screen" />
    <node pkg="image_view" type="image_view" name="image_view_left" respawn="false" output="screen">
        <remap from="image" to="/left_cam/image_raw"/>
        <param name="autosize" value="true" />
    </node>
    <node pkg="image_view" type="image_view" name="image_view_right" respawn="false" output="screen">
        <remap from="image" to="/right_cam/image_raw"/>
        <param name="autosize" value="true" />
    </node>
</launch>

6.运行看看效果

cd catkin_ws
catkin_make
source ./devel/setup.bash
roslaunch camera_split camera_split_no_calibration.launch 

然后终于能看到古月居贴的这张图的效果啦:
ROS调用USB双目摄像头模组

参考:
ROS下单目摄像头的Calibration
【ROS实践入门(八)ROS使用USB视觉传感器相机】

上一篇:以友盟+U-Push为例,深度解读消息推送的筛选架构解决方案应用与实践


下一篇:前端图片压缩上传