pcDuino+OpenCV实现人脸追踪摄像头(3)

新建一个名为face_tracking_camera的C++项目,编辑face_tracking_camera.pro文件,加入OpenCV和c_enviroment的源文件、头文件和类库路径,我这里OpenCV安装在/usr/local/,c_enviroment安装在/home/Ubuntu/c_enviroment/ SOURCES += \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/main.cpp \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/platform.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/Print.cpp \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/Stream.cpp \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/Tone.cpp \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/WInterrupts.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/wiring.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/wiring_analog.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/wiring_digital.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/wiring_pulse.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/wiring_shift.c \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/WMath.cpp \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/WString.cpp \
        /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino/Serial.cpp \
        /home/ubuntu/c_enviroment/libraries/Wire/Wire.cpp \
        /home/ubuntu/c_enviroment/libraries/SPI/SPI.cpp \
        /home/ubuntu/c_enviroment/libraries/LiquidCrystal/Dyrobot_MCP23008.cpp \
        /home/ubuntu/c_enviroment/libraries/LiquidCrystal/LiquidCrystal.cpp \
        /home/ubuntu/c_enviroment/libraries/PN532_SPI/PN532.cpp \
        httpget.cpp

INCLUDEPATH += /usr/local/include/opencv \
                /usr/local/include/opencv2 \
                /home/ubuntu/c_enviroment/hardware/arduino/cores/arduino \
                /home/ubuntu/c_enviroment/hardware/arduino/variants/sunxi \
                /home/ubuntu/c_enviroment/libraries \
                /home/ubuntu/c_enviroment/libraries/Serial \
                /home/ubuntu/c_enviroment/libraries/SPI \
                /home/ubuntu/c_enviroment/libraries/Wire \
                /home/ubuntu/c_enviroment/libraries/LiquidCrystal \
                /home/ubuntu/c_enviroment/libraries/PN532_SPI

LIBS += /home/ubuntu/c_enviroment/libarduino.a \
        /usr/local/lib/libopencv_calib3d.so \
        /usr/local/lib/libopencv_contrib.so \
        /usr/local/lib/libopencv_core.so \
        /usr/local/lib/libopencv_features2d.so \
        /usr/local/lib/libopencv_flann.so \
        /usr/local/lib/libopencv_gpu.so \
        /usr/local/lib/libopencv_highgui.so \
        /usr/local/lib/libopencv_legacy.so \
        /usr/local/lib/libopencv_ml.so \
        /usr/local/lib/libopencv_objdetect.so \
        /usr/local/lib/libopencv_photo.so \
        /usr/local/lib/libopencv_stitching.so \
        /usr/local/lib/libopencv_superres.so \
        /usr/local/lib/libopencv_nonfree.so \
        /usr/local/lib/libopencv_ts.so \
        /usr/local/lib/libopencv_videostab.so \
        /usr/local/lib/libopencv_video.so \
        /usr/local/lib/libopencv_imgproc.so \
        /usr/local/lib/libopencv_calib3d.so.2.4 \
        /usr/local/lib/libopencv_contrib.so.2.4 \
        /usr/local/lib/libopencv_core.so.2.4 \
        /usr/local/lib/libopencv_features2d.so.2.4 \
        /usr/local/lib/libopencv_flann.so.2.4 \
        /usr/local/lib/libopencv_gpu.so.2.4 \
        /usr/local/lib/libopencv_highgui.so.2.4 \
        /usr/local/lib/libopencv_legacy.so.2.4 \
        /usr/local/lib/libopencv_ml.so.2.4 \
        /usr/local/lib/libopencv_objdetect.so.2.4 \
        /usr/local/lib/libopencv_photo.so.2.4 \
        /usr/local/lib/libopencv_stitching.so.2.4 \
        /usr/local/lib/libopencv_superres.so.2.4 \
        /usr/local/lib/libopencv_nonfree.so.2.4 \
        /usr/local/lib/libopencv_ts.so.2.4 \
        /usr/local/lib/libopencv_videostab.so.2.4 \
        /usr/local/lib/libopencv_video.so.2.4 \
        /usr/local/lib/libopencv_imgproc.so.2.4 \
        /usr/local/lib/libopencv_calib3d.so.2.4.6 \
        /usr/local/lib/libopencv_contrib.so.2.4.6 \
        /usr/local/lib/libopencv_core.so.2.4.6 \
        /usr/local/lib/libopencv_features2d.so.2.4.6 \
        /usr/local/lib/libopencv_flann.so.2.4.6 \
        /usr/local/lib/libopencv_gpu.so.2.4.6 \
        /usr/local/lib/libopencv_highgui.so.2.4.6 \
        /usr/local/lib/libopencv_legacy.so.2.4.6 \
        /usr/local/lib/libopencv_ml.so.2.4.6 \
        /usr/local/lib/libopencv_objdetect.so.2.4.6 \
        /usr/local/lib/libopencv_photo.so.2.4.6 \
        /usr/local/lib/libopencv_stitching.so.2.4.6 \
        /usr/local/lib/libopencv_superres.so.2.4.6 \
        /usr/local/lib/libopencv_nonfree.so.2.4.6 \
        /usr/local/lib/libopencv_ts.so.2.4.6 \
        /usr/local/lib/libopencv_videostab.so.2.4.6 \
        /usr/local/lib/libopencv_video.so.2.4.6 \
        /usr/local/lib/libopencv_imgproc.so.2.4.6 <br><br>到这里,环境就全部搭好了,开始写代码吧:#include <iostream>
#include <opencv2/opencv.hpp>
#include <Arduino.h>
#include <wiring_private.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <assert.h>
#include <math.h>
#include <float.h>
#include <limits.h>
#include <time.h>
#include <ctype.h>
#include <sys/time.h>
#include <signal.h>


//用于人脸识别的分类器特征库文件路径
const char* cascade_name = "/usr/local/share/OpenCV/haarcascades/haarcascade_frontalface_alt.xml";
//定义了X轴(横向摆动),Y轴(纵向摆动)舵机的中心点
static int centerlevelX = 110;
static int centerlevelY = 60;
//定义了舵机的频率
const int frequncy = 260;
//用一个整数存储目前舵机摆动方向
static int turningRight = 1;

//函数的签名列表
void detect_and_draw( IplImage* image );
void start_pulse(int pwm_id,int freq,int value);
void sigroutine(int dunno);
void reset();
long getCurrentTime();
long startTime;
long endTime;
//led指示灯pin脚
int pin_led = 3;

//为OpenCV申请一块用于计算的内存
static CvMemStorage* storage = 0;

//定义一个haar分类器
static CvHaarClassifierCascade* cascade = 0;


void setup(){
 //定义指示灯针脚为输出
    pinMode(pin_led,OUTPUT);
 //复位云台舵机
    reset();
 //监听中断信号
    signal(SIGINT,sigroutine);
    //建立一个名为result的窗口
    cvNamedWindow( "result", 1 );
    //打开摄像头
    CvCapture* capture = cvCaptureFromCAM(-1);
   
    //定义图像类
    IplImage *img;
    IplImage *newImg;
   
    //加载分类器
    cascade = (CvHaarClassifierCascade*)cvLoad( cascade_name, 0, 0, 0 );
   
    //检查分类器加载异常
    if( !cascade ){
        fprintf( stderr, "ERROR: Could not load classifier cascade\n" );
    }
   
    //定位内存块
    storage = cvCreateMemStorage(0);
   
    while(1) {
  //由于pcduino的计算能力有限,为了保证帧率,把从摄像头采集来的画面缩小1/2
        newImg = cvQueryFrame( capture );
        if( !newImg ) break;
        img = cvCreateImage(cvSize(newImg->width/2, newImg->height/2), newImg->depth, newImg->nChannels);
        cvResize(newImg, img);
       
        //翻转图像
        cvFlip(img, img, 1);
  //调用识别和绘制图像的函数
        detect_and_draw(img);
       
        //释放图像使用的内存
        cvReleaseImage(&img);
        //监听esc键
        int c = cvWaitKey(33);
        if( c == 27 ) break;
       
    }
    //释放摄像头
    cvReleaseCapture( &capture );
   
    //销毁窗口
    cvDestroyWindow("result");
}

void detect_and_draw( IplImage* img ){
    startTime = getCurrentTime();

//清空使用过的内存空间
    cvClearMemStorage( storage );
   
    int scale = 1;
    int i;
   
    //定义一个中心点存储识别出来的人脸位置
    CvPoint ptcenter;
   
    //人脸识别
    if( cascade ){
       
        //如果监测到多张脸,逐一绘制
        CvSeq* faces = cvHaarDetectObjects( img, cascade, storage,
                                          1.1, 2, CV_HAAR_DO_CANNY_PRUNING,
                                          cvSize(80, 80));
       
        //如果监测到多张脸,遍历取出
        for( i = 0; i < (faces ? faces->total : 0); i++ ){
            //创建人脸矩形
            CvRect* r = (CvRect*)cvGetSeqElem( faces, i );
         
            //换算出人脸矩形的中心点
            ptcenter.x = (r->x+(r->width/2))*scale;
            ptcenter.y = (r->y+(r->height/2))*scale;
           
            //绘制一个圆形标识出人脸的位置
            cvCircle(img, ptcenter, (r->width+r->height)/4, CV_RGB(255,0,0), 3, 8, 0 );
        }
    }
    //显示图像
    cvShowImage( "result", img );
 //计算帧率
    endTime = getCurrentTime();
    long time = endTime-startTime;
    int framerate = 1000/time;
 //检查中心点是否为空
    if(ptcenter.x && ptcenter.y){
        //std::cout<<"center_point:("<<ptcenter.x<<","<<ptcenter.y<<")\tframe_rate:"<<framerate<<"\n"<<std::endl;
        //std::cout<<"x:"<<(ptcenter.x-img->width/2)<<"\ty:"<<(ptcenter.y-img->height/2)<<std::endl;
  //向led指示灯引脚输出低电平,熄灭指示灯
  digitalWrite(pin_led,LOW);
  //驱动摄像头移动到人脸中心位置
  centerlevelX += (ptcenter.x-img->width/2)/110*2;
  if(centerlevelX <= 170 && centerlevelX >= 50)start_pulse(6,frequncy,centerlevelX);

centerlevelY -= (ptcenter.y-img->height/2)/70;
  if(centerlevelY <= 90 && centerlevelY >= 45)start_pulse(5,frequncy,centerlevelY);
  //显示修正的X和Y轴幅度和帧率
  std::cout<<"X:"<<centerlevelX<<"\tY:"<<centerlevelY<<"\tFrameRate:"<<framerate<<std::endl;

}else{
        printf("no face is detected in the image\n");
  //指示灯亮起
  digitalWrite(pin_led,HIGH);
  //如果没有检测到人脸则左右摇摆摄像头
  if(centerlevelX <= 170 && turningRight == 1){
   start_pulse(6,frequncy,centerlevelX+=2);
   if(centerlevelX > 170)turningRight = 0;
   //std::cout<<centerlevelX<<std::endl;
  }
  if(centerlevelX >= 50 && turningRight == 0){
   start_pulse(6,frequncy,centerlevelX-=2);
   if(centerlevelX < 50)turningRight =1; 
   //std::cout<<centerlevelX<<std::endl;
  }
    }
 //防止摄像头下移过度
 if(centerlevelY < 45) centerlevelY = 45;
}
//复位函数,调整舵机X、Y轴到中心位置
void reset(){
    delay(50);
    start_pulse(5,frequncy,60);
    start_pulse(6,frequncy,110);
    delay(50);
}

long getCurrentTime(){
    struct timeval tv;
    gettimeofday(&tv,NULL);
    long time =  tv.tv_sec * 1000 + tv.tv_usec / 1000;
    return time;
}
//舵机驱动函数
void start_pulse(int pwm_id,int freq,int value){
    int step = 0;
    step = pwmfreq_set(pwm_id, freq);
    //printf("PWM%d set freq %d and valid duty cycle range [0, %d]\n", pwm_id, freq, step);
    if (step > 0){
      //printf("PWM%d test with duty cycle %d\n", pwm_id, value);
      analogWrite(pwm_id, value);
      delay(50);
    }
}
//signal监听函数,监听中断信号,做一些状态复位工作
void sigroutine(int dunno) {
    switch (dunno) {
    case 2:
    printf("Get a signal -- SIGINT \n");
    reset();
    analogWrite(6,0);
    analogWrite(5,0);
    digitalWrite(pin_led,LOW);
    exit(0);
    break;
    }
}

void loop(){}

内容版权声明:除非注明,否则皆为本站原创文章。

转载注明出处:http://www.heiqu.com/c0ec589152892cc31872e34af89fafc6.html