一抡柿、ROS圖像接口
攝像頭驅(qū)動(dòng)安裝
i5@i5-ThinkPad-T460p:~$ sudo apt install ros-kinetic-usb-cam
編寫攝像頭啟動(dòng)usb-cam.launch文件
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="640" />
<param name="image_height" value="480" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
</node>
</launch>
usb_cam功能包中的參數(shù)
參數(shù) | 類型 | 默認(rèn)值 | 描述 |
---|---|---|---|
~video_device | string | "/dev/video0" | 攝像頭設(shè)備號(hào) |
~image_width | integer | 640 | 橫向分辨率 |
~image_height | integer | 480 | 縱向分辨率 |
~pixel_format | string | "mjpeg" | 像素編碼 |
~io_method | string | "mmap" | IO通道 |
~camera_frame_id | string | "head_camera" | 攝像頭坐標(biāo)系 |
~framerate | integer | 30 | 幀率 |
~contrast | integer | 32 | 對(duì)比度号胚,0-255 |
~brightness | integer | 32 | 亮度叶洞,0-255 |
~saturation | integer | 32 | 飽和度,0-255 |
~sharpness | integer | 22 | 清晰度磅网,0-255 |
~autofocus | boolean | false | 自動(dòng)對(duì)焦 |
~focus | integer | 51 | 焦點(diǎn)(非自動(dòng)對(duì)焦?fàn)顟B(tài)下有效) |
~camera_info_url | string | "" | 攝像頭校準(zhǔn)文件路徑 |
~camera_name | string | "head_camera" | 攝像頭名稱 |
usb_cam功能包中的話題
名稱 | 類型 | 描述 |
---|---|---|
~<camera_name>/image | sensor_msgs/Image | 發(fā)布圖像數(shù)據(jù) |
i5@i5-ThinkPad-T460p:~$ rosmsg show sensor_msgs/Image
std_msgs/Header header
uint32 seq
time stamp
string frame_id
uint32 height
uint32 width
string encoding
uint8 is_bigendian
uint32 step
uint8[] data
消息中各個(gè)域的含義如下:
- header
消息頭户盯,包含消息序號(hào)屯伞,時(shí)間戳喊崖,綁定坐標(biāo)系 - height
圖像縱向分辨率 - width
圖像橫向分辨率 - encoding
圖像編碼格式挣磨,包含RGB菲宴、YUV等常用格式,不涉及圖像壓縮編碼 - is_bigendian
圖像數(shù)據(jù)的大小端存儲(chǔ)模式 - step
一行圖像數(shù)據(jù)的字節(jié)數(shù)量趋急,作為數(shù)據(jù)的步長(zhǎng)參數(shù) - data
存儲(chǔ)圖像數(shù)據(jù)的數(shù)組,大小為step*height個(gè)字節(jié)
啟動(dòng)攝像頭
i5@i5-ThinkPad-T460p:~$ roslaunch vision_application usb_cam.launch
如果使用的是帶內(nèi)置USB攝像頭的筆記本势誊,此時(shí)攝像頭應(yīng)當(dāng)已經(jīng)啟動(dòng)了:
查看攝像頭圖像
i5@i5-ThinkPad-T460p:~$ rqt_image_view
二呜达、攝像頭內(nèi)參標(biāo)定
內(nèi)參屬于攝像頭自身參數(shù),外參是指和機(jī)械臂之間的位置關(guān)系粟耻。標(biāo)定內(nèi)參是為了消除圖像的畸變查近,再做后面的識(shí)別。ROS提供了標(biāo)定功能包挤忙,直接命令行安裝:
i5@pop-os:~$ sudo apt install ros-melodic-camera-calibration
安裝后啟動(dòng)攝像頭和標(biāo)定功能程序:
i5@pop-os:~$ rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.024 image:=/usb_cam/image_raw camera:=/usb_cam
將標(biāo)定板擺放不同的位置和角度霜威,直到CALIBRATE變?yōu)榫G色,點(diǎn)擊册烈,即可完成攝像頭內(nèi)參標(biāo)定戈泼。
點(diǎn)擊SAVE,程序?qū)?biāo)定文件寫入磁盤保存赏僧。
解壓后會(huì)得到一系列標(biāo)定過(guò)程中獲得的圖片和一個(gè)yaml標(biāo)定文件大猛,這個(gè)標(biāo)定文件即包含了攝像頭的內(nèi)參,可直接在usb_cam功能包中使用淀零。
得到標(biāo)定文件后挽绩,在開頭的usb_cam.lauch文件中加入tag:
<param name="camera_info_url" type="string" value="file://$(find ur5_vision)/ost.yaml"/>
再次啟動(dòng)攝像頭后獲得的圖像即為標(biāo)定后的圖像了。如果啟動(dòng)過(guò)程中有警告:does not match name narrow_stereo in file驾中,可嘗試將yaml文件中的camera_name修改為head_camera后再重新啟動(dòng)唉堪。
三、ROS+OpenCV物體識(shí)別
在ROS中使用OpenCV肩民,可以通過(guò)CvBridge功能包來(lái)實(shí)現(xiàn)ROS圖像消息和OpenCV圖像數(shù)據(jù)結(jié)構(gòu)間的轉(zhuǎn)換:
在ROS中進(jìn)行OpenCV物體識(shí)別開發(fā)一般經(jīng)過(guò)如下的流程:
- ROS驅(qū)動(dòng)攝像頭唠亚,發(fā)布圖像消息
- 將ROS圖像消息轉(zhuǎn)換成OpenCV圖像數(shù)據(jù)
- OpenCV圖像處理
- OpenCV圖像轉(zhuǎn)換成ROS消息
下面給出在ROS中使用OpenCV人臉識(shí)別API編寫的程序示例:
頭文件
#ifndef FACE_DETECTOR_HPP_
#define FACE_DETECTOR_HPP_
#include <stdio.h>
#include <stdlib.h>
#include <iostream>
#include <opencv2/core/core.hpp>
#include <opencv2/opencv.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/objdetect.hpp>
#include "opencv2/highgui/highgui.hpp"
#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <image_transport/image_transport.h>
////定義7種顏色,用于標(biāo)記人臉
cv::Scalar colors[] =
{
// 紅橙黃綠青藍(lán)紫
CV_RGB(255,0,0),
CV_RGB(255, 97, 0),
CV_RGB(255, 255, 0),
CV_RGB(0, 255, 0),
CV_RGB(255, 97, 0),
CV_RGB(0, 0, 255),
CV_RGB(160, 32, 240),
};
class FaceDetector
{
public:
FaceDetector(ros::NodeHandle& nh);
~FaceDetector();
private:
void detectFace(const sensor_msgs::ImageConstPtr &msg);
void drawFace(cv::Mat &image, const std::vector<cv::Rect> &rect);
void imageCb(const sensor_msgs::ImageConstPtr &msg);
image_transport::ImageTransport it_;
image_transport::Subscriber image_sub_;
image_transport::Publisher image_pub_;
cv_bridge::CvImagePtr cv_ptr_;
cv::Mat gray_img_;
cv::Mat process_img_;
cv::CascadeClassifier cascade_;
std::vector<cv::Rect> rect_;
};
#endif /* FACE_DETECTOR_HPP_ */
cpp文件
#include "face_detector.hpp"
FaceDetector::FaceDetector(ros::NodeHandle& nh) : it_(nh)
{
// 加載人臉分類器
cascade_.load("/usr/share/opencv/haarcascades/haarcascade_frontalface_alt2.xml");
image_sub_ = it_.subscribe("/usb_cam/image_raw", 1, &FaceDetector::imageCb, this);
image_pub_ = it_.advertise("/face_detect", 1);
}
FaceDetector::~FaceDetector()
{
ROS_INFO("Bye bye\n");
}
void FaceDetector::drawFace(cv::Mat &image, const std::vector<cv::Rect> &rect)
{
cv::Point center;
int radius;
for(int i = 0; i < rect.size(); i++)
{
center.x = cvRound((rect[i].x + rect[i].width * 0.5));
center.y = cvRound((rect[i].y + rect[i].height * 0.5));
radius = cvRound((rect[i].width + rect[i].height) *0.25);
cv::circle(image, center, radius, colors[i % 7], 2);
}
}
void FaceDetector::detectFace(const sensor_msgs::ImageConstPtr &msg)
{
try
{
cv_ptr_ = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
}
catch (cv_bridge::Exception &e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
cv::Mat &image = cv_ptr_->image;
process_img_ = image.clone();
cv::cvtColor(image, gray_img_, CV_BGR2GRAY);
cascade_.detectMultiScale(gray_img_, rect_, 1.3, 4, 0);
ROS_INFO("%d face detected\n", static_cast<int>(rect_.size()));
drawFace(process_img_, rect_);
cv_bridge::CvImage out_image;
out_image.encoding = cv_ptr_->encoding;
out_image.header = cv_ptr_->header;
out_image.image = process_img_;
image_pub_.publish(out_image.toImageMsg());
}
void FaceDetector::imageCb(const sensor_msgs::ImageConstPtr &msg)
{
detectFace(msg);
}
int main(int argc, char** argv )
{
ros::init(argc, argv, "simple_face_vision_detection");
ros::NodeHandle n_;
ros::WallDuration(0.1).sleep();
FaceDetector fd(n_);
while (ros::ok())
{
// Process image callback
ros::spinOnce();
ros::WallDuration(0.1).sleep();
}
return 0;
}
launch文件
<launch>
<include file="$(find ur5_vision)/launch/usb_cam.launch" />
<node name="face_detector" pkg="ur5_vision" type="face_detector" output="screen" />
<node name="image_viewer" pkg="rqt_image_view" type="rqt_image_view" output="screen" >
<param name="image" value="/face_detect" />
</node>
</launch>
啟動(dòng)后將看到標(biāo)注人臉(如果有)的視頻流此改,終端會(huì)打印檢測(cè)到人臉的數(shù)目: