前言
对于一般的USB相机,没有专门的相机驱动供我们使用,利用ros功能包usb_cam可以让我们把相机传感器接收到的图片信息转化为topic供其他程序使用
创建工作空间
mkdir -p usb_ws/src
cd usb_ws/src
catkin_init_workspace
编译工作空间
cd ~/usb_ws/
catkin_make
使得环境变量在所有的终端中都有效
echo "source ~/usb_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
查看添加的环境变量是否生效:
echo $ROS_PACKAGE_PATH
编译安装USB相机驱动
下载usb_cam压缩包
在网站:usb_cam选择合适的压缩包(我是ubuntu20.04/ros neotic选择的是develop的包)
提取到工作空间/usb_ws/src目录下
编译代码文件
cd usb_ws
catkin_make
报错
No package 'libv4l2' found
再打开一个终端,输入
sudo apt-get install libv4l-dev
然后重新编译即可
修改启动文件
将相机插入电脑,利用指令
ls /dev/video*
查看相机设备号
打开launch文件usb_cam-test.lauch,修改如下:
<launch>
<arg name="image_view" default="false" />
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<rosparam command="load" file="$(find usb_cam)/config/usb_cam.yml"/>
<param name="video_device" value="/dev/video0" />
//把/dev/video0修改为自己相机对应的设备号
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
//usb_cam支持三种图片格式:yuyv,mjpeg,uyvy,可以先设置为yuyv,移动摄像头,如果画面很卡顿那就轮流试试mjpeg和uyuv
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap" />
</node>
<node if="$(arg image_view)" name="image_view" pkg="image_view" type="image_view"
respawn="false" output="screen">
<remap from="image" to="/usb_cam/image_raw"/>
<param name="autosize" value="true" />
</node>
</launch>
如果需要运行双目单usb端口摄像头,launch文件单目的大体相同,只是改第四第五行分辨率640*480为2560*720,如果不改分辨率640*480只有双目其中一个摄像头的画面,2560*720是两个1280*720的图像,改完分辨率运行步骤与单目相同
编译usb_cam相机驱动
cd usb_ws
catkin_make
使工作空间的环境变量永久有效
source devel/setup.bash
echo "source ~/usb_ws/devel/setup.sh" >> ~/.bashrc //永久生效环境
启动相机节点接收信息
使用指令:
roslaunch usb_cam usb_cam-test.launch
启动相机,再打开rviz选择相应的topic即可查看图像信息
分割双目图像
1.创建工作空间并添加依赖
mkdir -p cut_ws/src
cd cut_ws
catkin_make
cd src
catkin_create_pkg camera_split cv_bridge image_transport roscpp sensor_msgs std_msgs camera_info_manager
2.修改CMakeList.txt文件
find_package(OpenCV REQUIRED)
#修改include_directories:
include_directories (
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
)
#添加可执行文件
add_executable(camera_split_node src/camera_split.cpp )
#指定链接库
target_link_libraries(camera_split_node
${catkin_LIBRARIES}
${OpenCV_LIBRARIES}
)
3.创建源代码文件camera_split.cpp
//
// 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 cut_ws
catkin_make
source ./devel/setup.bash
roslaunch camera_split camera_split_no_calibration.launch