From: Jérémie D. <Ba...@us...> - 2011-05-21 17:27:58
|
This is an automated email from the git hooks/post-receive script. It was generated because a ref change was pushed to the repository containing the project "krobot". The branch, master has been updated via b3d20062e69f317da0894f7b78746c5cf59dd320 (commit) from fd338215ec279f96b2992d7faf8e26fe866fbefe (commit) Those revisions listed above that are new to this repository have not appeared on any other notification email; so we list those revisions in full, below. - Log ----------------------------------------------------------------- commit b3d20062e69f317da0894f7b78746c5cf59dd320 Author: Jérémie Dimino <je...@di...> Date: Sat May 21 19:26:51 2011 +0200 [vision] copy the coupe2008 folder to coupe2011 and add config file parsing to findBalles ----------------------------------------------------------------------- Changes: diff --git a/info/vision/coupe2011/Makefile b/info/vision/coupe2011/Makefile new file mode 100644 index 0000000..277fe19 --- /dev/null +++ b/info/vision/coupe2011/Makefile @@ -0,0 +1,24 @@ +OBJECTS = camfilter capture capturevideo findBallse fiteellipse_cam fiteellipse_camfilter + +all: $(OBJECTS) + +clean: + rm -f $(OBJECTS) + +camfilter: camfilter.c + $(CXX) $^ -o $@ `pkg-config --cflags --libs opencv` + +capture: capture.c + $(CXX) $^ -o $@ `pkg-config --cflags --libs opencv` + +capturevideo: capturevideo.c + $(CXX) $^ -o $@ `pkg-config --cflags --libs opencv` + +findBallse: findBallse.c + $(CXX) $^ -o $@ `pkg-config --cflags --libs opencv` + +fiteellipse_cam: fiteellipse_cam.c + $(CXX) $^ -o $@ `pkg-config --cflags --libs opencv` + +fiteellipse_camfilter: fiteellipse_camfilter.c + $(CXX) $^ -o $@ `pkg-config --cflags --libs opencv` \ No newline at end of file diff --git a/info/vision/coupe2011/camfilter.c b/info/vision/coupe2011/camfilter.c new file mode 100644 index 0000000..f90c95f --- /dev/null +++ b/info/vision/coupe2011/camfilter.c @@ -0,0 +1,283 @@ +#include <cv.h> +#include <highgui.h> +#include <math.h> +#include <stdio.h> + +int slider_pos = 70, minCont = 20, maxCont = 100; +int cenH=90, radH=180, minS=0, maxS=255, minV=0, maxV=255; + +// Load the source image. HighGUI use. +IplImage *image01 = 0, *image02 = 0, *image03 = 0; +IplImage *imH = 0, *imS = 0, *imV = 0, *imHSV = 0, *imFil = 0, *imCont = 0; + +void process_image(int h); +int in_radius(int val, int center, int radius, int max); + +int main( int argc, char** argv ) +{ + int ncams, source, c, quit=0; + CvCapture *capture = NULL; + + // Ouvre la webcam + ncams = (argc >= 2 ? atoi(argv[1]) : 1); + source = (argc >= 3 ? atoi(argv[2]) : 0); + capture = cvCaptureFromCAM(source); + + // Create windows. + cvNamedWindow("H",1); + cvNamedWindow("S",1); + cvNamedWindow("V",1); + cvNamedWindow("Source", 1); + cvNamedWindow("Filtered",1); + cvNamedWindow("Result", 1); + + // Create toolbars. HighGUI use. + cvCreateTrackbar( "Threshold", "Result", &slider_pos, 255, NULL); + cvCreateTrackbar( "Min radius", "Result", &minCont, 255, NULL); + cvCreateTrackbar( "Max radius", "Result", &maxCont, 255, NULL); + + cvCreateTrackbar("Center", "H", &cenH, 180, NULL); + cvCreateTrackbar("Radius", "H", &radH, 180, NULL); + cvCreateTrackbar("Min", "S", &minS, 255, NULL); + cvCreateTrackbar("Max", "S", &maxS, 255, NULL); + cvCreateTrackbar("Min", "V", &minV, 255, NULL); + cvCreateTrackbar("Max", "V", &maxV, 255, NULL); + + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + // Création de l'image03 à la taile de l'image prise par la webcam + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + imH = cvCloneImage(image03); cvZero(imH); + imS = cvCloneImage(image03); cvZero(imS); + imV = cvCloneImage(image03); cvZero(imV); + + // Même chose avec image05 + imHSV = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 3); + + while (!quit) + { + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + process_image(0); + + // Show the images. + cvShowImage("H", imH); + cvShowImage("S", imS); + cvShowImage("V", imV); + cvShowImage("Source", image01); + cvShowImage("Filtered", imFil); + cvShowImage("Result", imCont); + + // Wait for a key stroke; the same function arranges events processing + c = (char)cvWaitKey(10); + + switch (c) + { + case 'c': + source = (source+1) % ncams; + cvReleaseCapture(&capture); + capture = cvCaptureFromCAM(source); + cvReleaseImage(&image03); + image01 = cvQueryFrame(capture); + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + imHSV = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 3); + imH = cvCloneImage(image03); + imS = cvCloneImage(image03); + imV = cvCloneImage(image03); + break; + case 'p': + printf("\nH (center,radius) : (%d,%d)\n", cenH, radH); + printf("S (min,max) : (%d,%d)\n", minS, maxS); + printf("V (min,max) : (%d,%d)\n", minV, maxV); + printf("Threshold : %d\n", slider_pos); + printf("Sort radius (min,max) : (%d,%d)\n", minCont, maxCont); + break; + case 'P': + putchar('\n'); + printf("centH = %d\n", cenH); + printf("radH = %d\n", radH); + printf("minS = %d\n", minS); + printf("maxS = %d\n", maxS); + printf("minV = %d\n", minV); + printf("maxV = %d\n", maxV); + printf("threshold = %d\n", slider_pos); + printf("minCont = %d\n", minCont); + printf("maxCont = %d\n", maxCont); + break; + case 'q': + quit = 1; + break; + } + + cvReleaseImage(&imCont); + cvReleaseImage(&imFil); + } + + + // On release la mémoire + cvReleaseCapture(&capture); + + cvReleaseImage(&image02); + cvReleaseImage(&image03); + cvReleaseImage(&imH); + cvReleaseImage(&imS); + cvReleaseImage(&imV); + cvReleaseImage(&imHSV); + cvReleaseImage(&imFil); + cvReleaseImage(&imCont); + + cvDestroyWindow("H"); + cvDestroyWindow("S"); + cvDestroyWindow("V"); + cvDestroyWindow("Source"); + cvDestroyWindow("Result"); + + return 0; +} + +// Define trackbar callback functon. This function find contours, +// draw it and approximate it by ellipses. +void process_image(int h) +{ + CvMemStorage* stor; + CvSeq* cont; + CvBox2D32f* box; + CvPoint* PointArray; + CvPoint2D32f* PointArray2D32f; + int i, meanRad; + + // Filtre de couleur + cvCvtColor(image01, imHSV, CV_BGR2HSV); + imFil = cvCloneImage(image01); + imCont = cvCloneImage(image01); + + // Génération des images H,S,V + for (i=0 ; i < imHSV->width*imHSV->height; i++) + { + imH->imageData[i] = in_radius(imHSV->imageData[3*i], cenH, radH, 180) ? 255 : 0; + imS->imageData[i] = (((uchar)imHSV->imageData[3*i+1] >= minS) && ((uchar)imHSV->imageData[3*i+1] <= maxS)) ? 255 : 0; + imV->imageData[i] = (((uchar)imHSV->imageData[3*i+2] >= minV) && ((uchar)imHSV->imageData[3*i+2] <= maxV)) ? 255 : 0; + } + + for (i=0 ; i < imFil->width*imFil->height; i++) + { + if (in_radius(imHSV->imageData[3*i], cenH, radH, 180) && + (uchar)imHSV->imageData[3*i+1] >= minS && (uchar)imHSV->imageData[3*i+1] <= maxS && + (uchar)imHSV->imageData[3*i+2] >= minV && (uchar)imHSV->imageData[3*i+2] <= maxV ) + { + // On laisse la couleur du pixel + } + else + { + // sinon on l'efface + imFil->imageData[3*i ] = 0; + imFil->imageData[3*i+1] = 0; + imFil->imageData[3*i+2] = 0; + } + } + + // Conversion en niveaux de gris de l'image filtrée + cvCvtColor(imFil, image03, CV_BGR2GRAY); + + // Create the destination images + image02 = cvCloneImage( image03 ); + + // Create dynamic memory storage and sequence. + stor = cvCreateMemStorage(0); + cont = cvCreateSeq(CV_SEQ_ELTYPE_POINT, sizeof(CvSeq), sizeof(CvPoint) , stor); + + // Threshold the source image. This needful for cvFindContours(). + cvThreshold( image03, image02, slider_pos, 255, CV_THRESH_BINARY ); + + // Find all contours. + cvFindContours( image02, stor, &cont, sizeof(CvContour), + CV_RETR_LIST, CV_CHAIN_APPROX_NONE, cvPoint(0,0)); + + // Clear images. IPL use. + cvZero(image02); + cvZero(imCont); + + // On fixe la ROI de l'image pour ne pas dessiner à l'extérieur + imCont->roi = (_IplROI*)malloc(sizeof(IplROI)); + imCont->roi->coi = 0; + imCont->roi->xOffset = 0; + imCont->roi->yOffset = 0; + imCont->roi->width = imCont->width; + imCont->roi->height = imCont->height; + + // This cycle draw all contours and approximate it by ellipses. + for(;cont;cont = cont->h_next) + { + int i; // Indicator of cycle. + int count = cont->total; // This is number point in contour + CvPoint center; + CvSize size; + + // Number point must be more than or equal to 6 (for cvFitEllipse_32f). + if( count < 6 ) + continue; + + // Alloc memory for contour point set. + PointArray = (CvPoint*)malloc( count*sizeof(CvPoint) ); + PointArray2D32f= (CvPoint2D32f*)malloc( count*sizeof(CvPoint2D32f) ); + + // Alloc memory for ellipse data. + box = (CvBox2D32f*)malloc(sizeof(CvBox2D32f)); + + // Get contour point set. + cvCvtSeqToArray(cont, PointArray, CV_WHOLE_SEQ); + + // Convert CvPoint set to CvBox2D32f set. + for(i=0; i<count; i++) + { + PointArray2D32f[i].x = (float)PointArray[i].x; + PointArray2D32f[i].y = (float)PointArray[i].y; + } + + // Fits ellipse to current contour. + cvFitEllipse(PointArray2D32f, count, box); + + // Convert ellipse data from float to integer representation. + center.x = cvRound(box->center.x); + center.y = cvRound(box->center.y); + size.width = cvRound(box->size.width*0.5); + size.height = cvRound(box->size.height*0.5); + box->angle = -box->angle; + + // On ne dessine le contour et l'ellipse que si son rayon est dans les bornes + meanRad = (size.width + size.height) / 2; + + if (meanRad >= minCont && meanRad <= maxCont) + { + // Draw current contour. + cvDrawContours(imCont,cont,CV_RGB(255,255,255),CV_RGB(255,255,255),0,1,8,cvPoint(0,0)); + + // Draw ellipse. + cvEllipse(imCont, center, size, + box->angle, 0, 360, + CV_RGB(255,0,0), 1, CV_AA, 0); + } + + // Free memory. + free(imCont->roi); imCont->roi = NULL; + free(PointArray); + free(PointArray2D32f); + free(box); + + } + + // On libère la mémoire + cvReleaseMemStorage(&stor); + cvReleaseImage(&image02); +} + +#define min(a,b) (((a) < (b)) ? (a) : (b)) + +int in_radius(int val, int center, int radius, int max) +{ + int d; + d = abs(val - center); + return min(d,max - d) <= radius; +} diff --git a/info/vision/coupe2011/capture.c b/info/vision/coupe2011/capture.c new file mode 100644 index 0000000..168a74f --- /dev/null +++ b/info/vision/coupe2011/capture.c @@ -0,0 +1,62 @@ +// Programme permettant de voir l'image d'une webcam +// et d'en faire des shots + +#include "cv.h" +#include "highgui.h" +#include <stdio.h> +#include <string.h> + +int main(int argc, char** argv) +{ + CvCapture *capture = NULL; + IplImage *frame = NULL; + unsigned int compteur = 0, source = 0, ncams; + char c, file[51]; + + ncams = (argc == 2 ? atoi(argv[1]) : 1); + capture = cvCaptureFromCAM(source); + + printf("Programme de capture d'image depuis une webcam\n\n"); + printf("Commandes :\n"); + printf("\tq : quitter\n"); + printf("\tc : cycler au travers des différentes webcam coonectées\n"); + printf("\tEspace : sauvegarder une image\n\n"); + printf("\t\tPasser en argument le nombre de webcams si plus d'une.\n\n\n"); + + cvNamedWindow("Capture", 0); + + while (1) + { + frame = cvQueryFrame(capture); + if(frame==NULL) + { + printf("Impossible de lire l'image !\n"); + } + else + { + cvShowImage("Capture", frame); + + c = (char)cvWaitKey(10); + + if (c=='q') break; + switch (c) + { + case 'c' : + source = (source + 1 ) % ncams; + cvReleaseCapture(&capture); + capture = cvCaptureFromCAM(source); + break; + + case ' ' : + compteur++; + sprintf(file, "img%d.jpg", compteur); + cvSaveImage(file,frame); + } + } + } + + cvReleaseCapture(&capture); + cvDestroyWindow("Capture"); + + return 0; +} diff --git a/info/vision/coupe2011/capturevideo.c b/info/vision/coupe2011/capturevideo.c new file mode 100644 index 0000000..a398ace --- /dev/null +++ b/info/vision/coupe2011/capturevideo.c @@ -0,0 +1,86 @@ +// Programme permettant de récupérer une video par la webcam +// sous forme d'une série d'images tiff + +#include "cv.h" +#include "highgui.h" +#include <stdio.h> +#include <string.h> + +int main(int argc, char** argv) +{ + CvCapture *capture = NULL; + IplImage *frame = NULL; + unsigned int compteur = 0, source = 0, ncams; + char c, file[60], basename[51], ext[5]; + int isFilming = 0; + double t; + + ncams = (argc == 2 ? atoi(argv[1]) : 1); + capture = cvCaptureFromCAM(source); + + printf("Programme de capture de video depuis une webcam\n\n"); + printf("Commandes :\n"); + printf("\tq : quitter\n"); + printf("\tc : cycler au travers des différentes webcam coonectées\n"); + printf("\t\t(ne marche que quand le film n'est pas en cours d'acquisition\n"); + printf("\tEspace : commencer/areter de filmer\n\n"); + printf("\t\tPasser en argument le nombre de webcams si plus d'une.\n\n\n"); + + printf("\n\nNom de la série d'images : "); + scanf("%s", basename); + printf("\nExtension des images : "); + scanf("%s", ext); + + cvNamedWindow("Capture", 0); + + t = (double) cvGetTickCount(); + + while (1) + { + // On récupère une image + frame = cvQueryFrame(capture); + if(frame==NULL) + { + printf("Impossible de lire l'image !\n"); + } + else + { + // On l'affiche dans la fenêtre + cvShowImage("Capture", frame); + + c = (char)cvWaitKey(5); + + // On gère l'appui sur une touche du clavier + if (c=='q') break; + switch (c) + { + case 'c' : + if (!isFilming) + { + source = (source + 1 ) % ncams; + cvReleaseCapture(&capture); + capture = cvCaptureFromCAM(source); + break; + } + + case ' ' : + isFilming = !isFilming; + } + + // Si on doit filmer, on vérifie qu'il est temps de prendre une image + // On filme a 25 images par secondes + if (isFilming && ((double)cvGetTickCount() - t >= 0.04)) + { + // On prend une image et on remet à jour le compteur de temps + compteur++; + sprintf(file, "%s%.3d.%s", basename, compteur, ext); + cvSaveImage(file, frame); + } + } + } + + cvReleaseCapture(&capture); + cvDestroyWindow("Capture"); + + return 0; +} diff --git a/info/vision/coupe2011/constructionPositifs.c b/info/vision/coupe2011/constructionPositifs.c new file mode 100644 index 0000000..32fe1c8 --- /dev/null +++ b/info/vision/coupe2011/constructionPositifs.c @@ -0,0 +1,198 @@ +// Programme permettant de traiter une série d'images et de créer une liste +// des fichiers avec les occurences d'un objet dans celles-ci + +#include "cv.h" +#include "highgui.h" +#include <stdio.h> +#include <string.h> + +IplImage *image = NULL; +CvPoint origin; +CvRect selection; +int select_object = 0; + +// Fonction de callback pour gérer la selection à la souris +void on_mouse(int event, int x, int y, int flags, void* param) +{ + if (image != NULL) + { + if (image->origin) + { + x = image->width - x; + y = image->height - y; + } + + // Mise à jour de la zone de sélection + if (select_object) + { + selection.x = MIN(x, origin.x); + selection.y = MIN(y, origin.y); + selection.width = selection.x + CV_IABS(x - origin.x); + selection.height = selection.y + CV_IABS(y-origin.y); + + selection.x = MAX(selection.x, 0); + selection.y = MAX(selection.y, 0); + selection.width = MIN(selection.width, image->width); + selection.height = MIN(selection.height, image->height); + selection.width -= selection.x; + selection.height -= selection.y; + } + + // Gestion des évènements souris + switch(event) + { + case CV_EVENT_LBUTTONDOWN: + // On commence une phase de sélection + origin = cvPoint(x,y); + selection = cvRect(x,y,0,0); + select_object = 1; + break; + case CV_EVENT_LBUTTONUP: + // On termine une phase de sélection + select_object = 0; + if (selection.width > 0 && selection.height > 0) + { + // action à effectuer après la sélection + // On ne fait rien, l'action est exécutée par la boucle principale + } + break; + } + } + + return; +} + + +// Fonction principale +int main(int argc, char** argv) +{ + IplImage *frame = NULL; + int i, j, nbrObjets, quit=0, imgsuiv=0; + CvRect objets[10]; + char c, file[51]; + FILE *fichier; + + printf("Programme de generation d'une liste d'images positives\n"); + printf("pour la generation d'une base de donnees de reconnaissance d'objet\n\n"); + printf("Utilisation : passer la liste d'images a traiter en argument.\n\n"); + printf("Commandes :\n"); + printf("\tq : quitter\n"); + printf("\t<ESPACE> : valider la selection courante\n"); + printf("\t<ESC> : annuler les selections de l'image courante\n"); + printf("\t<ENTREE> : valider les selections et passer a l'image suivante\n\n\n"); + + if (argc < 2) + { + printf("Pas assez d'arguments\n"); + return 1; + } + + printf("Nom du fichier a ecrire (le fichier sera ecrase) : "); + scanf("%s", file); + printf("\n\n\n"); + + if ( (fichier = fopen(file, "w+")) == NULL) + { + printf("Impossible d'ouvrir le fichier destination !\n"); + return 1; + } + + cvNamedWindow("Image courante", 0); + cvSetMouseCallback("Image courante", on_mouse, 0); + + for (i=1; i < argc && !quit; i++) + { + printf("Image : %s\n", argv[i]); + printf("===================================================\n\n"); + + if ( (image = cvLoadImage(argv[i], 1)) == NULL ) + { + printf("\tImpossible de charger l'image...\n\n\n\n"); + continue; + } + cvShowImage("Image courante", image); + + // On alloue les buffers si ce n'est pa déjà fait + if (frame == NULL) + { + frame = cvCreateImage(cvGetSize(image), 8, 3); + frame->origin = image->origin; + } + + // il n'y a pas d'objet + nbrObjets = 0; + // On efface une éventuelle sélection + selection.width = 0; + selection.height = 0; + // On boucle jusqu'à devoir passer à l'image suivante + imgsuiv=0; + + while (!imgsuiv) + { + // On fait le rendu de l'image en ajoutant la zone de selection + // On travaille sur une copie de l'image + cvCopy(image, frame, 0); + // On rend la zone de selection + if( selection.width > 0 && selection.height > 0 ) + { + cvSetImageROI(frame, selection); + cvXorS(frame, cvScalarAll(255), frame, 0); + cvResetImageROI(frame); + } + + // On affiche l'image + cvShowImage("Image courante", frame); + + // On répond aux entrées utilisateur + c = (char)cvWaitKey(10); + + switch (c) + { + case 'q' : + // On passe à l'image suivante + imgsuiv=1; + // En fait, non, on quitte + quit=1; + break; + + case 27 : // <ESC> + nbrObjets = 0; + break; + + case 10 : // <ENTREE> + fprintf(fichier, "%s", argv[i]); + if (nbrObjets > 0) + { + fprintf(fichier, " %d", nbrObjets); + for (j = 0; j < nbrObjets; j++) + fprintf(fichier, " %d %d %d %d", + objets[j].x, objets[j].y, objets[j].width, objets[j].height); + } + fprintf(fichier, "\n"); + // On passe à l'image suivante + imgsuiv=1; + break; + + case 32 : // <ESPACE> + if (selection.width > 0 && selection.height > 0) + { + objets[nbrObjets] = selection; + nbrObjets++; + printf("\t%d. rect x=%d\ty=%d\t\twidth=%d\theight=%d\n", + nbrObjets, selection.x, selection.y, selection.width, selection.height); + } + // On efface la selection courante de l'ecran + selection.width = 0; + selection.height = 0; + break; + } + } + printf("\n\n\n"); + } + + fclose(fichier); + + cvDestroyWindow("Image courante"); + + return 0; +} diff --git a/info/vision/coupe2011/findBallse.c b/info/vision/coupe2011/findBallse.c new file mode 100644 index 0000000..a97c54a --- /dev/null +++ b/info/vision/coupe2011/findBallse.c @@ -0,0 +1,298 @@ +#include "cv.h" +#include "highgui.h" +#include <math.h> +#include <stdio.h> +#include <ctype.h> +#include <err.h> + +#define min(a,b) (((a) < (b)) ? (a) : (b)) + +/* The parameters of the color to find in images. */ +struct color_params { + int centH, radH, minS, maxS, minV, maxV; + int threshold; + int minCont, maxCont; +}; + +/* Global parameters. */ +struct color_params params; + +// Load the source image. HighGUI use. +IplImage *image01 = 0, *image02 = 0, *image03 = 0, *imCont = 0, *imFill = 0, *imHSV = 0; + +int affichage = 0; +int slider_pos; + +void process_image(); +int in_radius(int val, int center, int radius, int max); + +/* Parse the configuration file and store the result into params. */ +void parse_config(char *file_name) +{ + FILE *fp = fopen(file_name, "r"); + + char *line = NULL; + size_t line_len = 0; + char key[1024]; + int value; + + while (getline(&line, &line_len, fp) != -1) { + char *p; + + /* Skip blanks at the beginning of the line. */ + for (p = line; *p && isblank(*p); p++); + + /* Skip empty lines and comments. */ + if (*p == 0 || *p == '#') continue; + + /* Check that key won't overflow. */ + if (strlen(line) >= 1024) errx(2, "line too long in configuration file"); + + /* Parse the line. */ + if (sscanf(p, "%s = %d \n", &key, &value) != 2) errx(2, "invalid configuration file"); + + /* Assign the value to the right parameter. */ + if (strcmp(key, "centH") == 0) + params.centH = value; + else if (strcmp(key, "radH") == 0) + params.radH = value; + else if (strcmp(key, "minS") == 0) + params.minS = value; + else if (strcmp(key, "maxS") == 0) + params.maxS = value; + else if (strcmp(key, "minV") == 0) + params.minV = value; + else if (strcmp(key, "maxV") == 0) + params.maxV = value; + else if (strcmp(key, "threshold") == 0) + params.threshold = value; + else if (strcmp(key, "minCont") == 0) + params.minCont = value; + else if (strcmp(key, "maxCont") == 0) + params.maxCont = value; + else + errx(2, "invalid key in configuration file: '%s'", key); + } + + if (line) free(line); + fclose(fp); +} + +int main( int argc, char** argv ) +{ + int source, c, quit=0; + CvCapture *capture = NULL; + FILE *fichier; + + // Traitement des paramètres de ligne de commande + if (argc < 2) + { + printf("argv[1] : chemin du fichier de paramètres\n"); + printf("argv[2] : (optionnel) si différent de 0, affiche une fenêtre\n"); + printf("argv[3] : (optionnel) numéro de la webcam à utiliser\n"); + return 1; + } + + /* Parse configuration. */ + parse_config(argv[1]); + + affichage = argc >= 3 ? atoi(argv[2]) : 0; + source = argc >= 4 ? atoi(argv[3]) : 0; + + // Ouvre la webcam + capture = cvCaptureFromCAM(source); + + // Create window + if (affichage != 0) + cvNamedWindow("Result", 1); + + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + // Création de l'image en niveaux de gris à la taile de l'image prise par la webcam + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + + // Même chose avec l'image pour conversion + imHSV = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 3); + + while (!quit) + { + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + process_image(); + + // Show the image + if (affichage != 0) + cvShowImage("Result", imCont); + + // Wait for a key stroke; the same function arranges events processing + c = (char)cvWaitKey(10); + + switch (c) + { + case 'q': + quit = 1; + break; + } + + cvReleaseImage(&imCont); + cvReleaseImage(&imFill); + } + + + // On release la mémoire + cvReleaseCapture(&capture); + + cvReleaseImage(&image02); + cvReleaseImage(&image03); + cvReleaseImage(&imHSV); + cvReleaseImage(&imFill); + cvReleaseImage(&imCont); + + if (affichage != 0) + cvDestroyWindow("Result"); + + return 0; +} + +// This function the balls, +void process_image() +{ + CvMemStorage* stor; + CvSeq* cont; + CvBox2D32f* box; + CvPoint* PointArray; + CvPoint2D32f* PointArray2D32f; + int i, j, meanRad; + + // Changement d'espace de couleur + cvCvtColor(image01, imHSV, CV_BGR2HSV); + + // Génération de l'image avec les résultats + if (affichage != 0) + { + imCont = cvCloneImage(image01); + cvZero(imCont); + // On fixe la ROI de l'image pour ne pas dessiner à l'extérieur + imCont->roi = (_IplROI*)malloc(sizeof(IplROI)); + imCont->roi->coi = 0; + imCont->roi->xOffset = 0; + imCont->roi->yOffset = 0; + imCont->roi->width = imCont->width; + imCont->roi->height = imCont->height; + } + + // On fait le traitement pour chaque couleur de balle + imFill = cvCloneImage(image01); + + for (i=0 ; i < imFill->width*imFill->height; i++) + { + if (in_radius(imHSV->imageData[3*i], params.centH, params.radH, 180) && + (uchar)imHSV->imageData[3*i+1] >= params.minS && (uchar)imHSV->imageData[3*i+1] <= params.maxS && + (uchar)imHSV->imageData[3*i+2] >= params.minV && (uchar)imHSV->imageData[3*i+2] <= params.maxV ) + { + // On laisse la couleur du pixel + } + else + { + // sinon on l'efface + imFill->imageData[3*i ] = 0; + imFill->imageData[3*i+1] = 0; + imFill->imageData[3*i+2] = 0; + } + } + + // Conversion en niveaux de gris de l'image filtrée + cvCvtColor(imFill, image03, CV_BGR2GRAY); + + // Create the destination images + image02 = cvCloneImage( image03 ); + + // Create dynamic memory storage and sequence. + stor = cvCreateMemStorage(0); + cont = cvCreateSeq(CV_SEQ_ELTYPE_POINT, sizeof(CvSeq), sizeof(CvPoint) , stor); + + // Threshold the source image. This needful for cvFindContours(). + cvThreshold( image03, image02, slider_pos, 255, CV_THRESH_BINARY ); + + // Find all contours. + cvFindContours( image02, stor, &cont, sizeof(CvContour), + CV_RETR_LIST, CV_CHAIN_APPROX_NONE, cvPoint(0,0)); + + // Clear image. IPL use. + cvZero(image02); + + // This cycle draw all contours and approximate it by ellipses. + for(;cont;cont = cont->h_next) + { + int i; // Indicator of cycle. + int count = cont->total; // This is number point in contour + CvPoint center; + CvSize size; + + // Number point must be more than or equal to 6 (for cvFitEllipse_32f). + if( count < 6 ) + continue; + + // Alloc memory for contour point set. + PointArray = (CvPoint*)malloc( count*sizeof(CvPoint) ); + PointArray2D32f= (CvPoint2D32f*)malloc( count*sizeof(CvPoint2D32f) ); + + // Alloc memory for ellipse data. + box = (CvBox2D32f*)malloc(sizeof(CvBox2D32f)); + + // Get contour point set. + cvCvtSeqToArray(cont, PointArray, CV_WHOLE_SEQ); + + // Convert CvPoint set to CvBox2D32f set. + for(i=0; i<count; i++) + { + PointArray2D32f[i].x = (float)PointArray[i].x; + PointArray2D32f[i].y = (float)PointArray[i].y; + } + + // Fits ellipse to current contour. + cvFitEllipse(PointArray2D32f, count, box); + + // Convert ellipse data from float to integer representation. + center.x = cvRound(box->center.x); + center.y = cvRound(box->center.y); + size.width = cvRound(box->size.width*0.5); + size.height = cvRound(box->size.height*0.5); + box->angle = -box->angle; + + // On ne dessine le contour et l'ellipse que si son rayon est dans les bornes + meanRad = (size.width + size.height) / 2; + + if (meanRad >= params.minCont && meanRad <= params.maxCont) + { + // Draw current contour. + cvDrawContours(imCont,cont,CV_RGB(255,255,255),CV_RGB(255,255,255),0,1,8,cvPoint(0,0)); + + // Draw ellipse. + cvEllipse(imCont, center, size, + box->angle, 0, 360, + CV_RGB(255,0,0), 1, CV_AA, 0); + } + + // Free memory. + free(imCont->roi); imCont->roi = NULL; + free(PointArray); + free(PointArray2D32f); + free(box); + + } + + // On libère la mémoire + cvReleaseMemStorage(&stor); + cvReleaseImage(&image02); + cvReleaseImage(&imFill); +} + +int in_radius(int val, int center, int radius, int max) +{ + int d; + d = abs(val - center); + return min(d,max - d) <= radius; +} diff --git a/info/vision/coupe2011/fiteellipse_cam.c b/info/vision/coupe2011/fiteellipse_cam.c new file mode 100644 index 0000000..1fbb99f --- /dev/null +++ b/info/vision/coupe2011/fiteellipse_cam.c @@ -0,0 +1,198 @@ +/******************************************************************************** +* +* +* This program is demonstration for ellipse fitting. Program finds +* contours and approximate it by ellipses. +* +* Trackbar specify threshold parametr. +* +* White lines is contours. Red lines is fitting ellipses. +* +* +* Autor: Denis Burenkov. +* +* +* +********************************************************************************/ +#ifdef _CH_ +#pragma package <opencv> +#endif + +#ifndef _EiC +#include "cv.h" +#include "highgui.h" +#endif + +int slider_pos = 70; + +// Load the source image. HighGUI use. +IplImage *image01 = 0, *image02 = 0, *image03 = 0, *image04 = 0; + +void process_image(int h); + +int main( int argc, char** argv ) +{ + int ncams, source, c, quit=0; + CvCapture *capture = NULL; + + // Ouvre la webcam + ncams = (argc >= 2 ? atoi(argv[1]) : 1); + source = (argc >= 3 ? atoi(argv[2]) : 0); + capture = cvCaptureFromCAM(source); + + // Create windows. + cvNamedWindow("Source", 1); + cvNamedWindow("Result", 1); + + // Create toolbars. HighGUI use. + cvCreateTrackbar( "Threshold", "Result", &slider_pos, 255, process_image ); + + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + // Conversion en niveaux de gris + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + + while (!quit) + { + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + // Conversion en niveaux de gris + cvCvtColor(image01, image03, CV_BGR2GRAY); + + cvReleaseImage(&image02); + cvReleaseImage(&image04); + + // Create the destination images + image02 = cvCloneImage( image03 ); + image04 = cvCloneImage( image03 ); + + // Show the image. + cvShowImage("Source", image03); + + process_image(0); + + // Wait for a key stroke; the same function arranges events processing + c = (char)cvWaitKey(10); + + switch (c) + { + case 'c': + source = (source+1) % ncams; + cvReleaseCapture(&capture); + capture = cvCaptureFromCAM(source); + cvReleaseImage(&image03); + image01 = cvQueryFrame(capture); + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + break; + case 'q': + quit = 1; + break; + } + + } + + + // On release la mémoire + cvReleaseCapture(&capture); + + cvReleaseImage(&image01); + cvReleaseImage(&image02); + cvReleaseImage(&image03); + cvReleaseImage(&image04); + + cvDestroyWindow("Source"); + cvDestroyWindow("Result"); + + return 0; +} + +// Define trackbar callback functon. This function find contours, +// draw it and approximate it by ellipses. +void process_image(int h) +{ + CvMemStorage* stor; + CvSeq* cont; + CvBox2D32f* box; + CvPoint* PointArray; + CvPoint2D32f* PointArray2D32f; + + // Create dynamic memory storage and sequence. + stor = cvCreateMemStorage(0); + cont = cvCreateSeq(CV_SEQ_ELTYPE_POINT, sizeof(CvSeq), sizeof(CvPoint) , stor); + + // Threshold the source image. This needful for cvFindContours(). + cvThreshold( image03, image02, slider_pos, 255, CV_THRESH_BINARY ); + + // Find all contours. + cvFindContours( image02, stor, &cont, sizeof(CvContour), + CV_RETR_LIST, CV_CHAIN_APPROX_NONE, cvPoint(0,0)); + + // Clear images. IPL use. + cvZero(image02); + cvZero(image04); + + // This cycle draw all contours and approximate it by ellipses. + for(;cont;cont = cont->h_next) + { + int i; // Indicator of cycle. + int count = cont->total; // This is number point in contour + CvPoint center; + CvSize size; + + // Number point must be more than or equal to 6 (for cvFitEllipse_32f). + if( count < 6 ) + continue; + + // Alloc memory for contour point set. + PointArray = (CvPoint*)malloc( count*sizeof(CvPoint) ); + PointArray2D32f= (CvPoint2D32f*)malloc( count*sizeof(CvPoint2D32f) ); + + // Alloc memory for ellipse data. + box = (CvBox2D32f*)malloc(sizeof(CvBox2D32f)); + + // Get contour point set. + cvCvtSeqToArray(cont, PointArray, CV_WHOLE_SEQ); + + // Convert CvPoint set to CvBox2D32f set. + for(i=0; i<count; i++) + { + PointArray2D32f[i].x = (float)PointArray[i].x; + PointArray2D32f[i].y = (float)PointArray[i].y; + } + + // Fits ellipse to current contour. + cvFitEllipse(PointArray2D32f, count, box); + + // Draw current contour. + cvDrawContours(image04,cont,CV_RGB(255,255,255),CV_RGB(255,255,255),0,1,8,cvPoint(0,0)); + + // Convert ellipse data from float to integer representation. + center.x = cvRound(box->center.x); + center.y = cvRound(box->center.y); + size.width = cvRound(box->size.width*0.5); + size.height = cvRound(box->size.height*0.5); + box->angle = -box->angle; + + // Draw ellipse. + /*cvEllipse(image04, center, size, + box->angle, 0, 360, + CV_RGB(0,0,255), 1, CV_AA, 0);*/ + + // Free memory. + free(PointArray); + free(PointArray2D32f); + free(box); + + } + + // Show image. HighGUI use. + cvShowImage( "Result", image04 ); + + cvReleaseMemStorage(&stor); +} + +#ifdef _EiC +main(1,"fitellipse.c"); +#endif diff --git a/info/vision/coupe2011/fiteellipse_camfilter.c b/info/vision/coupe2011/fiteellipse_camfilter.c new file mode 100644 index 0000000..899fe05 --- /dev/null +++ b/info/vision/coupe2011/fiteellipse_camfilter.c @@ -0,0 +1,217 @@ +/******************************************************************************** +* +* +* This program is demonstration for ellipse fitting. Program finds +* contours and approximate it by ellipses. +* +* Trackbar specify threshold parametr. +* +* White lines is contours. Red lines is fitting ellipses. +* +* +* Autor: Denis Burenkov. +* +* +* +********************************************************************************/ +#ifdef _CH_ +#pragma package <opencv> +#endif + +#ifndef _EiC +#include "cv.h" +#include "highgui.h" +#endif + +int slider_pos = 70; + +// Load the source image. HighGUI use. +IplImage *image01 = 0, *image02 = 0, *image03 = 0, *image04 = 0, *image05 = 0, *image06 = 0; + +void process_image(int h); + +int main( int argc, char** argv ) +{ + int ncams, source, c, quit=0, i; + CvCapture *capture = NULL; + + // Ouvre la webcam + ncams = (argc >= 2 ? atoi(argv[1]) : 1); + source = (argc >= 3 ? atoi(argv[2]) : 0); + capture = cvCaptureFromCAM(source); + + // Create windows. + cvNamedWindow("HSV",1); + cvNamedWindow("Source", 1); + cvNamedWindow("Result", 1); + + // Create toolbars. HighGUI use. + cvCreateTrackbar( "Threshold", "Result", &slider_pos, 255, process_image ); + + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + // Création de l'image03 à la taile de l'image prise par la webcam + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + + // Même chose avec image05 + image05 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 3); + + while (!quit) + { + // Récupère une image de la webcam + image01 = cvQueryFrame(capture); + + // Conversion en niveaux de gris + cvCvtColor(image01, image03, CV_BGR2GRAY); + + // Filtre de couleur + cvCvtColor(image01, image05, CV_BGR2HSV); + cvReleaseImage(&image06); + image06 = cvCloneImage(image03); + + for (i=0 ; i < image06->width*image06->height; i++) + { + image06->imageData[i] = ((image05->imageData[3*i] > 90 && image05->imageData[3*i] < 110 && image05->imageData[3*i+1] > 20) ? 255 : 0); + } + + + cvReleaseImage(&image02); + cvReleaseImage(&image04); + + // Create the destination images + image02 = cvCloneImage( image03 ); + image04 = cvCloneImage( image03 ); + + // Show the image. + cvShowImage("HSV", image06); + cvShowImage("Source", image01); + + process_image(0); + + // Wait for a key stroke; the same function arranges events processing + c = (char)cvWaitKey(10); + + switch (c) + { + case 'c': + source = (source+1) % ncams; + cvReleaseCapture(&capture); + capture = cvCaptureFromCAM(source); + cvReleaseImage(&image03); + image01 = cvQueryFrame(capture); + image03 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 1); + image05 = cvCreateImage(cvSize(image01->width,image01->height), IPL_DEPTH_8U, 3); + break; + case 'q': + quit = 1; + break; + } + + } + + + // On release la mémoire + cvReleaseCapture(&capture); + + cvReleaseImage(&image01); + cvReleaseImage(&image02); + cvReleaseImage(&image03); + cvReleaseImage(&image04); + cvReleaseImage(&image05); + + cvDestroyWindow("HSV"); + cvDestroyWindow("Source"); + cvDestroyWindow("Result"); + + return 0; +} + +// Define trackbar callback functon. This function find contours, +// draw it and approximate it by ellipses. +void process_image(int h) +{ + CvMemStorage* stor; + CvSeq* cont; + CvBox2D32f* box; + CvPoint* PointArray; + CvPoint2D32f* PointArray2D32f; + + // Create dynamic memory storage and sequence. + stor = cvCreateMemStorage(0); + cont = cvCreateSeq(CV_SEQ_ELTYPE_POINT, sizeof(CvSeq), sizeof(CvPoint) , stor); + + // Threshold the source image. This needful for cvFindContours(). + cvThreshold( image03, image02, slider_pos, 255, CV_THRESH_BINARY ); + + // Find all contours. + cvFindContours( image02, stor, &cont, sizeof(CvContour), + CV_RETR_LIST, CV_CHAIN_APPROX_NONE, cvPoint(0,0)); + + // Clear images. IPL use. + cvZero(image02); + cvZero(image04); + + // This cycle draw all contours and approximate it by ellipses. + for(;cont;cont = cont->h_next) + { + int i; // Indicator of cycle. + int count = cont->total; // This is number point in contour + CvPoint center; + CvSize size; + + // Number point must be more than or equal to 6 (for cvFitEllipse_32f). + if( count < 6 ) + continue; + + // Alloc memory for contour point set. + PointArray = (CvPoint*)malloc( count*sizeof(CvPoint) ); + PointArray2D32f= (CvPoint2D32f*)malloc( count*sizeof(CvPoint2D32f) ); + + // Alloc memory for ellipse data. + box = (CvBox2D32f*)malloc(sizeof(CvBox2D32f)); + + // Get contour point set. + cvCvtSeqToArray(cont, PointArray, CV_WHOLE_SEQ); + + // Convert CvPoint set to CvBox2D32f set. + for(i=0; i<count; i++) + { + PointArray2D32f[i].x = (float)PointArray[i].x; + PointArray2D32f[i].y = (float)PointArray[i].y; + } + + // Fits ellipse to current contour. + cvFitEllipse(PointArray2D32f, count, box); + + // Draw current contour. + cvDrawContours(image04,cont,CV_RGB(255,255,255),CV_RGB(255,255,255),0,1,8,cvPoint(0,0)); + + // Convert ellipse data from float to integer representation. + center.x = cvRound(box->center.x); + center.y = cvRound(box->center.y); + size.width = cvRound(box->size.width*0.5); + size.height = cvRound(box->size.height*0.5); + box->angle = -box->angle; + + // Draw ellipse. + /*cvEllipse(image04, center, size, + box->angle, 0, 360, + CV_RGB(0,0,255), 1, CV_AA, 0);*/ + + // Free memory. + free(PointArray); + free(PointArray2D32f); + free(box); + + } + + // Show image. HighGUI use. + cvShowImage( "Result", image04 ); + + cvReleaseMemStorage(&stor); +} + +#ifdef _EiC +main(1,"fitellipse.c"); +#endif hooks/post-receive -- krobot |