ar_recog.cpp
Go to the documentation of this file.
00001 
00002 #include <ros/ros.h>
00003 #include <image_transport/image_transport.h>
00004 #include <opencv/cv.h>
00005 #include <opencv/highgui.h>
00006 #include <cv_bridge/CvBridge.h>
00007 
00008 #include <ar_recog/Tag.h>
00009 #include <ar_recog/Tags.h>
00010 #include <ar_recog/CalibrateDistance.h>
00011 
00012 #include <math.h>
00013 
00014 #include <AR/ar.h>
00015 #include <AR/video.h>
00016 #include <AR/matrix.h>
00017 
00018 
00019 extern "C" { 
00020 #include "object.h" 
00021 }
00022 
00023 #include <iostream>
00024 
00025 #define THRESH 100
00026 #define THRESH_VARIATION 5
00027 #define THRESH_RANGE_LIMIT 40
00028 using namespace cv;
00029 
00030 char cparam_name[65536];
00031 ARParam cparam;
00032 
00033 char model_name[65536];
00034 ObjectData_T *object;
00035 int objectnum;
00036 double patt_trans[3][4];
00037 
00038 bool using_rectified_images;
00039 
00040 
00041 int thresh = THRESH;        // used by adaptative threshold variation
00042 int threshVariation = THRESH_VARIATION;
00043 int kThresh = 1;
00044 int sign = 1;
00045 
00046 void init(int width, int height) {
00047   ARParam wparam;
00048   if (arParamLoad(cparam_name, 1, &wparam) < 0) {
00049     std::cerr << "Problem loading AR camera parameters." << std::endl;
00050     exit(-1);
00051   }
00052         
00053   /*for (int i = 0; i < 4; i++) {
00054     std::cout << wparam.dist_factor[i] << "\t";
00055   }
00056   std::cout << std::endl;
00057   */
00058   
00059   arParamChangeSize(&wparam, width, height, &cparam);
00060   arInitCparam(&cparam);
00061 
00062   if ((object = read_ObjData(model_name, &objectnum)) == NULL) {
00063     std::cerr << "Problem reading patterns." << std::endl;
00064     exit(-1);
00065   }
00066 }
00067 
00068 
00069 IplImage * drawHistogram(IplImage *img)
00070 {
00071   int numBins = 256;
00072   float range[] = {0, 255};
00073   float *ranges[] = { range };
00074   float scaleX = 2, scaleY = 2;
00075   const int width = 3;
00076 
00077   CvHistogram *hist = cvCreateHist(1, &numBins, CV_HIST_ARRAY, ranges, 1);
00078   cvClearHist(hist);
00079 
00080   IplImage *im_gray = cvCreateImage(cvGetSize(img), IPL_DEPTH_8U, 1);
00081   cvCvtColor(img, im_gray, CV_RGB2GRAY);
00082 
00083   cvCalcHist(&im_gray, hist, 0, 0);
00084   IplImage *imgHistGray = cvCreateImage(cvSize(256*scaleX, 64*scaleY), 8, 3);
00085   cvZero(imgHistGray);
00086 
00087   float histMax = 0;
00088   cvGetMinMaxHistValue(hist, 0, &histMax, 0, 0);
00089 
00090    for(int i=0;i<255;i++)
00091    {
00092         float histValue = cvQueryHistValue_1D(hist, i);
00093         float nextValue = cvQueryHistValue_1D(hist, i+1);
00094  
00095         CvPoint pt1 = cvPoint(i*scaleX, 64*scaleY);
00096         CvPoint pt2 = cvPoint(i*scaleX+scaleX, 64*scaleY);
00097         CvPoint pt3 = cvPoint(i*scaleX+scaleX, (64-nextValue*64/histMax)*scaleY);
00098         CvPoint pt4 = cvPoint(i*scaleX, (64-histValue*64/histMax)*scaleY);
00099  
00100         int numPts = 5;
00101         CvPoint pts[] = {pt1, pt2, pt3, pt4, pt1};
00102  
00103         cvFillConvexPoly(imgHistGray, pts, numPts, CV_RGB(255,255,255));
00104    }
00105   
00106   cvLine(imgHistGray,cvPoint(thresh*scaleX, 0), 
00107            cvPoint(thresh*scaleX, 64*scaleY),
00108            CV_RGB(255,0,0),width);
00109     
00110 
00111   cvReleaseImage(&im_gray);
00112   cvReleaseHist(&hist);
00113 
00114   return imgHistGray;
00115 }
00116 
00117 /* Adaptive local thresholding for binarization
00118  * Mat& img: input image
00119  * Mat& dst: thresholded image
00120  * double k: weight for the local deviation in the 
00121              threshold computation
00122  * int window: size of the window for mean computation
00123  */
00124 void localThreshold(Mat& img, Mat& dst, double k, int window)
00125 {
00126     Mat mean(img.size(), CV_32F);
00127     Mat deviation(img.size(), CV_32F);
00128     Mat aux(img.size(), CV_32F);
00129     Mat thresh(img.size(), CV_8U);
00130     boxFilter(img, mean, CV_32F, Size(window, window));
00131     subtract(img, mean, deviation, noArray(), CV_32F);
00132     subtract(Scalar(1), deviation, aux, noArray(), CV_32F);
00133     divide(deviation, aux, aux, 1, CV_32F);
00134     subtract(aux, Scalar(1), aux, noArray(), CV_32F);
00135     multiply(Scalar(k), aux, aux, 1, CV_32F);
00136     add(Scalar(1), aux, aux, noArray(), CV_32F);
00137     multiply(mean, aux, thresh, 1, CV_8U);
00138     dst = img > thresh;
00139 }
00140 
00141 //int count;
00142 double haov, vaov;
00143 bool ar_smooth = true;
00144 ros::Publisher tags_pub;
00145 image_transport::Publisher ar_img; //used by the handling functions
00146 image_transport::Publisher ar_hist;
00147 int last_reported_distance; // Saved by the publisher for use by the calibration service
00148 
00149 void handleImage(const sensor_msgs::ImageConstPtr& in, const sensor_msgs::CameraInfoConstPtr& camera_info) {
00150   sensor_msgs::CvBridge bridge;
00151   double icpara[3][4], trans[3][4];
00152   IplImage* img = bridge.imgMsgToCv(in, "rgb8");
00153 
00154   if (img->width != arImXsize || img->height != arImYsize) init(img->width, img->height);
00155   IplImage *hist = drawHistogram(img);
00156 
00157   // Apply an ADAPTIVE THRESHOLD BINARIZATION
00158   IplImage *im_gray = cvCreateImage(cvGetSize(img),IPL_DEPTH_8U,1);
00159   Mat gray(im_gray);
00160   Mat thresholded(gray.size(), CV_8U);
00161 
00162   localThreshold(gray, thresholded, 0.06, 11);
00163   
00164   /*
00165   ARUint8 *data = (ARUint8*) malloc(sizeof(ARUint8)*img->width*img->height*3);
00166   int i = 0;
00167   for (int y = 0; y < img->height; y++) {
00168     for (int x = 0; x < img->width; x++) {
00169       for (int j = 0; j < 3; j++) {
00170         data[i++] = img->imageData[y*(img->widthStep/sizeof(uchar))+x*3+j];
00171       }
00172     }
00173   }*/
00174 
00175   // copy thresholded image into data
00176   ARUint8 *data = (ARUint8*) malloc(sizeof(ARUint8)*img->width*img->height*3);
00177   int i = 0;
00178   for (int y = 0; y < img->height; y++) {
00179     for (int x = 0; x < img->width; x++) {
00180       for (int j = 0; j < 3; j++) {
00181         data[i++] = thresholded.at<uchar>(y,x);
00182       }
00183     }
00184   }
00185 
00186   // draw histogram over image
00187   cvSetImageROI(img, cvRect(img->width - hist->width, img->height - hist->height,
00188                             img->width, img->height));
00189   cvCopy(hist, img);
00190   cvResetImageROI(img);
00191 
00192 
00193   ARMarkerInfo *marker_info;
00194   int marker_num;
00195   if(arDetectMarker(data, thresh, &marker_info, &marker_num) < 0) {
00196     std::cerr << "Problem running detect marker." << std::endl;
00197     exit(-1);
00198   }
00199 
00200   if( arParamDecompMat(cparam.mat, icpara, trans) < 0 ) {
00201         printf("gConvGLcpara: Parameter error!!\n");
00202         exit(0);
00203     }
00204 
00205 
00206     for( int i = 0; i < 3; i++ ) {
00207         for( int j = 0; j < 3; j++ ) {
00208             icpara[i][j] = icpara[i][j] / icpara[2][2];
00209             printf("%.3f ", icpara[i][j]);
00210         }
00211         printf("\n");
00212     }
00213 
00214   /*
00215   for(int i = 0; i < marker_num; i++) {
00216     const int width = 3;
00217     cvLine(img,cvPoint(marker_info[i].vertex[0][0],marker_info[i].vertex[0][1]),
00218            cvPoint(marker_info[i].vertex[1][0],marker_info[i].vertex[1][1])
00219            ,CV_RGB(0,255,0),width);
00220     cvLine(img,cvPoint(marker_info[i].vertex[1][0],marker_info[i].vertex[1][1]),
00221            cvPoint(marker_info[i].vertex[2][0],marker_info[i].vertex[2][1])
00222            ,CV_RGB(0,255,0),width);
00223     cvLine(img,cvPoint(marker_info[i].vertex[2][0],marker_info[i].vertex[2][1]),
00224            cvPoint(marker_info[i].vertex[3][0],marker_info[i].vertex[3][1])
00225            ,CV_RGB(0,255,0),width);
00226     cvLine(img,cvPoint(marker_info[i].vertex[3][0],marker_info[i].vertex[3][1]),
00227            cvPoint(marker_info[i].vertex[0][0],marker_info[i].vertex[0][1])
00228            ,CV_RGB(0,255,0),width);
00229   }*/
00230 
00231   if (using_rectified_images) {
00232     // Potential non-portability issue here... P uses ROS float64, but
00233     // I'm just using doubles for now.
00234 
00235     // These numbers are not always accurate after a calibration.  It
00236     // may be that our checkerboard calibrators are insufficient to
00237     // nail down the parameters of cheap webcams, or that the
00238     // calibration routines within opencv are not the greatest.
00239     // Uncalibrated raw image data seems to work pretty well, though,
00240     // once you've measured a known distance.
00241 
00242     double y_foc = camera_info->P[5];
00243     double y_princ = camera_info->P[6];
00244     double x_foc = camera_info->P[0];
00245     double x_princ = camera_info->P[2];
00246 
00247     // Camera angle of view
00248     haov = 2.0 * atan(x_princ / x_foc);
00249     vaov = 2.0 * atan(y_princ / y_foc);
00250 
00251     ROS_INFO("entrando por using_rectified_images");
00252   }
00253   else {
00254     vaov = haov * ((double)img->height / (double)img->width);
00255     ROS_INFO("no entrando por using_rectified_images");
00256   } 
00257 
00258   ar_recog::Tags tags;  
00259   tags.image_width = img->width;
00260   tags.image_height = img->height;
00261   tags.angle_of_view = haov;
00262 
00263   // Record the time stamp close to the observation, not the reporting.
00264   tags.header.stamp = ros::Time::now();
00265 
00266   for( int i = 0; i < objectnum; i++ ) {
00267     int k = -1;
00268     for( int j = 0; j < marker_num; j++ ) {
00269 
00270       if( object[i].id == marker_info[j].id) {
00271               /*********************
00272               if( k == -1 ) 
00273                 k = j;
00274               else // make sure you have the best pattern (highest confidence factor) 
00275                 ROS_INFO("objnum=%d, objid=%d, markid=%d", objectnum, object[i].id, marker_info[j].id);
00276 
00277                 if( marker_info[k].cf < marker_info[j].cf ) k = j;
00278               ********************************/
00279                 k=j;
00280       //----------------------------------------------------------------------}
00281     //-----------------------------------------------------------------------}
00282 
00283     if( k == -1 ) {
00284       object[i].visible = 0;
00285       continue;
00286     }
00287                 
00288     /* calculate the transform for each marker */
00289     if( (!ar_smooth) || (object[i].visible == 0) ) {
00290       arGetTransMat(&marker_info[k], 
00291                     object[i].marker_center, 
00292                     object[i].marker_width, 
00293                     object[i].trans);
00294     } else {
00295       arGetTransMatCont(&marker_info[k], 
00296                         object[i].trans, 
00297                         object[i].marker_center, 
00298                         object[i].marker_width, 
00299                         object[i].trans);
00300     }
00301 
00302     object[i].visible = 1;
00303     /*for (int k = 0; k < 3; k++)
00304       for (int l= 0; l < 4; l++)
00305         patt_trans[k][l] = object[i].trans[k][l];
00306     */
00307     const int width = 3;
00308     cvLine(img,cvPoint(marker_info[k].vertex[0][0],marker_info[k].vertex[0][1]),
00309            cvPoint(marker_info[k].vertex[1][0],marker_info[k].vertex[1][1])
00310            ,CV_RGB(0,255,0),width);
00311     cvLine(img,cvPoint(marker_info[k].vertex[1][0],marker_info[k].vertex[1][1]),
00312            cvPoint(marker_info[k].vertex[2][0],marker_info[k].vertex[2][1])
00313            ,CV_RGB(0,255,0),width);
00314     cvLine(img,cvPoint(marker_info[k].vertex[2][0],marker_info[k].vertex[2][1]),
00315            cvPoint(marker_info[k].vertex[3][0],marker_info[k].vertex[3][1])
00316            ,CV_RGB(0,255,0),width);
00317     cvLine(img,cvPoint(marker_info[k].vertex[3][0],marker_info[k].vertex[3][1]),
00318            cvPoint(marker_info[k].vertex[0][0],marker_info[k].vertex[0][1])
00319            ,CV_RGB(0,255,0),width);
00320     
00321         ARMat cameraMatrix, cubeMatrix, proyMatrix, kMatrix, pMatrix;
00322     double cube[4][4] = { {0, 10, 0, 0}, {0, 0, 10, 0}, {0, 0, 0, 10}, {1, 1, 1, 1}};
00323     double proy[3][4];
00324     double cam[3][4];
00325     double km[3][3];
00326 
00327     pMatrix.m = &cam[0][0];
00328     pMatrix.row = 3;
00329     pMatrix.clm = 4;
00330 
00331     cameraMatrix.m = &object[i].trans[0][0];
00332     cameraMatrix.row = 3;
00333     cameraMatrix.clm = 4;
00334 
00335     kMatrix.m = &km[0][0];
00336     kMatrix.row = 3;
00337     kMatrix.clm = 3;
00338 
00339     cubeMatrix.m = &cube[0][0];
00340     cubeMatrix.row = 4;
00341     cubeMatrix.clm = 4;
00342 
00343     proyMatrix.m = &proy[0][0];
00344     proyMatrix.row = 3;
00345     proyMatrix.clm = 4;
00346     
00347     for (int k = 0 ; k < 3; k++) {
00348       for (int l = 0; l < 3; l++)
00349         kMatrix.m[k*3+l] = icpara[k][l];
00350     }    
00351     arMatrixMul(&pMatrix, &kMatrix, &cameraMatrix);
00352     arMatrixMul(&proyMatrix, &pMatrix, &cubeMatrix);
00353 
00354     /*cvLine(img, cvPoint(proyMatrix.m[4]/proyMatrix.m[8]+img->width/2, proyMatrix.m[4]/proyMatrix.m[8]+img->height/2),
00355            cvPoint(proyMatrix.m[1]/proyMatrix.m[9]+img->width/2, proyMatrix.m[5]/proyMatrix.m[9]+img->height/2),
00356            CV_RGB(255,0,0), width);*/
00357 
00358     cvLine(img, cvPoint(proyMatrix.m[0]/proyMatrix.m[8], proyMatrix.m[4]/proyMatrix.m[8]),
00359            cvPoint(proyMatrix.m[1]/proyMatrix.m[9], proyMatrix.m[5]/proyMatrix.m[9]),
00360            CV_RGB(0,0,255), width);
00361 
00362     cvLine(img, cvPoint(proyMatrix.m[0]/proyMatrix.m[8], proyMatrix.m[4]/proyMatrix.m[8]),
00363            cvPoint(proyMatrix.m[2]/proyMatrix.m[10], proyMatrix.m[6]/proyMatrix.m[10]),
00364            CV_RGB(255,0,0), width);
00365 
00366     cvLine(img, cvPoint(proyMatrix.m[0]/proyMatrix.m[8], proyMatrix.m[4]/proyMatrix.m[8]),
00367            cvPoint(proyMatrix.m[3]/proyMatrix.m[11], proyMatrix.m[7]/proyMatrix.m[11]),
00368            CV_RGB(127,0,127), width);
00369 
00370     CvFont font;
00371     cvInitFont(&font, CV_FONT_HERSHEY_SIMPLEX, 0.5, 0.5, 0, 2, CV_AA);
00372     char posZ[16];
00373     sprintf(posZ, "%.1f", object[i].trans[2][3]/20);
00374     cvPutText(img, posZ, cvPoint(marker_info[k].pos[0], marker_info[k].pos[1]+32),
00375                    &font, cvScalar(255,145,0, 0));
00376 
00377 
00378 
00379     printf("origen x = %.2f\n", marker_info[k].vertex[0][0]);
00380     printf("origen y = %.2f\n", marker_info[k].vertex[0][1]);
00381 
00382     for (int k = 0; k < 3; k++) {
00383       for (int l = 0; l < 4; l++) {
00384          printf("%.2f ", pMatrix.m[k*4+l]);
00385       }
00386       printf("\n");
00387     }
00388 
00389 
00390     printf("---------------\n");
00391 
00392     for (int k = 0; k < 3; k++) {
00393       for (int l = 0; l < 3; l++) {
00394          printf("%.2f ", kMatrix.m[k*3+l]);
00395       }
00396       printf("\n");
00397     }
00398 
00399 
00400     printf("---------------\n");
00401 
00402     for (int k = 0; k < 3; k++) {
00403       for (int l = 0; l < 4; l++) {
00404          printf("%.2f ", icpara[k][l]);
00405       }
00406       printf("\n");
00407     }
00408 
00409 
00410     printf("---------------\n");
00411     for (int k = 0; k < 2; k++) {
00412       for (int l = 0; l < 4; l++) {
00413          //printf("%.2f ", proyMatrix.m[k*4+l]);
00414          printf("%.2f ", proyMatrix.m[k*4+l]/proyMatrix.m[2*4+l]);
00415       }
00416       printf("\n");
00417     }
00418        
00419 
00420     int x, y;
00421     double diameter;
00422     double xRot, yRot, zRot;
00423     double xMetric, yMetric, zMetric;
00424 
00425     x = marker_info[k].pos[0];
00426     y = marker_info[k].pos[1];
00427     //diameter = (int) ((double) .5 + (double) sqrt(marker_info[k].area));
00428 
00429     // Transformation below pinched and modified from 
00430     // http://paulbourke.net/geometry/eulerangle/Aij-to-Eulerangles.pdf
00431     xRot = -asin(-object[i].trans[1][2]);
00432     yRot = -atan2(object[i].trans[0][2],-object[i].trans[2][2]);
00433     zRot = atan2(object[i].trans[1][0],-object[i].trans[1][1]);
00434 
00435     // This relative x and y stuff corrects for the distortion that
00436     // comes from an AR tag moving out of the fovea.  When the tag is
00437     // at the edge of the image, it appears rotated, even when it is
00438     // parallel to the image plane.  This is not the behavior we want,
00439     // and leads to inaccurate distance measurement, for one thing.
00440     double x_delta = (double)(2*x-img->width)/(double)img->width;
00441     double y_delta = (double)(2*y-img->height)/(double)img->height;
00442     double rel_theta = x_delta * haov / 2.0;
00443     double rel_phi = y_delta * vaov / 2.0;
00444 
00445     // xRot is rotation around the horizontal axis, which means
00446     // changes in apparent _vertical_ size, and vice versa with yRot.
00447     // Which is why these look backwards.
00448 
00449     // Whoa.  AR Toolkit appears to have fixed this behavior.  So this
00450     // fix was making things worse.
00451 
00452     // xRot -= y_delta * rel_phi;
00453     // yRot -= x_delta * rel_theta;
00454 
00455     // Figure out the tag's area from the quadrilateral's corners
00456     double x1 = marker_info[k].vertex[0][0] - marker_info[k].vertex[2][0];
00457     double y1 = marker_info[k].vertex[0][1] - marker_info[k].vertex[2][1];
00458     double x2 = marker_info[k].vertex[1][0] - marker_info[k].vertex[3][0];
00459     double y2 = marker_info[k].vertex[1][1] - marker_info[k].vertex[3][1];
00460     double area = 0.5 * fabs(x1*y2 - x2*y1);
00461     double unrotated_area = area / (cos(xRot)*cos(yRot));
00462     diameter = sqrt(unrotated_area);
00463 
00464     double theta_object = haov * (diameter / (double)img->width);
00465     //double phi_object = vaov * (diameter / (double)img->height);
00466     // Whichever measurement is closer to the center of the image is likelier to be more accurate.
00467     //int dist = object[i].marker_width / tan(x_delta < y_delta ? theta_object : phi_object);
00468     // However, it also makes the measurement less stable.
00469     int dist = object[i].marker_width / tan(theta_object);
00470 
00471     xMetric = dist * cos(rel_theta) / 1000.0;
00472     yMetric = -dist * sin(rel_theta) * cos(rel_phi) / 1000.0;
00473     zMetric = -dist * cos(rel_theta) * sin(rel_phi) / 1000.0;
00474     
00475     ar_recog::Tag tag;
00476     tag.id = i;
00477     tag.cf = marker_info[k].cf; 
00478     tag.x = x;
00479     tag.y = y;
00480     tag.diameter = diameter;
00481     tag.distance = dist/1000.0; // Convert to meters
00482     tag.xRot = xRot;
00483     tag.yRot = yRot;
00484     tag.zRot = zRot;
00485     tag.xMetric = xMetric;
00486     tag.yMetric = yMetric;
00487     tag.zMetric = zMetric;
00488     int b = marker_info[k].dir;
00489     int idx[4];
00490     //rotate based on direction
00491     switch (b) {
00492     case 0:
00493       idx[0] = 0;
00494       idx[1] = 1;
00495       idx[2] = 2;
00496       idx[3] = 3;
00497       break;
00498     case 3:
00499       idx[0] = 1;
00500       idx[1] = 2;
00501       idx[2] = 3;
00502       idx[3] = 0;
00503       break;
00504     case 2:
00505       idx[0] = 2;
00506       idx[1] = 3;
00507       idx[2] = 0;
00508       idx[3] = 1;
00509       break;
00510     default: //1
00511       idx[0] = 3;
00512       idx[1] = 0;
00513       idx[2] = 1;
00514       idx[3] = 2;
00515       break;
00516     }
00517 
00518     tag.cwCorners[0] = marker_info[k].vertex[idx[0]][0];
00519     tag.cwCorners[1] = marker_info[k].vertex[idx[0]][1]; //upper left
00520     tag.cwCorners[2] = marker_info[k].vertex[idx[1]][0];
00521     tag.cwCorners[3] = marker_info[k].vertex[idx[1]][1]; //upper right
00522     tag.cwCorners[4] = marker_info[k].vertex[idx[2]][0];
00523     tag.cwCorners[5] = marker_info[k].vertex[idx[2]][1]; //lower right
00524     tag.cwCorners[6] = marker_info[k].vertex[idx[3]][0];
00525     tag.cwCorners[7] = marker_info[k].vertex[idx[3]][1]; //lower left
00526 
00527     // TESTING ONLY
00528     // tag.c3[0] = object[i].trans[0][3];
00529     // tag.c3[1] = object[i].trans[1][3];
00530     // tag.c3[2] = object[i].trans[2][3];
00531 
00532     // tag.t0[0] = object[i].trans[0][0];
00533     // tag.t0[1] = object[i].trans[0][1];
00534     // tag.t0[2] = object[i].trans[0][2];
00535 
00536     // tag.t1[0] = object[i].trans[1][0];
00537     // tag.t1[1] = object[i].trans[1][1];
00538     // tag.t1[2] = object[i].trans[1][2];
00539 
00540     // tag.t2[0] = object[i].trans[2][0];
00541     // tag.t2[1] = object[i].trans[2][1];
00542     // tag.t2[2] = object[i].trans[2][2];
00543     // END TESTING ONLY
00544 
00545     tags.tags.push_back(tag);
00546 
00547     last_reported_distance = dist;
00548     
00549     // adaptative threshold variation
00550       }
00551     }
00552   }
00553  
00554   ROS_INFO("markernum=%d", marker_num); 
00555   if (marker_num == 0) {
00556       thresh += sign * kThresh * threshVariation;
00557       kThresh = kThresh + 1;
00558       sign = -sign;
00559       
00560       if (abs(thresh - THRESH) > THRESH_RANGE_LIMIT) {
00561         thresh = THRESH;
00562         kThresh = 1;
00563         sign = 1;
00564       }
00565   }
00566     
00567     ROS_INFO("THRESH=%d\n", thresh);
00568 
00569   tags.tag_count = tags.tags.size();
00570 
00571   sensor_msgs::ImagePtr out = sensor_msgs::CvBridge::cvToImgMsg(img, "bgr8");
00572   sensor_msgs::ImagePtr outhist = sensor_msgs::CvBridge::cvToImgMsg(hist, "passthrough");
00573   ar_img.publish(out);
00574   ar_hist.publish(outhist);
00575 
00576   tags_pub.publish(tags);
00577 
00578   free(data);
00579 }
00580 
00581 void handleRawImage(const sensor_msgs::ImageConstPtr& in) {
00582         if (using_rectified_images) return;
00583         const sensor_msgs::CameraInfoConstPtr ign;
00584         handleImage(in,ign);
00585 }
00586 
00587 bool calibrateDistance(ar_recog::CalibrateDistance::Request &req,
00588                        ar_recog::CalibrateDistance::Response &resp) {
00589 
00590   using_rectified_images = false;
00591   haov = haov*((double)last_reported_distance / (double)req.dist);
00592   resp.aov = haov;
00593   return true;
00594 }
00595 
00596 int main(int argc, char **argv) {
00597   ros::init(argc, argv, "image_listener");
00598   ros::NodeHandle nh;
00599 
00600   std::string tmp;
00601   nh.param<std::string>("camera_para", tmp, "camera_para.dat");
00602   strcpy(cparam_name, tmp.c_str());
00603   nh.param<std::string>("model_name", tmp, "object_data");
00604   strcpy(model_name, tmp.c_str());
00605 
00606   if (nh.getParam("aov", haov)) {
00607     using_rectified_images = false;
00608     //nh.param<double>("aov", theta, 0.67018834495304758);
00609     std::cout << "aov-: " << haov << std::endl;
00610   }
00611   else {
00612     using_rectified_images = true;
00613   }
00614 
00615   if (nh.getParam("ar_smooth", ar_smooth)) {
00616       std::cout << "ar_smooth: " << ar_smooth << std::endl;
00617     } else {
00618       std::cout << "ar_smooth parameter missing, will implement smoothing" << std::endl;
00619     }
00620 
00621   tags_pub = nh.advertise<ar_recog::Tags>("tags",1);
00622 
00623   ros::ServiceServer calibrate_distance = nh.advertiseService("ar/calibrate_distance", calibrateDistance);
00624 
00625   image_transport::ImageTransport it(nh);
00626   ar_img = it.advertise("ar/image", 1);
00627   ar_hist = it.advertise("ar/hist", 1);
00628 
00629   arImXsize = arImYsize = 0;
00630   //count = 0;
00631 
00632   image_transport::CameraSubscriber sub = it.subscribeCamera("image", 1, handleImage);
00633   image_transport::Subscriber subRaw = it.subscribe("image", 1, handleRawImage);
00634   ros::spin();
00635 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


ar_recog
Author(s): Graylin Trevor Jay and Christopher Crick
autogenerated on Fri Jan 25 2013 12:14:59