最近买了个1280x960的黑白摄像头,默认输出640x480,需要调节摄像头参数。
最终代码:
#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/features2d/features2d.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/calib3d/calib3d.hpp>
#include <opencv2/nonfree/nonfree.hpp>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/image_encodings.h>
#include <cv_bridge/cv_bridge.h>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
using namespace std;
using namespace cv;
int main(int argc, char** argv)
{
sensor_msgs::ImagePtr img_msg; // >> message to be sent
cv::Mat frame;
ros::init(argc, argv, "cam");
ros::NodeHandle nh;
int32_t device_id(0);
int32_t image_width(1280);
int32_t image_height(960);
nh.getParam("device_id",device_id);
nh.getParam("image_width",image_width);
nh.getParam("image_height",image_height);
VideoCapture cap(device_id); // open the default camera
if(!cap.isOpened())cout<<"Error open cam!"<<endl;
if(!cap.isOpened())return -1;// check if we succeeded
cout<<"Camera is open,to topic:cam/image"<<endl;
bool bsw,bsh;
if(cap.get(CV_CAP_PROP_FRAME_WIDTH)!=image_width)
{
bsw = cap.set(CV_CAP_PROP_FRAME_WIDTH,image_width);
bsh = cap.set(CV_CAP_PROP_FRAME_HEIGHT,image_height);
}
cout<<"Resolution:"<<cap.get(CV_CAP_PROP_FRAME_WIDTH)<<"x"<<cap.get(CV_CAP_PROP_FRAME_HEIGHT)<<endl;
image_transport::ImageTransport it(nh);
image_transport::Publisher pub_img = it.advertise("cam/image", 1);
ros::Rate rate(50);
while(nh.ok())
{
cap >> frame; // get a new frame from camera
img_msg=cv_bridge::CvImage(std_msgs::Header(), "bgr8", frame).toImageMsg();
pub_img.publish(img_msg); // ros::Publisher pub_img = node.advertise<sensor_msgs::Image>("topic", queuesize);
ros::spinOnce();
rate.sleep();
}
return 0;
}
这里有个问题,就是插上摄像头第一次可以调用set进行写入参数,但是第二次就会报错:
HIGHGUI ERROR: V4L: Initial Capture Error: Unable to load initial memory buffers.
现在还没搞清什么原因,我就才去了一个办法:
if(cap.get(CV_CAP_PROP_FRAME_WIDTH)!=image_width)
{
bsw = cap.set(CV_CAP_PROP_FRAME_WIDTH,image_width);
bsh = cap.set(CV_CAP_PROP_FRAME_HEIGHT,image_height);
}
就是一般情况不需要频繁调节分辨率,所以先读取现在的分辨率,如果和想要的一致(插上摄像头第一次运行已经配置好了)就不执行set函数了。
然后是launch文件:
<launch>
<param name="device_id" value="0"/>
<param name="image_width" value="1280"/>
<param name="image_height" value="960"/>
<node pkg="demo" type="cam" name="cam" output="screen">
</node>
</launch>
还没完,标定时发现没发布camera_info信息。待续