自己最近写了一个USB相机的OpenCV程序,基于ROS。
代码:https://github.com/LarryDong/usb_cam_utils
具备功能:
- 支持打开指定端口的USB相机,避免内置镜头或其他相机设备的干扰;
- 支持自动曝光/手动曝光,支持手动曝光时间设定;
- 支持帧率fps设定、增益设定(有接口未实现);
- 支持在ros中按照一定频率发布数据,对于相机标定时(例如Kalibr)降低频率很有用;
- 独立线程高速读取相机缓存,避免缓存造成图像延迟
使用方法
请查看代码的Readme.md
。
一些Bug记录
- OpenCV的Set指令,无法改变相机的曝光值
原因:需要先禁用自动曝光,再手动修改曝光值
cap.set(cv::CAP_PROP_AUTO_EXPOSURE, 0.25); // 注意禁用的参数是0.25
cap.set(cv::CAP_PROP_EXPOSURE, exposure);
- 无法切换为自动曝光
原因:需要重置相机,即插拔后CAP_PROP_AUTO_EXPOSURE
才有效。
cap.set(cv::CAP_PROP_AUTO_EXPOSURE, -1); // 注意启用自动曝光参数是-1
- 拍摄的图像有很大的延迟,低频发布时更加明显
原因:VideoCapture的Cap是有缓存的,因此会有延迟。Set中有一个参数CAP_PROP_BUFFERSIZE
虽然看起来可以修改缓存长度,但没有作用。详见:https://github.com/dactylroot/rtsp/issues/13
另一种解决思路,是新开一个线程不断读取buffer,当主线程需要图像时获取新开线程的最新读到的数据。
但是直接采用VideoCapture.read()
或cap>>frame
的方式占用过高,因此采用grab
+retrieve
的方法,grab时只是捕获图像不进行读取,retrieve时在读取出来。具体代码:
bool res = cap.grab();
if(res)
cap.retrieve(g_newest_frame);
- 开启子线程后启动时报错:“<待补充>”
原因:不清楚,但需要增加一个std::ref()
表示是引用
// 子线程
void read_video_buffer(VideoCapture& cap){}
// 主线程中传递VideoCapture
VideoCapture cap(video_port);
thread t(read_video_buffer,std::ref(cap)); // 注意这里不加 `std::ref` 会报错
完整代码如下
#include <iostream>
#include <opencv2/opencv.hpp>
#include <ros/ros.h>
#include <std_msgs/String.h>
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
#include <thread> // thread for reading to clean the buffer.
#include <mutex>
using namespace std;
using namespace cv;
std::mutex g_mutex;
Mat g_newest_frame;
void read_video_buffer(VideoCapture& cap){
cout << "--> New thread begin." << endl;
if(!cap.isOpened()){
cout << "[Error]. No cap found." << endl;
return ;
}
while(1){ // always retriving image using "grab" in a new thread.
bool res = cap.grab();
g_mutex.lock();
if(res){
cap.retrieve(g_newest_frame);
}
g_mutex.unlock();
}
}
int main(int argc, char **argv){
// google::ParseCommandLineFlags(&argc, &argv, true);
ros::init(argc, argv, "rgb_driver");
ros::NodeHandle nh;
int video_port = 0;
int fps = 10;
double exposure = 0;
double gain = 0; // not implemented
bool show_image = false;
ros::param::get("~video_port", video_port); // get videoX, X is defined in roslaunch file.
ros::param::get("~fps", fps); // set FPS.
ros::param::get("~exposure", exposure); // set exposure time. unit: s.
int output_rate = 100;
ros::param::get("~output_rate", output_rate); // set exposure time. unit: s.
ros::param::get("~show_image", show_image); // show image or not.
image_transport::ImageTransport it(nh);
image_transport::Publisher pubImage = it.advertise("/image", 1);
ROS_INFO_STREAM("Open camera from: /dev/video" << video_port);
VideoCapture cap(video_port);
while(!cap.isOpened()){
ROS_WARN("Cannot open camera...");
sleep(1);
}
ROS_INFO("Camera opened. Setting camera properties...");
cap.set(cv::CAP_PROP_FRAME_WIDTH, 1920);
cap.set(cv::CAP_PROP_FRAME_HEIGHT, 1280);
cap.set(cv::CAP_PROP_FPS, fps);
if(exposure == 0){
ROS_INFO("Using auto-exposure");
cap.set(cv::CAP_PROP_AUTO_EXPOSURE, -1);
}
else{
// ROS_INFO_STREAM("Set exposure time: " << exposure << "s.");
cap.set(cv::CAP_PROP_AUTO_EXPOSURE, 0.25);
cap.set(cv::CAP_PROP_EXPOSURE, exposure);
}
int actual_fps = cap.get(cv::CAP_PROP_FPS);
if(actual_fps != fps){
ROS_WARN_STREAM("FPS not setted correctly. Set: " << fps << ", actual: " << actual_fps);
}
if(actual_fps < output_rate){
ROS_WARN_STREAM("image publish rate (" <<output_rate<<") is larger than actual fps ("<<actual_fps<<"), which may contain duplicated frames");
}
ROS_INFO("Begin to publish rgb image...");
cout << "------------------------------ Settings ------------------------------" << endl;
cout << "Image size: " << cap.get(cv::CAP_PROP_FRAME_WIDTH) << ", " << cap.get(cv::CAP_PROP_FRAME_HEIGHT) << endl;
cout << "Exposure time: " << cap.get(cv::CAP_PROP_EXPOSURE) << "s. (Setting: " << to_string(exposure) << ")." << endl;
cout << "FPS: " << cap.get(cv::CAP_PROP_FPS) << ". (Settings " << to_string(fps) << "). " << endl;
cout << "Gain: " << cap.get(cv::CAP_PROP_GAIN) << endl;
cout << "------------------------------ Settings ------------------------------" << endl;
thread t(read_video_buffer,std::ref(cap)); // start a new treading for reading.
ROS_INFO_STREAM("Publish image topic rate (MAX): " << output_rate);
ros::Rate r(output_rate); // publish the topic by output-rate
while (ros::ok()) {
g_mutex.lock();
Mat src = g_newest_frame.clone();
g_mutex.unlock();
if(!src.empty()){
std_msgs::Header hd;
hd.stamp = ros::Time::now();
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(hd, "bgr8", src).toImageMsg();
pubImage.publish(msg);
if(show_image){
cv::imshow("video"+to_string(video_port), src);
int key = waitKey(1);
if (key == 'q'){
ROS_INFO("Stop viewing image.");
show_image = false;
cv::destroyWindow("video"+to_string(video_port));
}
}
}
ros::spinOnce();
r.sleep();
}
return 0;
}
启动的launch
文件
<launch>
<node pkg="rgb_driver" type="rgb_driver" name="rgb_driver" output="screen">
<!-- Camera properties -->
<param name="video_port" type="int" value= "0"/> <!-- Open /dev/video%{video_port} to avoid built-in camera. -->
<param name="fps" type="int" value= "10"/> <!-- fps cannot be set for some camera -->
<param name="exposure" type="double" value= "0.01"/> <!-- exposure unit: s. Set 0 for auto exposure. Plug-in/off the camera if switch to auto.-->
<!-- view properties -->
<param name="show_image" type="bool" value= "true"/> <!-- show image or not. Press 'q' to quit viewing. -->
<!-- ros properties -->
<param name="output_rate" type="int" value= "2"/> <!-- image output topic rate. If the `actual fps` < `output_rate`, the published images may be duplicated -->
<remap from="/image" to="/image"/>
</node>
</launch>