human_assisted_object_detection_alg.cpp
Go to the documentation of this file.
00001 #include "human_assisted_object_detection_alg.h"
00002 
00003 HumanAssistedObjectDetectionAlgorithm::HumanAssistedObjectDetectionAlgorithm(void)
00004 {
00005   this->ptrPrms = &this->prms;
00006   this->ptrRFs = &this->RFs;
00007   this->ptrClfr = &this->clfr;
00008 
00009   ptrRFs->fun_set_values(ptrPrms->fun_get_num_ferns(), ptrPrms->fun_get_num_features(), ptrPrms->fun_get_fern_size());
00010   ptrRFs->fun_random_ferns();
00011 }
00012 
00013 HumanAssistedObjectDetectionAlgorithm::~HumanAssistedObjectDetectionAlgorithm(void)
00014 {
00015 //  cvReleaseImage(&this->img);
00016 }
00017 
00018 void HumanAssistedObjectDetectionAlgorithm::config_update(Config& new_cfg, uint32_t level)
00019 {
00020   this->lock();
00021 
00022   // save the current configuration
00023   this->config_=new_cfg;
00024   
00025   this->unlock();
00026 }
00027 
00028 // HumanAssistedObjectDetectionAlgorithm Public API
00029 bool HumanAssistedObjectDetectionAlgorithm::init_detector(sensor_msgs::ImageConstPtr &image,face_detector_mono::Rect &coord)
00030 {
00031   try
00032   {
00033     this->lock();
00034     // transform ROS image into OpenCV image
00035     this->cv_image = cv_bridge::toCvCopy(image,sensor_msgs::image_encodings::BGR8);
00036     this->img=this->cv_image->image;
00037     this->show_img=this->cv_image->image;
00038 
00039     // transform rectangle information from ROS to library
00040     CvRect box = cvRect(coord.x-coord.width/2,coord.y-coord.height/2 ,coord.width ,coord.height);
00041     // call the iri library initialization function
00042     fun_train_classifier(this->ptrPrms, this->ptrClfr, this->ptrRFs, &this->img, box);
00043     // save all initialization data into the class attributes
00044     this->unlock();
00045     return true;
00046   }
00047   catch (cv_bridge::Exception& e)
00048   {
00049     this->unlock();
00050     ROS_ERROR("cv_bridge exception: %s", e.what());
00051     return false;
00052   }
00053 }
00054 
00055 bool HumanAssistedObjectDetectionAlgorithm::detect(sensor_msgs::ImageConstPtr &image)
00056 {
00057   try
00058   {
00059     this->lock();
00060     // transform ROS image into OpenCV image
00061     this->cv_image = cv_bridge::toCvCopy(image, sensor_msgs::image_encodings::BGR8);
00062     this->img=this->cv_image->image;
00063     this->show_img=this->cv_image->image;
00064 
00065     // call the iri library detection function
00066     /* (2) detection stage */
00067     this->detections = fun_detection(this->ptrPrms, this->ptrClfr, this->ptrRFs, &this->img);
00068 
00069     /* (3) check assistance */
00070     this->assistance = fun_check_assistance(this->ptrPrms, this->detections);
00071 
00072     // call the iri library learning function
00073     if(this->assistance)
00074     {
00075       /* (4) show detections */
00076       fun_show_detections(this->ptrPrms, this->ptrClfr, &this->show_img, this->detections, this->assistance);
00077       this->unlock();
00078       return assistance;
00079     }
00080     else
00081     {
00082       /* (5) learning stage */
00083       fun_learning(this->ptrPrms, this->ptrRFs, this->ptrClfr, &this->img, this->detections, this->assistance, true);
00084 
00085       /* (4) show detections */
00086       fun_show_detections(this->ptrPrms, this->ptrClfr, &this->show_img, this->detections, this->assistance);
00087 
00088       this->unlock();
00089       return this->assistance;
00090     }
00091   }
00092   catch (cv_bridge::Exception& e)
00093   {
00094     this->unlock();
00095     ROS_ERROR("cv_bridge exception: %s", e.what());
00096     return true;
00097   }
00098 }
00099 
00100 bool HumanAssistedObjectDetectionAlgorithm::learn_detector(bool valid)
00101 {
00102   try
00103   {
00104     this->lock();
00105     // call the iri library learning function
00106     /* (5) learning stage */
00107     fun_learning(this->ptrPrms, this->ptrRFs, this->ptrClfr, &this->img, this->detections, this->assistance, valid);
00108 
00109     /* (4) show detections */
00110     fun_show_detections(this->ptrPrms, this->ptrClfr, &this->show_img, this->detections, this->assistance);
00111     // save all initialization data into the class attributes
00112     this->unlock();
00113     return true;
00114   }
00115   catch (cv_bridge::Exception& e)
00116   {
00117     this->unlock();
00118     ROS_ERROR("cv_bridge exception: %s", e.what());
00119     return false;
00120   }
00121 }
00122 
00123 bool HumanAssistedObjectDetectionAlgorithm::get_output_rect(cv::Rect & rect)
00124 {
00125   int xa, ya, xb, yb;
00126   float value;
00127   get_max_detection_values(this->detections, xa, ya, xb, yb, value);
00128   if(value>=0.58) //TODO: compare to detection threshold value, instead of hardcoded
00129   {
00130     rect.width  = abs(xa-xb);
00131     rect.height = abs(ya-yb);
00132     rect.x      = xa+ rect.width/2; //mid point
00133     rect.y      = ya+ rect.height/2;
00134   }
00135   else
00136   {
00137     rect.width=-1;
00138     rect.height=-1;
00139     rect.x=-1;
00140     rect.y=-1;
00141   }
00142   return true;
00143 }
00144 
00145 
00146 void HumanAssistedObjectDetectionAlgorithm::get_output_image(sensor_msgs::ImagePtr &image)
00147 {
00148   cv_bridge::CvImage roscv_outImage;
00149 
00150   roscv_outImage.header = this->cv_image->header;
00151   roscv_outImage.encoding = this->cv_image->encoding;
00152   roscv_outImage.image = cv::cvarrToMat(&this->show_img);
00153   image=roscv_outImage.toImageMsg();  
00154 }
00155 


iri_human_assisted_object_detection
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 20:01:33