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())
發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章