head_detector.cpp
Go to the documentation of this file.
00001 
00061 
00062 
00063 #ifdef __LINUX__
00064 #include "cob_people_detection/head_detector.h"
00065 #include "cob_vision_utils/GlobalDefines.h"
00066 #include "cob_vision_utils/VisionUtils.h"
00067 #else
00068 #endif
00069 
00070 #include <opencv2/opencv.hpp>
00071 
00072 using namespace ipa_PeopleDetector;
00073 
00074 HeadDetector::HeadDetector(void)
00075 {
00076         m_range_cascade = 0;
00077         m_initialized = false;
00078 }
00079 
00080 unsigned long HeadDetector::init(std::string model_directory, double depth_increase_search_scale, int depth_drop_groups, int depth_min_search_scale_x, int depth_min_search_scale_y)
00081 {
00082         // parameters
00083         m_depth_increase_search_scale = depth_increase_search_scale;
00084         m_depth_drop_groups = depth_drop_groups;
00085         m_depth_min_search_scale_x = depth_min_search_scale_x;
00086         m_depth_min_search_scale_y = depth_min_search_scale_y;
00087 
00088         // Load Haar-Classifier for head detection in depth images
00089         std::string rangeCascadePath = model_directory + "haarcascades/haarcascade_range_multiview_5p_bg.xml";
00090         //std::string rangeCascadePath = model_directory + "haarcascades/haarcascade_range_multiview_5p_bg+.xml";       // + "haarcascades/haarcascade_range.xml";
00091         m_range_cascade = (CvHaarClassifierCascade*)cvLoad(rangeCascadePath.c_str(), 0, 0, 0);
00092 
00093         // Create Memory
00094         m_storage = cvCreateMemStorage(0);
00095 
00096         m_initialized = true;
00097 
00098         return ipa_Utils::RET_OK;
00099 }
00100 
00101 HeadDetector::~HeadDetector(void)
00102 {
00103         // Release Classifiers and memory
00104         cvReleaseHaarClassifierCascade(&m_range_cascade);
00105         cvReleaseMemStorage(&m_storage);
00106 }
00107 
00108 unsigned long HeadDetector::interpolateUnassignedPixels(cv::Mat& img)
00109 {
00110         CV_Assert(img.type() == CV_8UC3);
00111 
00112         cv::Mat temp = img.clone();
00113 
00114         uchar* data = img.data;
00115         uchar* data2 = temp.data;
00116         int stride = img.step;
00117         for (int repetitions = 0; repetitions < 10; repetitions++)
00118         {
00119                 // each pixel with a value can propagate its value to black pixels in the 4 pixel neighborhood
00120                 for (int v = 1; v < img.rows - 1; v++)
00121                 {
00122                         for (int u = 1; u < img.cols - 1; u++)
00123                         {
00124                                 // only pixels with a value can propagate their value
00125                                 int index = v * stride + 3 * u;
00126                                 if (data[index] != 0)
00127                                 {
00128                                         uchar val = data[index];
00129                                         if (data2[index - 3] == 0)
00130                                                 for (int i = -3; i < 0; i++)
00131                                                         data2[index + i] = val; // left
00132                                         if (data2[index + 3] == 0)
00133                                                 for (int i = 3; i < 6; i++)
00134                                                         data2[index + i] = val; // right
00135                                         if (data2[index - stride] == 0)
00136                                                 for (int i = -stride; i < -stride + 3; i++)
00137                                                         data2[index + i] = val; // up
00138                                         if (data2[index + stride] == 0)
00139                                                 for (int i = stride; i < stride + 3; i++)
00140                                                         data2[index + i] = val; // down
00141                                 }
00142                         }
00143                 }
00144                 // copy back new data
00145                 for (int i = 0; i < img.rows * stride; i++)
00146                         data[i] = data2[i];
00147         }
00148         return ipa_Utils::RET_OK;
00149 }
00150 
00151 unsigned long HeadDetector::detectRangeFace(cv::Mat& depth_image, std::vector<cv::Rect>& rangeFaceCoordinates, bool fillUnassignedDepthValues)
00152 {
00153         if (m_initialized == false)
00154         {
00155                 std::cout << "Error: HeadDetector::detectRangeFace: init() must be called first." << std::endl;
00156                 return ipa_Utils::RET_FAILED;
00157         }
00158 
00159         rangeFaceCoordinates.clear();
00160 
00161         cv::Mat depth_image_8U3;
00162         ipa_Utils::ConvertToShowImage(depth_image, depth_image_8U3, 3);
00163         if (fillUnassignedDepthValues)
00164                 interpolateUnassignedPixels(depth_image_8U3);
00165 //      cv::namedWindow("depth image filled");
00166 //      cv::imshow("depth image filled", depth_image_8U3);
00167 //      cv::waitKey(10);
00168         IplImage imgPtr = (IplImage)depth_image_8U3;
00169         CvSeq* rangeFaces = cvHaarDetectObjects(&imgPtr, m_range_cascade, m_storage, m_depth_increase_search_scale, m_depth_drop_groups, CV_HAAR_DO_CANNY_PRUNING,
00170                         cvSize(m_depth_min_search_scale_x, m_depth_min_search_scale_y));
00171 
00172         for (int i = 0; i < rangeFaces->total; i++)
00173         {
00174                 cv::Rect *rangeFace = (cv::Rect*)cvGetSeqElem(rangeFaces, i);
00175                 rangeFaceCoordinates.push_back(*rangeFace);
00176         }
00177 
00178         return ipa_Utils::RET_OK;
00179 }


cob_people_detection
Author(s): Richard Bormann , Thomas Zwölfer
autogenerated on Mon May 6 2019 02:32:06