SendAutoselectMessage.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 
00003 #include <opencv/cv.h>
00004 #include <opencv/highgui.h>
00005 #include <sensor_msgs/Image.h>
00006 #include <cv_bridge/CvBridge.h>
00007 #include <image_transport/image_transport.h>
00008 
00009 //service definitions
00010 #include <face_contour_detector/GetFilters.h>
00011 #include <face_contour_detector/ApplyFilters.h>
00012 #include <face_contour_detector/ContourDetectorGUI.h>
00013 #include <face_contour_detector/autoselect_result.h>
00014 
00015 //filters
00016 #include <face_contour_detector/filters/List.h>
00017 #include <face_contour_detector/filters/Canny.h>
00018 #include <face_contour_detector/filters/ColorGraphs.h>
00019 #include <face_contour_detector/filters/DeleteShortLines.h>
00020 #include <face_contour_detector/filters/EdgeConnectorGraphBased.h>
00021 #include <face_contour_detector/filters/GaussianBlur.h>
00022 #include <face_contour_detector/filters/RosServices.h>
00023 
00024 //std
00025 #include <vector>
00026 
00027 
00029 int main(int argc, char* argv[]) {
00030     
00031         ros::init(argc, argv, "send_autoselect_message");
00032         ros::NodeHandle n;
00033     
00034     int pos = 0;
00035     if ((2) & (1<<(pos))) {
00036         ROS_INFO("Bit 1");
00037     } else {
00038         ROS_INFO("Bit 0");
00039     }
00040     
00041     if (argc < 2) {
00042         ROS_ERROR("there must be an image to transfer");
00043     
00044     }
00045     
00046     std::string topic = "display_on_gui";
00047     if (argc >= 3) {
00048         topic = argv[2];
00049     }
00050     //ros::Publisher chatter_pub = n.advertise<face_contour_detector::autoselect_result>("autoselect_results", 10000);
00051     
00052     //ros::Rate loop_rate(10);
00053     
00054     //while (ros::ok()) {
00055     
00056     face_contour_detector::autoselect_result result;
00057         
00058     //load image
00059     cv::Mat img = cv::imread(argv[1]);
00060     
00061     try {
00062         sensor_msgs::CvBridge cvBridge;
00063         IplImage ipl = img;
00064         result.image = *(cvBridge.cvToImgMsg(&ipl));
00065     } catch (sensor_msgs::CvBridgeException error) {
00066         ROS_ERROR("could not convert the image with the cvBridge to a sensor_msgs/Image");
00067         return 1;
00068     }
00069     
00070     std::stringstream s; 
00071     s<<"Image width="<<img.cols<<" height="<<img.rows;
00072     ROS_INFO(s.str().c_str());
00073         
00074     //generate areas
00075     face_contour_detector::name_value_pair param;
00076     face_contour_detector::filter_area_setup areaSetup;
00077         
00078     //alles
00079     {
00080         face_contour_detector::filter_area_setup areaSetup;
00081         
00082         areaSetup.area.name = "Complete Face";
00083         areaSetup.area.x = 0;
00084         areaSetup.area.y = 0;
00085         areaSetup.area.width = img.cols;
00086         areaSetup.area.height = img.rows;
00087         
00088         //blur
00089         {
00090             face_contour_detector::filter_setup filterSetup;
00091             filterSetup.name = "GaussianBlur";
00092             {
00093                 face_contour_detector::name_value_pair param;
00094                 param.name = "blurwidth";
00095                 param.type = "int";
00096                 param.value = "21";
00097                 filterSetup.parameters.push_back(param);
00098             }
00099             {
00100                 face_contour_detector::name_value_pair param;
00101                 param.name = "blurheight";
00102                 param.type = "int";
00103                 param.value = "21";
00104                 filterSetup.parameters.push_back(param);
00105             }
00106             areaSetup.filters.push_back(filterSetup);
00107         }
00108         //canny
00109         {
00110             face_contour_detector::filter_setup filterSetup;
00111             filterSetup.name = "Canny";
00112             {
00113                 face_contour_detector::name_value_pair param;
00114                 param.name = "threshold1";
00115                 param.type = "float";
00116                 param.value = "2000";
00117                 filterSetup.parameters.push_back(param);
00118             }
00119             {
00120                 face_contour_detector::name_value_pair param;
00121                 param.name = "threshold2";
00122                 param.type = "float";
00123                 param.value = "10000";
00124                 filterSetup.parameters.push_back(param);
00125             }
00126             {
00127                 face_contour_detector::name_value_pair param;
00128                 param.name = "l2gradientent";
00129                 param.type = "bool";
00130                 param.value = "true";
00131                 filterSetup.parameters.push_back(param);
00132             }
00133             areaSetup.filters.push_back(filterSetup);
00134         }
00135             
00136         //edge connector
00137         {
00138             face_contour_detector::filter_setup filterSetup;
00139             filterSetup.name = "EdgeConnector";
00140             {
00141                 face_contour_detector::name_value_pair param;
00142                 param.name = "searchRadius";
00143                 param.type = "int";
00144                 param.value = "2";
00145                 filterSetup.parameters.push_back(param);
00146             }
00147             areaSetup.filters.push_back(filterSetup);
00148         }
00149         //delete short lines
00150         {
00151             face_contour_detector::filter_setup filterSetup;
00152             filterSetup.name = "DeleteShortLines";
00153             {
00154                 face_contour_detector::name_value_pair param;
00155                 param.name = "minNumPixels";
00156                 param.type = "int";
00157                 param.value = "1";
00158                 filterSetup.parameters.push_back(param);
00159             }
00160             areaSetup.filters.push_back(filterSetup);
00161         }
00162         
00163         result.areas.push_back(areaSetup);
00164     }
00165     
00166     //foo
00167     {
00168             face_contour_detector::filter_area_setup areaSetup;
00169 
00170             areaSetup.area.name = "LeftEye";
00171             areaSetup.area.x = 114;
00172             areaSetup.area.y = 168;
00173             areaSetup.area.width = 62;
00174             areaSetup.area.height = 60;
00175 
00176             //blur
00177             {
00178                 face_contour_detector::filter_setup filterSetup;
00179                 filterSetup.name = "GaussianBlur";
00180                 {
00181                     face_contour_detector::name_value_pair param;
00182                     param.name = "blurwidth";
00183                     param.type = "int";
00184                     param.value = "11";
00185                     filterSetup.parameters.push_back(param);
00186                 }
00187                 {
00188                     face_contour_detector::name_value_pair param;
00189                     param.name = "blurheight";
00190                     param.type = "int";
00191                     param.value = "11";
00192                     filterSetup.parameters.push_back(param);
00193                 }
00194                 areaSetup.filters.push_back(filterSetup);
00195             }
00196             //canny
00197             {
00198                 face_contour_detector::filter_setup filterSetup;
00199                 filterSetup.name = "Canny";
00200                 {
00201                     face_contour_detector::name_value_pair param;
00202                     param.name = "threshold1";
00203                     param.type = "float";
00204                     param.value = "500";
00205                     filterSetup.parameters.push_back(param);
00206                 }
00207                 {
00208                     face_contour_detector::name_value_pair param;
00209                     param.name = "threshold2";
00210                     param.type = "float";
00211                     param.value = "1000";
00212                     filterSetup.parameters.push_back(param);
00213                 }
00214                 {
00215                     face_contour_detector::name_value_pair param;
00216                     param.name = "l2gradientent";
00217                     param.type = "bool";
00218                     param.value = "true";
00219                     filterSetup.parameters.push_back(param);
00220                 }
00221                 areaSetup.filters.push_back(filterSetup);
00222             }
00223 
00224             //edge connector
00225             {
00226                 face_contour_detector::filter_setup filterSetup;
00227                 filterSetup.name = "EdgeConnector";
00228                 {
00229                     face_contour_detector::name_value_pair param;
00230                     param.name = "searchRadius";
00231                     param.type = "int";
00232                     param.value = "2";
00233                     filterSetup.parameters.push_back(param);
00234                 }
00235                 areaSetup.filters.push_back(filterSetup);
00236             }
00237             //delete short lines
00238             {
00239                 face_contour_detector::filter_setup filterSetup;
00240                 filterSetup.name = "DeleteShortLines";
00241                 {
00242                     face_contour_detector::name_value_pair param;
00243                     param.name = "minNumPixels";
00244                     param.type = "int";
00245                     param.value = "1";
00246                     filterSetup.parameters.push_back(param);
00247                 }
00248                 areaSetup.filters.push_back(filterSetup);
00249             }
00250 
00251             result.areas.push_back(areaSetup);
00252         }
00253 
00254     //foo2
00255     {
00256             face_contour_detector::filter_area_setup areaSetup;
00257 
00258             areaSetup.area.name = "RightEye";
00259             areaSetup.area.x = 240;
00260             areaSetup.area.y = 168;
00261             areaSetup.area.width = 62;
00262             areaSetup.area.height = 60;
00263 
00264             //blur
00265             {
00266                 face_contour_detector::filter_setup filterSetup;
00267                 filterSetup.name = "GaussianBlur";
00268                 {
00269                     face_contour_detector::name_value_pair param;
00270                     param.name = "blurwidth";
00271                     param.type = "int";
00272                     param.value = "11";
00273                     filterSetup.parameters.push_back(param);
00274                 }
00275                 {
00276                     face_contour_detector::name_value_pair param;
00277                     param.name = "blurheight";
00278                     param.type = "int";
00279                     param.value = "11";
00280                     filterSetup.parameters.push_back(param);
00281                 }
00282                 areaSetup.filters.push_back(filterSetup);
00283             }
00284             //canny
00285             {
00286                 face_contour_detector::filter_setup filterSetup;
00287                 filterSetup.name = "Canny";
00288                 {
00289                     face_contour_detector::name_value_pair param;
00290                     param.name = "threshold1";
00291                     param.type = "float";
00292                     param.value = "500";
00293                     filterSetup.parameters.push_back(param);
00294                 }
00295                 {
00296                     face_contour_detector::name_value_pair param;
00297                     param.name = "threshold2";
00298                     param.type = "float";
00299                     param.value = "1000";
00300                     filterSetup.parameters.push_back(param);
00301                 }
00302                 {
00303                     face_contour_detector::name_value_pair param;
00304                     param.name = "l2gradientent";
00305                     param.type = "bool";
00306                     param.value = "true";
00307                     filterSetup.parameters.push_back(param);
00308                 }
00309                 areaSetup.filters.push_back(filterSetup);
00310             }
00311 
00312             //edge connector
00313             /*{
00314                 face_contour_detector::filter_setup filterSetup;
00315                 filterSetup.name = "EdgeConnector";
00316                 {
00317                     face_contour_detector::name_value_pair param;
00318                     param.name = "searchRadius";
00319                     param.type = "int";
00320                     param.value = "2";
00321                     filterSetup.parameters.push_back(param);
00322                 }
00323                 areaSetup.filters.push_back(filterSetup);
00324             }
00325             //delete short lines
00326             {
00327                 face_contour_detector::filter_setup filterSetup;
00328                 filterSetup.name = "DeleteShortLines";
00329                 {
00330                     face_contour_detector::name_value_pair param;
00331                     param.name = "minNumPixels";
00332                     param.type = "int";
00333                     param.value = "1";
00334                     filterSetup.parameters.push_back(param);
00335                 }
00336                 areaSetup.filters.push_back(filterSetup);
00337             }*/
00338 
00339             result.areas.push_back(areaSetup);
00340         }
00341 
00342     //foo3
00343     {
00344                 face_contour_detector::filter_area_setup areaSetup;
00345 
00346                 areaSetup.area.name = "Nose";
00347                 areaSetup.area.x = 177;
00348                 areaSetup.area.y = 178;
00349                 areaSetup.area.width = 62;
00350                 areaSetup.area.height = 72;
00351 
00352                 //blur
00353                 {
00354                         face_contour_detector::filter_setup filterSetup;
00355                         filterSetup.name = "GaussianBlur";
00356                         {
00357                                 face_contour_detector::name_value_pair param;
00358                                 param.name = "blurwidth";
00359                                 param.type = "int";
00360                                 param.value = "11";
00361                                 filterSetup.parameters.push_back(param);
00362                         }
00363                         {
00364                                 face_contour_detector::name_value_pair param;
00365                                 param.name = "blurheight";
00366                                 param.type = "int";
00367                                 param.value = "11";
00368                                 filterSetup.parameters.push_back(param);
00369                         }
00370                         areaSetup.filters.push_back(filterSetup);
00371                 }
00372                 //cannyr
00373                 {
00374                         face_contour_detector::filter_setup filterSetup;
00375                         filterSetup.name = "Canny";
00376                         {
00377                                 face_contour_detector::name_value_pair param;
00378                                 param.name = "threshold1";
00379                                 param.type = "float";
00380                                 param.value = "500";
00381                                 filterSetup.parameters.push_back(param);
00382                         }
00383                         {
00384                                 face_contour_detector::name_value_pair param;
00385                                 param.name = "threshold2";
00386                                 param.type = "float";
00387                                 param.value = "1000";
00388                                 filterSetup.parameters.push_back(param);
00389                         }
00390                         {
00391                                 face_contour_detector::name_value_pair param;
00392                                 param.name = "l2gradientent";
00393                                 param.type = "bool";
00394                                 param.value = "true";
00395                                 filterSetup.parameters.push_back(param);
00396                         }
00397                         areaSetup.filters.push_back(filterSetup);
00398                 }
00399 
00400                 //edge connector
00401                 {
00402                         face_contour_detector::filter_setup filterSetup;
00403                         filterSetup.name = "EdgeConnector";
00404                         {
00405                                 face_contour_detector::name_value_pair param;
00406                                 param.name = "searchRadius";
00407                                 param.type = "int";
00408                                 param.value = "2";
00409                                 filterSetup.parameters.push_back(param);
00410                         }
00411                         areaSetup.filters.push_back(filterSetup);
00412                 }
00413                 //delete short lines
00414                 {
00415                         face_contour_detector::filter_setup filterSetup;
00416                         filterSetup.name = "DeleteShortLines";
00417                         {
00418                                 face_contour_detector::name_value_pair param;
00419                                 param.name = "minNumPixels";
00420                                 param.type = "int";
00421                                 param.value = "1";
00422                                 filterSetup.parameters.push_back(param);
00423                         }
00424                         areaSetup.filters.push_back(filterSetup);
00425                 }
00426 
00427                 result.areas.push_back(areaSetup);
00428         }
00429 
00430     //foo4
00431         {
00432                 face_contour_detector::filter_area_setup areaSetup;
00433 
00434                 areaSetup.area.name = "Mouth";
00435                 areaSetup.area.x = 161;
00436                 areaSetup.area.y = 259;
00437                 areaSetup.area.width = 93;
00438                 areaSetup.area.height = 41;
00439 
00440                 //blur
00441                 {
00442                         face_contour_detector::filter_setup filterSetup;
00443                         filterSetup.name = "GaussianBlur";
00444                         {
00445                                 face_contour_detector::name_value_pair param;
00446                                 param.name = "blurwidth";
00447                                 param.type = "int";
00448                                 param.value = "11";
00449                                 filterSetup.parameters.push_back(param);
00450                         }
00451                         {
00452                                 face_contour_detector::name_value_pair param;
00453                                 param.name = "blurheight";
00454                                 param.type = "int";
00455                                 param.value = "11";
00456                                 filterSetup.parameters.push_back(param);
00457                         }
00458                         areaSetup.filters.push_back(filterSetup);
00459                 }
00460                 //canny
00461                 {
00462                         face_contour_detector::filter_setup filterSetup;
00463                         filterSetup.name = "Canny";
00464                         {
00465                                 face_contour_detector::name_value_pair param;
00466                                 param.name = "threshold1";
00467                                 param.type = "float";
00468                                 param.value = "500";
00469                                 filterSetup.parameters.push_back(param);
00470                         }
00471                         {
00472                                 face_contour_detector::name_value_pair param;
00473                                 param.name = "threshold2";
00474                                 param.type = "float";
00475                                 param.value = "1000";
00476                                 filterSetup.parameters.push_back(param);
00477                         }
00478                         {
00479                                 face_contour_detector::name_value_pair param;
00480                                 param.name = "l2gradientent";
00481                                 param.type = "bool";
00482                                 param.value = "true";
00483                                 filterSetup.parameters.push_back(param);
00484                         }
00485                         areaSetup.filters.push_back(filterSetup);
00486                 }
00487 
00488                 //edge connector
00489                 /*{
00490                         face_contour_detector::filter_setup filterSetup;
00491                         filterSetup.name = "EdgeConnector";
00492                         {
00493                                 face_contour_detector::name_value_pair param;
00494                                 param.name = "searchRadius";
00495                                 param.type = "int";
00496                                 param.value = "2";
00497                                 filterSetup.parameters.push_back(param);
00498                         }
00499                         areaSetup.filters.push_back(filterSetup);
00500                 }
00501                 //delete short lines
00502                 {
00503                         face_contour_detector::filter_setup filterSetup;
00504                         filterSetup.name = "DeleteShortLines";
00505                         {
00506                                 face_contour_detector::name_value_pair param;
00507                                 param.name = "minNumPixels";
00508                                 param.type = "int";
00509                                 param.value = "1";
00510                                 filterSetup.parameters.push_back(param);
00511                         }
00512                         areaSetup.filters.push_back(filterSetup);
00513                 }*/
00514 
00515                 result.areas.push_back(areaSetup);
00516         }
00517 
00518     ros::ServiceClient client = n.serviceClient<face_contour_detector::ContourDetectorGUI>(topic);
00519     face_contour_detector::ContourDetectorGUI srv;
00520     srv.request.proposals.push_back(result);
00521     srv.request.proposals.push_back(result);
00522     srv.request.proposals.push_back(result);
00523     srv.request.proposals.push_back(result);
00524     ROS_INFO("Service request send");
00525     if (client.call(srv)) {
00526         ROS_INFO("got response!");
00527     } else  {
00528         
00529         ROS_ERROR("Failed to call service %s", topic.c_str());
00530         return 1;
00531     }
00532     
00533         //loop_rate.sleep();
00534         
00535     //}
00536         
00537         return 0;
00538     
00539 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


face_contour_detector
Author(s): Fabian Wenzelmann and Julian Schmid
autogenerated on Wed Dec 26 2012 16:18:17