ROS实战之人脸检测

ROS实战之人脸检测

ROS:indigo
摄像头:罗技c270
本次实战中人脸检测代码主要参考opencv源码中的facedetect.cpp,根据自己的需要进行裁剪。
编程思想:
在上一篇博客ROS实战之图像发送和接收开始已经定义两个节点分别用于发送摄像头图像和显示图像,在本次实战中将再次增加一个节点用于人脸检测算法的执行。
以下贴出源码:
img_deal.cpp

/*
 *  Author: OJ
 *  Date: 2016/08/27
 *  Function: deal with the image
 */
#include <iterator>
#include <ros/ros.h>
#include "../include/img_deal.h"
#include <cv_bridge/cv_bridge.h>
#include <opencv2/highgui/highgui.hpp>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/objdetect/objdetect.hpp>
#include <image_transport/image_transport.h>


using namespace std;
using namespace cv;


int main(int argc, char *argv[])
{
    /*初始化节点,并设定节点名*/
    ros::init(argc, argv, "img_deal");
    /*设置节点句柄*/
    ros::NodeHandle n;  

    /*定义图像节点*/
    NODE img_node(n);

    /*回调响应循环*/
    ros::spin();

    return 0;
}

img_deal.h

#ifndef IMG_DEAL_H_INCLUDE
#define IMG_DEAL_H_INCLUDE

#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/highgui/highgui.hpp>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/objdetect/objdetect.hpp>
#include <image_transport/image_transport.h>

using namespace std;
using namespace cv;

/*人脸分类器配置文件*/
string cascadeName = "../haarcascade_frontalface_alt.xml";
//string nestedCascadeName = "../haarcascade_eye_tree_eyeglasses.xml";


/*
 *  class name: IMAGE
 *  function:   作为人脸检测及数据预处理过程中的图像对象
 */
class IMAGE{
friend class NODE;
public:
    /*构造函数*/
    IMAGE(Mat preimg, double &scale):
        img(preimg),
        smallImg(cvRound((img.rows)/scale), cvRound((img.cols)/scale), CV_8UC1){
            /*对图像进行灰度处理,并存放到gray中*/
            cvtColor(img, gray, CV_BGR2GRAY);
            /*使用双线性插值法来对图像进行缩放*/
            resize(gray, smallImg, smallImg.size(), 0, 0, INTER_LINEAR);
            /*将缩放后的灰度图像进行直方均衡化处理*/
            equalizeHist(smallImg, histImg);
            /*初始化CvImage智能指针,CvImage为Mat与ROS图像之间转换的载体*/
            frame = boost::make_shared<cv_bridge::CvImage>();
            /*加载分类器配置文件,并判断是否成功*/
            if(!cascade.load(cascadeName))
            {
                ROS_ERROR("Fail to load the '%s'.", cascadeName.c_str());
                exit(1);
            }
        }
    int facedetect(double scale);   /*声明人脸检测程序facedetect*/
private:
    Mat img;    //从主题接收到的图像信息
    Mat gray;   //灰度图像
    Mat smallImg;   //缩放图像
    Mat histImg;    //直方均衡化图像
    cv_bridge::CvImagePtr frame;    //转换为ROS图像的中介
    CascadeClassifier cascade;  /*定义分类器变量*/
};


/*
 *  class name: NODE
 *  function:   节点对象,包含节点的各项属性和回调函数
 */
class NODE{
public:
    void imgpredeal(const sensor_msgs::ImageConstPtr &msg);
    NODE(ros::NodeHandle &n):
        it(n){
        /*订阅信息并设定回调函数,不是很明白*/
        sub = it.subscribe("camera/original_img", 1, &NODE::imgpredeal, this);
        /*发布主题,向主节点进行注册*/
        pub = it.advertise("camera/deal_img", 1);
    }
private:
    image_transport::ImageTransport it; //设置接收图像的节点
    image_transport::Subscriber sub;    //设置图像订阅者
    image_transport::Publisher pub;     //设置图像发布者
};


/*
 *  Name: imgpredeal
 *  function: 对从主题上收到的图像信息进行预处理
 ×  param:  ROS上的图像信息
 */
void NODE::imgpredeal(const sensor_msgs::ImageConstPtr &msg)
{
    double scale = 1;   //图像缩放尺度

    /*将接收到的ROS图像进行人脸检测前的预处理*/
    try{
        IMAGE image(cv_bridge::toCvShare(msg, "bgr8")->image, scale);
        /*对图像进行人脸检测*/
        image.facedetect(scale);

        /*将检测完的图像发布出去*/
        /*设置ROS图片为BGR且每个像素点用1个字节来表示类似与CV_8U*/
        image.frame->encoding = sensor_msgs::image_encodings::BGR8;
        /*将处理完的图片传给frame*/
        image.frame->image = image.img;
        /*附上时间戳*/
        image.frame->header.stamp = ros::Time::now();
        /*节点发送主题*/
        pub.publish(image.frame->toImageMsg());
    }catch(cv_bridge::Exception &e){
        ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str()); 
    }   
}


/*
 *  Name: facedetect
 *  function: to detect the face of the image
 *  param:
 *      scale:  图像缩放尺度
 */
int IMAGE::facedetect(double scale)
{
    /*定义存放检测到的人脸序列容器*/
    vector<Rect>faces;
    int i = 0;

    /*定义调色板*/
    const static Scalar colors[] = {CV_RGB(0,0,255),
        CV_RGB(0,128,255),
        CV_RGB(0,255,255),
        CV_RGB(0,255,0),
        CV_RGB(255,128,0),
        CV_RGB(255,255,0),
        CV_RGB(255,0,0),
        CV_RGB(255,0,255)};

    /*进行人脸检测*/
    /*
     *  histImg: 要检测的图像
     *  faces: 存放检测到的图像序列
     *  1.1: 表示图像尺寸减小的比例
     *  2: 表示每个图像至少要被检测到三次才能算是检测成功
     *  CV_HAAR_SCALE_IMAGE: 表示不是缩放分类器来检测的,而是缩放图像
     *  Size(30, 30): 表示检测到图像的最小尺寸
     */
    cascade.detectMultiScale(histImg, faces,
        1.1, 2, 0
        |CV_HAAR_SCALE_IMAGE,
        Size(30, 30));

    /*在原始图像上圈出人脸*/
    for(vector<Rect>::const_iterator r = faces.begin(); r != faces.end(); ++r, ++i)
    {
        Point center;       //点的封装
        Scalar color = colors[i%8]; //调色板
        int radius = 0;

        double aspect_ratio = (double)r->width/r->height;   //图像的横纵比

        if(aspect_ratio >0.75 && aspect_ratio < 1.3)
        {
            center.x = cvRound((r->x + r->width*0.5)*scale);
            center.y = cvRound((r->y + r->height*0.5)*scale);
            radius = cvRound((r->width + r->height)*0.25*scale);
            circle(img, center, radius, color, 3, 8, 0);    //画圆,后三个参数为线条的粗细,类型以及圆心和半径的小数位数
        }else{
            rectangle(img, cvPoint(cvRound(r->x*scale), cvRound(r->y*scale)),
                      cvPoint(cvRound((r->x + r->width-1)*scale), cvRound((r->y + r->height-1)*scale)),
                      color, 3, 8, 0);          //画矩形,由对角的两个顶点来进行确定大小
        }
    }

    return 0;
}
#endif

在人脸检测算法中,由于考虑到需要反复地对一张图像进行操作,并利用到图像的各种形式,故将图像封装起来。关于程序的解释已经在注释中进行了说明。这里面有个NODE对象,其中在image::Subscriber::subscribe的函数中,第三个参数必须使用&来显性传递函数指针,个人猜测可能是带有命名空间的函数名无法被模板所识别,并且传入的函数的返回值也必须为void,否则会报错,这里不是很理解,虽然subscribe的原型中第三个参数为void(T::*)(M)可以看出他要求传入函数指针是指向一个返回值为void的函数,但是当非成员函数传入时并没有这个约束,是可以进行强制转换的。然后当Subscribe作为成员时还必须传入该对象的指针。关于subscribe的函数原型会在文章最后给出。
camera_publish.cpp

/*
 *  Author: OJ
 *  Date: 2016/08/25
 *  Function: camera image publisher
 */
#include <ros/ros.h>
#include <cv_bridge/cv_bridge.h>
#include "../include/camera_publish.h"
#include <opencv2/highgui/highgui.hpp>
#include <sensor_msgs/image_encodings.h>
#include <image_transport/image_transport.h>

using namespace std;
using namespace cv;


int main(int argc, char *argv[])
{
    /*初始化节点,并设定节点名*/
    ros::init(argc, argv, "img_publiser");
    /*设置节点句柄*/
    ros::NodeHandle n;

    /*判断输入参数是否完成*/
    if(argv[1] == NULL)
    {
        ROS_WARN("Please choose the camera you want to use !");
        return 1;
    }

    /*获取打开摄像机的设备号*/
    int video_source = 0;
    int default_p = 0;
    istringstream default_param(argv[1]);
    default_param >> default_p;
    n.param<int>("video_source", video_source, default_p);

    /*定义摄像机对象*/
    Camera_driver camera(n, video_source);

    /*设置主题的发布频率为5Hz*/
    ros::Rate loop_rate(5);
    /*图片节点进行主题的发布*/
    while(ros::ok())
    {
        camera.img_publish();
        ros::spinOnce();
        /*按照设定的频率来将程序挂起*/
        loop_rate.sleep();
    }

    return 0;
}

camera_publish.h

#ifndef CAMERA_PUB_H_INCLUDE
#define CAMERA_PUB_H_INCLUDE

#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 <opencv2/highgui/highgui.hpp>

using namespace std;
using namespace cv; 


/*
 *  class name: Camera_driver
 *  function:   摄像头驱动对象,包含摄像头正常工作和其节点工作的函数
 */
class Camera_driver{
public:
    /*构造函数*/
    Camera_driver(ros::NodeHandle &n, int video_source = 0):
        it(n),
        cap(video_source){
            /*判断摄像头是否正常打开,若正常打开isOpened返回1*/
            if(!cap.isOpened())
            {
                ROS_ERROR("Cannot open the camera!\n");
            }
            /*设置主题名和缓冲区*/   
            pub_img = it.advertise("camera/original_img", 1);

            /*初始化CvImage智能指针,CvImage为Mat与ROS图像之间转换的载体*/
            frame = boost::make_shared<cv_bridge::CvImage>();
            /*设置ROS图片为BGR且每个像素点用1个字节来表示类似与CV_8U*/
            frame->encoding = sensor_msgs::image_encodings::BGR8;
        }

    /*图像发布函数*/
    int img_publish()
    {
        /*将摄像头获取到的图像存放在frame中的image*/
        cap >> frame->image;
        /*判断是否获取到图像,若获取到图像,将其转化为ROS图片*/
        if(!(frame->image.empty()))
        {
            frame->header.stamp = ros::Time::now();
            pub_img.publish(frame->toImageMsg());
        }

        return 0;       
    }

private:    
    /*设置图片节点*/
    image_transport::ImageTransport it;
    /*设置图片的发布者*/
    image_transport::Publisher pub_img;
    /*设置存放摄像头图像的变量*/    
    VideoCapture cap;
    /*设置cvImage的智能指针*/
    cv_bridge::CvImagePtr frame;
};
#endif 

img_out.cpp

/*
 *  Author: OJ
 *  Date: 2016/08/26
 *  Function: deal with the image
 */
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/highgui/highgui.hpp>

using namespace std;
using namespace cv;



int imageCallback(const sensor_msgs::ImageConstPtr &msg)
{
    try{
        imshow("result", cv_bridge::toCvShare(msg, "bgr8")->image);
    }catch(cv_bridge::Exception &e){
        ROS_ERROR("Could not convert from '%s' to 'bgr8'.", msg->encoding.c_str());
    }
    return 0;
}

int main(int argc, char *argv[])
{
    /*初始化节点,并设定节点名*/
    ros::init(argc, argv, "img_out");
    /*设置节点句柄*/  
    ros::NodeHandle n;

    /*创建显示窗口*/
    namedWindow("result");
    /*打开创建的窗口*/
    startWindowThread();

    /*设置图像接受的节点*/
    image_transport::ImageTransport it(n);
    /*设置图像订阅者*/
    image_transport::Subscriber sub = it.subscribe("camera/deal_img", 1, imageCallback);

    /*回调响应循环*/
    ros::spin();

    /*关闭窗口*/
    destroyWindow("result");    

    return 0;
}

subscribe原型

template<class M , class T >
Subscriber ros::NodeHandle::subscribe(
const std::string &topic,
uint32_t queue_size, 
void(T::*)(M) fp,
*obj,
const TransportHints &transport_hints = TransportHints())
發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章