detector.c
Go to the documentation of this file.
00001 #include "network.h"
00002 #include "region_layer.h"
00003 #include "cost_layer.h"
00004 #include "utils.h"
00005 #include "parser.h"
00006 #include "box.h"
00007 #include "demo.h"
00008 #include "option_list.h"
00009 #include "detector.h"
00010 
00011 #ifdef OPENCV
00012 #include "opencv2/highgui/highgui_c.h"
00013 #endif
00014 static int coco_ids[] = {1,2,3,4,5,6,7,8,9,10,11,13,14,15,16,17,18,19,20,21,22,23,24,25,27,28,31,32,33,34,35,36,37,38,39,40,41,42,43,44,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,67,70,72,73,74,75,76,77,78,79,80,81,82,84,85,86,87,88,89,90};
00015 
00016 #ifdef OPENCV
00017 
00018 // ----------------------------------------------------------------------------
00019 // These functions are exported to the C++ system
00020 bool darknet_detect(network *net, IplImage *ipl, float thresh,
00021   char **class_names, darknet_object **detected_objects, int
00022   *num_detected_objects)
00023 {
00024   float nms = 0.4;
00025 
00026   // Setup the image?
00027   image im = ipl_to_image(ipl);
00028   image sized = resize_image(im, net->w, net->h);
00029   layer l = (*net).layers[net->n-1];
00030   int dimensions = l.w*l.h*l.n;
00031 
00032   // Prepare the data bins
00033   box *boxes = calloc(dimensions, sizeof(box));
00034   float **probs = calloc(dimensions, sizeof(float *));
00035   int j;
00036   for (j = 0; j < dimensions; j++)
00037   {
00038     probs[j] = calloc(l.classes, sizeof(float *));
00039   }
00040 
00041   // Perform the actual prediction
00042   float *X = sized.data;
00043 #ifdef DEBUG
00044   srand(2222222);
00045   clock_t time = clock();
00046 #endif
00047   network_predict(*net, X);
00048 #ifdef DEBUG
00049   fprintf(stdout, "Predicted in %f seconds.\n", sec(clock()-time));
00050 #endif
00051   get_region_boxes(l, 1, 1, thresh, probs, boxes, 0);
00052   if (nms)
00053   {
00054     do_nms_sort(boxes, probs, dimensions, l.classes, nms);
00055   }
00056 
00057   // Parse the boxes into darknet_objects that can be returned
00058   int num_objects = 0;
00059   *detected_objects = NULL;
00060   int i;
00061   for (i = 0; i < dimensions; i++)
00062   {
00063     int class = max_index(probs[i], l.classes);
00064     float prob = probs[i][class];
00065     if (prob > thresh)
00066     {
00067       *detected_objects = realloc(*detected_objects, ++num_objects * (sizeof
00068         **detected_objects));
00069       if (!(*detected_objects))               // Weird realloc fail
00070       {
00071         fprintf(stderr, "Realloc of objects FAILED!!\n");
00072         free(*detected_objects); *detected_objects = NULL;
00073         free_image(im);
00074         free_image(sized);
00075         free(boxes);
00076         free_ptrs((void **)probs, dimensions);
00077         return false;
00078       }
00079 
00080       box b = boxes[i];
00081       (*detected_objects)[num_objects-1].label = class_names[class];
00082       (*detected_objects)[num_objects-1].probability = prob;
00083       (*detected_objects)[num_objects-1].centroid_x = b.x*im.w;
00084       (*detected_objects)[num_objects-1].centroid_y = b.y*im.h;
00085       (*detected_objects)[num_objects-1].left_bot_x = (b.x-b.w/2.)*im.w;
00086       (*detected_objects)[num_objects-1].left_bot_y = (b.y+b.h/2.)*im.h;
00087       (*detected_objects)[num_objects-1].right_top_x = (b.x+b.w/2.)*im.w;
00088       (*detected_objects)[num_objects-1].right_top_y = (b.y-b.h/2.)*im.h;
00089 
00090 #ifdef DEBUG
00091       fprintf(
00092         stdout,
00093         "Detected object: %s, %f, (%hu,%hu), (%hu,%hu,%hu,%hu)\n",
00094         (*detected_objects)[num_objects-1].label
00095         (*detected_objects)[num_objects-1].probability
00096         (*detected_objects)[num_objects-1].centroid_x
00097         (*detected_objects)[num_objects-1].centroid_y
00098         (*detected_objects)[num_objects-1].left_bot_x
00099         (*detected_objects)[num_objects-1].left_bot_y
00100         (*detected_objects)[num_objects-1].right_top_x
00101         (*detected_objects)[num_objects-1].right_top_y
00102       );
00103 #endif
00104     }
00105   }
00106 
00107   *num_detected_objects = num_objects;
00108 
00109   // Free resources and exit
00110   free_image(im);
00111   free_image(sized);
00112   free(boxes);
00113   free_ptrs((void **)probs, dimensions);
00114 
00115   return true;
00116 }
00117 
00118 network create_network(char *cfg_filename, char *weight_filename)
00119 {
00120   network net = parse_network_cfg(cfg_filename);
00121   if (weight_filename)
00122   {
00123     load_weights(&net, weight_filename);
00124   }
00125   set_batch_network(&net, 1);
00126   return net;
00127 }
00128 
00129 char **get_class_names(char *classnames_filename)
00130 {
00131   char **names = get_labels(classnames_filename);
00132   return names;
00133 }
00134 // ----------------------------------------------------------------------------
00135 #endif
00136 
00137 void train_detector(char *datacfg, char *cfgfile, char *weightfile, int *gpus, int ngpus, int clear)
00138 {
00139     list *options = read_data_cfg(datacfg);
00140     char *train_images = option_find_str(options, "train", "data/train.list");
00141     char *backup_directory = option_find_str(options, "backup", "/backup/");
00142 
00143     srand(time(0));
00144     char *base = basecfg(cfgfile);
00145     printf("%s\n", base);
00146     float avg_loss = -1;
00147     network *nets = calloc(ngpus, sizeof(network));
00148 
00149     srand(time(0));
00150     int seed = rand();
00151     int i;
00152     for(i = 0; i < ngpus; ++i){
00153         srand(seed);
00154 #ifdef GPU
00155         cuda_set_device(gpus[i]);
00156 #endif
00157         nets[i] = parse_network_cfg(cfgfile);
00158         if(weightfile){
00159             load_weights(&nets[i], weightfile);
00160         }
00161         if(clear) *nets[i].seen = 0;
00162         nets[i].learning_rate *= ngpus;
00163     }
00164     srand(time(0));
00165     network net = nets[0];
00166 
00167     int imgs = net.batch * net.subdivisions * ngpus;
00168     printf("Learning Rate: %g, Momentum: %g, Decay: %g\n", net.learning_rate, net.momentum, net.decay);
00169     data train, buffer;
00170 
00171     layer l = net.layers[net.n - 1];
00172 
00173     int classes = l.classes;
00174     float jitter = l.jitter;
00175 
00176     list *plist = get_paths(train_images);
00177     //int N = plist->size;
00178     char **paths = (char **)list_to_array(plist);
00179 
00180     load_args args = {0};
00181     args.w = net.w;
00182     args.h = net.h;
00183     args.paths = paths;
00184     args.n = imgs;
00185     args.m = plist->size;
00186     args.classes = classes;
00187     args.jitter = jitter;
00188     args.num_boxes = l.max_boxes;
00189     args.d = &buffer;
00190     args.type = DETECTION_DATA;
00191     args.threads = 4;
00192 
00193     args.angle = net.angle;
00194     args.exposure = net.exposure;
00195     args.saturation = net.saturation;
00196     args.hue = net.hue;
00197 
00198     pthread_t load_thread = load_data(args);
00199     clock_t time;
00200     int count = 0;
00201     //while(i*imgs < N*120){
00202     while(get_current_batch(net) < net.max_batches){
00203         if(l.random && count++%10 == 0){
00204             printf("Resizing\n");
00205             int dim = (rand() % 10 + 10) * 32;
00206             //int dim = (rand() % 4 + 16) * 32;
00207             printf("%d\n", dim);
00208             args.w = dim;
00209             args.h = dim;
00210 
00211             pthread_join(load_thread, 0);
00212             train = buffer;
00213             free_data(train);
00214             load_thread = load_data(args);
00215 
00216             for(i = 0; i < ngpus; ++i){
00217                 resize_network(nets + i, dim, dim);
00218             }
00219             net = nets[0];
00220         }
00221         time=clock();
00222         pthread_join(load_thread, 0);
00223         train = buffer;
00224         load_thread = load_data(args);
00225 
00226         /*
00227            int k;
00228            for(k = 0; k < l.max_boxes; ++k){
00229            box b = float_to_box(train.y.vals[10] + 1 + k*5);
00230            if(!b.x) break;
00231            printf("loaded: %f %f %f %f\n", b.x, b.y, b.w, b.h);
00232            }
00233            image im = float_to_image(448, 448, 3, train.X.vals[10]);
00234            int k;
00235            for(k = 0; k < l.max_boxes; ++k){
00236            box b = float_to_box(train.y.vals[10] + 1 + k*5);
00237            printf("%d %d %d %d\n", truth.x, truth.y, truth.w, truth.h);
00238            draw_bbox(im, b, 8, 1,0,0);
00239            }
00240            save_image(im, "truth11");
00241          */
00242 
00243         printf("Loaded: %lf seconds\n", sec(clock()-time));
00244 
00245         time=clock();
00246         float loss = 0;
00247 #ifdef GPU
00248         if(ngpus == 1){
00249             loss = train_network(net, train);
00250         } else {
00251             loss = train_networks(nets, ngpus, train, 4);
00252         }
00253 #else
00254         loss = train_network(net, train);
00255 #endif
00256         if (avg_loss < 0) avg_loss = loss;
00257         avg_loss = avg_loss*.9 + loss*.1;
00258 
00259         i = get_current_batch(net);
00260         printf("%d: %f, %f avg, %f rate, %lf seconds, %d images\n", get_current_batch(net), loss, avg_loss, get_current_rate(net), sec(clock()-time), i*imgs);
00261         if(i%1000==0 || (i < 1000 && i%100 == 0)){
00262 #ifdef GPU
00263             if(ngpus != 1) sync_nets(nets, ngpus, 0);
00264 #endif
00265             char buff[256];
00266             sprintf(buff, "%s/%s_%d.weights", backup_directory, base, i);
00267             save_weights(net, buff);
00268         }
00269         free_data(train);
00270     }
00271 #ifdef GPU
00272     if(ngpus != 1) sync_nets(nets, ngpus, 0);
00273 #endif
00274     char buff[256];
00275     sprintf(buff, "%s/%s_final.weights", backup_directory, base);
00276     save_weights(net, buff);
00277 }
00278 
00279 
00280 static int get_coco_image_id(char *filename)
00281 {
00282     char *p = strrchr(filename, '_');
00283     return atoi(p+1);
00284 }
00285 
00286 static void print_cocos(FILE *fp, char *image_path, box *boxes, float **probs, int num_boxes, int classes, int w, int h)
00287 {
00288     int i, j;
00289     int image_id = get_coco_image_id(image_path);
00290     for(i = 0; i < num_boxes; ++i){
00291         float xmin = boxes[i].x - boxes[i].w/2.;
00292         float xmax = boxes[i].x + boxes[i].w/2.;
00293         float ymin = boxes[i].y - boxes[i].h/2.;
00294         float ymax = boxes[i].y + boxes[i].h/2.;
00295 
00296         if (xmin < 0) xmin = 0;
00297         if (ymin < 0) ymin = 0;
00298         if (xmax > w) xmax = w;
00299         if (ymax > h) ymax = h;
00300 
00301         float bx = xmin;
00302         float by = ymin;
00303         float bw = xmax - xmin;
00304         float bh = ymax - ymin;
00305 
00306         for(j = 0; j < classes; ++j){
00307             if (probs[i][j]) fprintf(fp, "{\"image_id\":%d, \"category_id\":%d, \"bbox\":[%f, %f, %f, %f], \"score\":%f},\n", image_id, coco_ids[j], bx, by, bw, bh, probs[i][j]);
00308         }
00309     }
00310 }
00311 
00312 void print_detector_detections(FILE **fps, char *id, box *boxes, float **probs, int total, int classes, int w, int h)
00313 {
00314     int i, j;
00315     for(i = 0; i < total; ++i){
00316         float xmin = boxes[i].x - boxes[i].w/2.;
00317         float xmax = boxes[i].x + boxes[i].w/2.;
00318         float ymin = boxes[i].y - boxes[i].h/2.;
00319         float ymax = boxes[i].y + boxes[i].h/2.;
00320 
00321         if (xmin < 0) xmin = 0;
00322         if (ymin < 0) ymin = 0;
00323         if (xmax > w) xmax = w;
00324         if (ymax > h) ymax = h;
00325 
00326         for(j = 0; j < classes; ++j){
00327             if (probs[i][j]) fprintf(fps[j], "%s %f %f %f %f %f\n", id, probs[i][j],
00328                     xmin, ymin, xmax, ymax);
00329         }
00330     }
00331 }
00332 
00333 void print_imagenet_detections(FILE *fp, int id, box *boxes, float **probs, int total, int classes, int w, int h, int *map)
00334 {
00335     int i, j;
00336     for(i = 0; i < total; ++i){
00337         float xmin = boxes[i].x - boxes[i].w/2.;
00338         float xmax = boxes[i].x + boxes[i].w/2.;
00339         float ymin = boxes[i].y - boxes[i].h/2.;
00340         float ymax = boxes[i].y + boxes[i].h/2.;
00341 
00342         if (xmin < 0) xmin = 0;
00343         if (ymin < 0) ymin = 0;
00344         if (xmax > w) xmax = w;
00345         if (ymax > h) ymax = h;
00346 
00347         for(j = 0; j < classes; ++j){
00348             int class = j;
00349             if (map) class = map[j];
00350             if (probs[i][class]) fprintf(fp, "%d %d %f %f %f %f %f\n", id, j+1, probs[i][class],
00351                     xmin, ymin, xmax, ymax);
00352         }
00353     }
00354 }
00355 
00356 void validate_detector(char *datacfg, char *cfgfile, char *weightfile)
00357 {
00358     list *options = read_data_cfg(datacfg);
00359     char *valid_images = option_find_str(options, "valid", "data/train.list");
00360     char *name_list = option_find_str(options, "names", "data/names.list");
00361     char *prefix = option_find_str(options, "results", "results");
00362     char **names = get_labels(name_list);
00363     char *mapf = option_find_str(options, "map", 0);
00364     int *map = 0;
00365     if (mapf) map = read_map(mapf);
00366 
00367 
00368     char buff[1024];
00369     char *type = option_find_str(options, "eval", "voc");
00370     FILE *fp = 0;
00371     int coco = 0;
00372     int imagenet = 0;
00373     if(0==strcmp(type, "coco")){
00374         snprintf(buff, 1024, "%s/coco_results.json", prefix);
00375         fp = fopen(buff, "w");
00376         fprintf(fp, "[\n");
00377         coco = 1;
00378     } else if(0==strcmp(type, "imagenet")){
00379         snprintf(buff, 1024, "%s/imagenet-detection.txt", prefix);
00380         fp = fopen(buff, "w");
00381         imagenet = 1;
00382     }
00383 
00384     network net = parse_network_cfg(cfgfile);
00385     if(weightfile){
00386         load_weights(&net, weightfile);
00387     }
00388     set_batch_network(&net, 1);
00389     fprintf(stderr, "Learning Rate: %g, Momentum: %g, Decay: %g\n", net.learning_rate, net.momentum, net.decay);
00390     srand(time(0));
00391 
00392     char *base = "comp4_det_test_";
00393     list *plist = get_paths(valid_images);
00394     char **paths = (char **)list_to_array(plist);
00395 
00396     layer l = net.layers[net.n-1];
00397     int classes = l.classes;
00398 
00399     int j;
00400     FILE **fps = calloc(classes, sizeof(FILE *));
00401     for(j = 0; j < classes; ++j){
00402         snprintf(buff, 1024, "%s/%s%s.txt", prefix, base, names[j]);
00403         fps[j] = fopen(buff, "w");
00404     }
00405     box *boxes = calloc(l.w*l.h*l.n, sizeof(box));
00406     float **probs = calloc(l.w*l.h*l.n, sizeof(float *));
00407     for(j = 0; j < l.w*l.h*l.n; ++j) probs[j] = calloc(classes, sizeof(float *));
00408 
00409     int m = plist->size;
00410     int i=0;
00411     int t;
00412 
00413     float thresh = .005;
00414     float nms = .45;
00415 
00416     int nthreads = 4;
00417     image *val = calloc(nthreads, sizeof(image));
00418     image *val_resized = calloc(nthreads, sizeof(image));
00419     image *buf = calloc(nthreads, sizeof(image));
00420     image *buf_resized = calloc(nthreads, sizeof(image));
00421     pthread_t *thr = calloc(nthreads, sizeof(pthread_t));
00422 
00423     load_args args = {0};
00424     args.w = net.w;
00425     args.h = net.h;
00426     args.type = IMAGE_DATA;
00427 
00428     for(t = 0; t < nthreads; ++t){
00429         args.path = paths[i+t];
00430         args.im = &buf[t];
00431         args.resized = &buf_resized[t];
00432         thr[t] = load_data_in_thread(args);
00433     }
00434     time_t start = time(0);
00435     for(i = nthreads; i < m+nthreads; i += nthreads){
00436         fprintf(stderr, "%d\n", i);
00437         for(t = 0; t < nthreads && i+t-nthreads < m; ++t){
00438             pthread_join(thr[t], 0);
00439             val[t] = buf[t];
00440             val_resized[t] = buf_resized[t];
00441         }
00442         for(t = 0; t < nthreads && i+t < m; ++t){
00443             args.path = paths[i+t];
00444             args.im = &buf[t];
00445             args.resized = &buf_resized[t];
00446             thr[t] = load_data_in_thread(args);
00447         }
00448         for(t = 0; t < nthreads && i+t-nthreads < m; ++t){
00449             char *path = paths[i+t-nthreads];
00450             char *id = basecfg(path);
00451             float *X = val_resized[t].data;
00452             network_predict(net, X);
00453             int w = val[t].w;
00454             int h = val[t].h;
00455             get_region_boxes(l, w, h, thresh, probs, boxes, 0);
00456             if (nms) do_nms_sort(boxes, probs, l.w*l.h*l.n, classes, nms);
00457             if (coco){
00458                 print_cocos(fp, path, boxes, probs, l.w*l.h*l.n, classes, w, h);
00459             } else if (imagenet){
00460                 print_imagenet_detections(fp, i+t-nthreads+1 + 9741, boxes, probs, l.w*l.h*l.n, 200, w, h, map);
00461             } else {
00462                 print_detector_detections(fps, id, boxes, probs, l.w*l.h*l.n, classes, w, h);
00463             }
00464             free(id);
00465             free_image(val[t]);
00466             free_image(val_resized[t]);
00467         }
00468     }
00469     for(j = 0; j < classes; ++j){
00470         fclose(fps[j]);
00471     }
00472     if(coco){
00473         fseek(fp, -2, SEEK_CUR); 
00474         fprintf(fp, "\n]\n");
00475         fclose(fp);
00476     }
00477     fprintf(stderr, "Total Detection Time: %f Seconds\n", (double)(time(0) - start));
00478 }
00479 
00480 void validate_detector_recall(char *cfgfile, char *weightfile)
00481 {
00482     network net = parse_network_cfg(cfgfile);
00483     if(weightfile){
00484         load_weights(&net, weightfile);
00485     }
00486     set_batch_network(&net, 1);
00487     fprintf(stderr, "Learning Rate: %g, Momentum: %g, Decay: %g\n", net.learning_rate, net.momentum, net.decay);
00488     srand(time(0));
00489 
00490     list *plist = get_paths("data/voc.2007.test");
00491     char **paths = (char **)list_to_array(plist);
00492 
00493     layer l = net.layers[net.n-1];
00494     int classes = l.classes;
00495 
00496     int j, k;
00497     box *boxes = calloc(l.w*l.h*l.n, sizeof(box));
00498     float **probs = calloc(l.w*l.h*l.n, sizeof(float *));
00499     for(j = 0; j < l.w*l.h*l.n; ++j) probs[j] = calloc(classes, sizeof(float *));
00500 
00501     int m = plist->size;
00502     int i=0;
00503 
00504     float thresh = .001;
00505     float iou_thresh = .5;
00506     float nms = .4;
00507 
00508     int total = 0;
00509     int correct = 0;
00510     int proposals = 0;
00511     float avg_iou = 0;
00512 
00513     for(i = 0; i < m; ++i){
00514         char *path = paths[i];
00515         image orig = load_image_color(path, 0, 0);
00516         image sized = resize_image(orig, net.w, net.h);
00517         char *id = basecfg(path);
00518         network_predict(net, sized.data);
00519         get_region_boxes(l, 1, 1, thresh, probs, boxes, 1);
00520         if (nms) do_nms(boxes, probs, l.w*l.h*l.n, 1, nms);
00521 
00522         char labelpath[4096];
00523         find_replace(path, "images", "labels", labelpath);
00524         find_replace(labelpath, "JPEGImages", "labels", labelpath);
00525         find_replace(labelpath, ".jpg", ".txt", labelpath);
00526         find_replace(labelpath, ".JPEG", ".txt", labelpath);
00527 
00528         int num_labels = 0;
00529         box_label *truth = read_boxes(labelpath, &num_labels);
00530         for(k = 0; k < l.w*l.h*l.n; ++k){
00531             if(probs[k][0] > thresh){
00532                 ++proposals;
00533             }
00534         }
00535         for (j = 0; j < num_labels; ++j) {
00536             ++total;
00537             box t = {truth[j].x, truth[j].y, truth[j].w, truth[j].h};
00538             float best_iou = 0;
00539             for(k = 0; k < l.w*l.h*l.n; ++k){
00540                 float iou = box_iou(boxes[k], t);
00541                 if(probs[k][0] > thresh && iou > best_iou){
00542                     best_iou = iou;
00543                 }
00544             }
00545             avg_iou += best_iou;
00546             if(best_iou > iou_thresh){
00547                 ++correct;
00548             }
00549         }
00550 
00551         fprintf(stderr, "%5d %5d %5d\tRPs/Img: %.2f\tIOU: %.2f%%\tRecall:%.2f%%\n", i, correct, total, (float)proposals/(i+1), avg_iou*100/total, 100.*correct/total);
00552         free(id);
00553         free_image(orig);
00554         free_image(sized);
00555     }
00556 }
00557 
00558 void test_detector(char *datacfg, char *cfgfile, char *weightfile, char *filename, float thresh)
00559 {
00560     list *options = read_data_cfg(datacfg);
00561     char *name_list = option_find_str(options, "names", "data/names.list");
00562     char **names = get_labels(name_list);
00563 
00564     image **alphabet = load_alphabet();
00565     network net = parse_network_cfg(cfgfile);
00566     if(weightfile){
00567         load_weights(&net, weightfile);
00568     }
00569     set_batch_network(&net, 1);
00570     srand(2222222);
00571     clock_t time;
00572     char buff[256];
00573     char *input = buff;
00574     int j;
00575     float nms=.4;
00576     while(1){
00577         if(filename){
00578             strncpy(input, filename, 256);
00579         } else {
00580             printf("Enter Image Path: ");
00581             fflush(stdout);
00582             input = fgets(input, 256, stdin);
00583             if(!input) return;
00584             strtok(input, "\n");
00585         }
00586         image im = load_image_color(input,0,0);
00587       printf("%d, %d\n", net.w, net.h);
00588         image sized = resize_image(im, net.w, net.h);
00589         layer l = net.layers[net.n-1];
00590 
00591         box *boxes = calloc(l.w*l.h*l.n, sizeof(box));
00592         float **probs = calloc(l.w*l.h*l.n, sizeof(float *));
00593         for(j = 0; j < l.w*l.h*l.n; ++j) probs[j] = calloc(l.classes, sizeof(float *));
00594 
00595         float *X = sized.data;
00596         time=clock();
00597         network_predict(net, X);
00598         //printf("%s: Predicted in %f seconds.\n", input, sec(clock()-time));
00599         get_region_boxes(l, 1, 1, thresh, probs, boxes, 0);
00600         if (nms) do_nms_sort(boxes, probs, l.w*l.h*l.n, l.classes, nms);
00601       
00602 /*      draw_detections(im, l.w*l.h*l.n, thresh, boxes, probs, names, alphabet, l.classes);
00603         save_image(im, "predictions");
00604         show_image(im, "predictions");
00605 */
00606 
00607         int i;
00608         int num = l.w*l.h*l.n;
00609         for(i = 0; i < num; ++i){
00610                 int class = max_index(probs[i], l.classes);
00611                 float prob = probs[i][class];
00612                 if(prob > thresh){
00613                         printf("%s\n", names[class]); //class name
00614                         printf("%lf\n", prob); //confidence of detection
00615                     box b = boxes[i];
00616                     short mid_x  = b.x*im.w;
00617                     short mid_y = b.y*im.h;
00618                     printf("%hu\n", mid_x); //x coordinate of centriod
00619                         printf("%hu\n", mid_y); //y coordinate of centriod
00620                     short left  = (b.x-b.w/2.)*im.w;
00621                     short right = (b.x+b.w/2.)*im.w;
00622                     short top   = (b.y-b.h/2.)*im.h;
00623                     short bot   = (b.y+b.h/2.)*im.h;
00624                     printf("%hu , %hu\n", left, bot); //bottom left coordinate of bounding box
00625                     printf("%hu , %hu\n", right, top); //top right coordinate of bounding box
00626                 }
00627         } 
00628         free_image(im);
00629         free_image(sized);
00630         free(boxes);
00631         free_ptrs((void **)probs, l.w*l.h*l.n);
00632 #ifdef OPENCV
00633         cvWaitKey(0);
00634         cvDestroyAllWindows();
00635 #endif
00636         if (filename) break;
00637     }
00638 }
00639 
00640 void run_detector(int argc, char **argv)
00641 {
00642     char *prefix = find_char_arg(argc, argv, "-prefix", 0);
00643     float thresh = find_float_arg(argc, argv, "-thresh", .25);
00644     int cam_index = find_int_arg(argc, argv, "-c", 0);
00645     int frame_skip = find_int_arg(argc, argv, "-s", 0);
00646     if(argc < 4){
00647         fprintf(stderr, "usage: %s %s [train/test/valid] [cfg] [weights (optional)]\n", argv[0], argv[1]);
00648         return;
00649     }
00650     char *gpu_list = find_char_arg(argc, argv, "-gpus", 0);
00651     int *gpus = 0;
00652     int gpu = 0;
00653     int ngpus = 0;
00654     if(gpu_list){
00655         printf("%s\n", gpu_list);
00656         int len = strlen(gpu_list);
00657         ngpus = 1;
00658         int i;
00659         for(i = 0; i < len; ++i){
00660             if (gpu_list[i] == ',') ++ngpus;
00661         }
00662         gpus = calloc(ngpus, sizeof(int));
00663         for(i = 0; i < ngpus; ++i){
00664             gpus[i] = atoi(gpu_list);
00665             gpu_list = strchr(gpu_list, ',')+1;
00666         }
00667     } else {
00668         gpu = gpu_index;
00669         gpus = &gpu;
00670         ngpus = 1;
00671     }
00672 
00673     int clear = find_arg(argc, argv, "-clear");
00674 
00675     char *datacfg = argv[3];
00676     char *cfg = argv[4];
00677     char *weights = (argc > 5) ? argv[5] : 0;
00678     char *filename = (argc > 6) ? argv[6]: 0;
00679     if(0==strcmp(argv[2], "test")) test_detector(datacfg, cfg, weights, filename, thresh);
00680     else if(0==strcmp(argv[2], "train")) train_detector(datacfg, cfg, weights, gpus, ngpus, clear);
00681     else if(0==strcmp(argv[2], "valid")) validate_detector(datacfg, cfg, weights);
00682     else if(0==strcmp(argv[2], "recall")) validate_detector_recall(cfg, weights);
00683     else if(0==strcmp(argv[2], "demo")) {
00684         list *options = read_data_cfg(datacfg);
00685         int classes = option_find_int(options, "classes", 20);
00686         char *name_list = option_find_str(options, "names", "data/names.list");
00687         char **names = get_labels(name_list);
00688         demo(cfg, weights, thresh, cam_index, filename, names, classes, frame_skip, prefix);
00689     }
00690 }


rail_object_detector
Author(s):
autogenerated on Sat Jun 8 2019 20:26:30