CV.cpp
Go to the documentation of this file.
00001 // Copyright (c) 2010, 2013 by Wayne C. Gramlich.  All rights reserved.
00002 
00003 #include <assert.h>
00004 #include <opencv/cv.h>
00005 #include <opencv/highgui.h>
00006 #include <string.h>
00007 
00008 #include "CV.hpp"
00009 #include "File.hpp"
00010 #include "String.hpp"
00011 
00012 static CvSlice whole_sequence;          // CV_WHOLE_SEQ (see below)
00013 CV_Slice CV__whole_seq = &whole_sequence;
00014 
00015 void CV_Slice__Initialize(void)
00016 {
00017     whole_sequence = CV_WHOLE_SEQ;
00018 }
00019 
00020 // Depth constants:
00021 int CV__depth_1u = IPL_DEPTH_1U;
00022 int CV__depth_8u = IPL_DEPTH_8U;
00023 int CV__depth_16u = IPL_DEPTH_16U;
00024 int CV__depth_8s = IPL_DEPTH_8S;
00025 int CV__depth_16s = IPL_DEPTH_16S;
00026 int CV__depth_32s = IPL_DEPTH_32S;
00027 int CV__depth_32f = IPL_DEPTH_32F;
00028 int CV__depth_64f = IPL_DEPTH_64F;
00029 
00030 int CV__load_image_any_color = CV_LOAD_IMAGE_ANYCOLOR;
00031 int CV__load_image_any_depth = CV_LOAD_IMAGE_ANYDEPTH;
00032 int CV__load_image_color = CV_LOAD_IMAGE_COLOR;
00033 int CV__load_image_gray_scale = CV_LOAD_IMAGE_GRAYSCALE;
00034 int CV__load_image_unchanged = CV_LOAD_IMAGE_UNCHANGED;
00035 int CV__window_auto_size = CV_WINDOW_AUTOSIZE;
00036 
00037 // Color space conversion codes:
00038 int CV__bgr_to_bgra = CV_BGR2BGRA;
00039 int CV__rgb_to_rgba = CV_RGB2RGBA;
00040 int CV__bgra_to_bgr = CV_BGRA2BGR;
00041 int CV__rgba_to_rgb = CV_RGBA2RGB;
00042 int CV__bgr_to_rgba = CV_BGR2RGBA;
00043 int CV__rgb_to_bgra = CV_RGB2BGRA;
00044 int CV__rgba_to_bgr = CV_RGBA2BGR;
00045 int CV__bgra_to_rgb = CV_BGRA2RGB;
00046 int CV__bgr_to_rgb = CV_BGR2RGB;
00047 int CV__rgb_to_bgr = CV_RGB2BGR;
00048 int CV__brga_to_rgba = CV_BGRA2RGBA;
00049 int CV__rgba_to_brga = CV_RGBA2BGRA;
00050 int CV__bgr_to_gray = CV_BGR2GRAY;
00051 int CV__rgb_to_gray = CV_RGB2GRAY;
00052 int CV__gray_to_brg = CV_GRAY2BGR;
00053 int CV__gray_to_rgb = CV_GRAY2RGB;
00054 int CV__gray_to_bgra = CV_GRAY2BGRA;
00055 int CV__gray_to_rgba = CV_GRAY2RGBA;
00056 int CV__brga_to_gray = CV_BGRA2GRAY;
00057 int CV__rgba_to_gray = CV_RGBA2GRAY;
00058 int CV__bgr_to_bgr565 = CV_BGR2BGR565;
00059 int CV__rgb_to_bgr565 = CV_RGB2BGR565;
00060 int CV__bgr565_to_bgr = CV_BGR5652BGR;
00061 int CV__bg4565_to_rgb = CV_BGR5652RGB;
00062 int CV__bgra_to_bgr565 = CV_BGRA2BGR565;
00063 int CV__rgba_to_bgr565 = CV_RGBA2BGR565;
00064 int CV__bgr565_to_bgra = CV_BGR5652BGRA;
00065 int CV__bgr565_to_rgba = CV_BGR5652RGBA;
00066 int CV__gray_to_bgr565 = CV_GRAY2BGR565;
00067 int CV__bgr565_to_gray =  CV_BGR5652GRAY;
00068 int CV__bgr_to_bgr555 = CV_BGR2BGR555;
00069 int CV__rgb_to_bgr555 = CV_RGB2BGR555;
00070 int CV__bgr555_to_bgr = CV_BGR5552BGR;
00071 int CV__bgr555_to_rgb = CV_BGR5552RGB;
00072 int CV__bgra_to_bgr555 = CV_BGRA2BGR555;
00073 int CV__rgba_to_bgr555 = CV_RGBA2BGR555;
00074 int CV__bgr555_to_bgra = CV_BGR5552BGRA;
00075 int CV__bgr555_to_rgba = CV_BGR5552RGBA;
00076 int CV__gray_to_bgr555 = CV_GRAY2BGR555;
00077 int CV__bgr555_to_gray = CV_BGR5552GRAY;
00078 int CV__bgr_to_xyz = CV_BGR2XYZ;
00079 int CV__rgb_to_xyz = CV_RGB2XYZ;
00080 int CV__xyz_to_bgr = CV_XYZ2BGR;
00081 int CV__xyz_to_rgb = CV_XYZ2RGB;
00082 int CV__bgr_to_ycrcb = CV_BGR2YCrCb;
00083 int CV__rgb_to_ycrcb = CV_RGB2YCrCb;
00084 int CV__ycrcb_to_bgr = CV_YCrCb2BGR;
00085 int CV__ycrcb_to_rgb = CV_YCrCb2RGB;
00086 int CV__bgr_to_hsv = CV_BGR2HSV;
00087 int CV__rgb_to_hsv = CV_RGB2HSV;
00088 int CV__bgr_to_lab = CV_BGR2Lab;
00089 int CV__rgb_to_lab = CV_RGB2Lab;
00090 int CV__bayerbg_to_bgr = CV_BayerBG2BGR;
00091 int CV__bayergb_to_bgr = CV_BayerGB2BGR;
00092 int CV__bayerrg_to_bgr = CV_BayerRG2BGR;
00093 int CV__bayergr_to_bgr = CV_BayerGR2BGR;
00094 int CV__bayerbg_to_rgb = CV_BayerBG2RGB;
00095 int CV__bayergb_to_rgb = CV_BayerGB2RGB;
00096 int CV__bayerrg_to_rgb = CV_BayerRG2RGB;
00097 int CV__bayergr_to_rgb = CV_BayerGR2RGB;
00098 int CV__bgr_to_luv = CV_BGR2Luv;
00099 int CV__rgb_to_luv = CV_RGB2Luv;
00100 int CV__bgr_to_hls = CV_BGR2HLS;
00101 int CV__rgb_to_hls = CV_RGB2HLS;
00102 int CV__hsv_to_bgr = CV_HSV2BGR;
00103 int CV__hsv_to_rgb = CV_HSV2RGB;
00104 int CV__lab_to_bgr = CV_Lab2BGR;
00105 int CV__lab_to_rgb = CV_Lab2RGB;
00106 int CV__luv_to_bgr = CV_Luv2BGR;
00107 int CV__luv_to_rgb = CV_Luv2RGB;
00108 int CV__hls_to_bgr = CV_HLS2BGR;
00109 int CV__hls_to_rgb = CV_HLS2RGB;
00110 
00111 int CV__adaptive_thresh_mean_c = CV_ADAPTIVE_THRESH_MEAN_C;
00112 int CV__adaptive_thresh_gaussian_c = CV_ADAPTIVE_THRESH_GAUSSIAN_C;
00113 int CV__thresh_binary = CV_THRESH_BINARY;
00114 int CV__thresh_binary_inv = CV_THRESH_BINARY_INV;
00115 
00116 // Types for Matrices and images:
00117 int CV__u8 = CV_8U;
00118 int CV__s8 = CV_8S;
00119 int CV__u16 = CV_16U;
00120 int CV__s16 = CV_16S;
00121 int CV__s32 = CV_32S;
00122 int CV__f32 = CV_32F;
00123 int CV__f64 = CV_64F;
00124 int CV__user_type = CV_USRTYPE1;
00125 
00126 int CV__u8c1 = CV_8UC1;
00127 int CV__u8c2 = CV_8UC2;
00128 int CV__u8c3 = CV_8UC3;
00129 int CV__u8c4 = CV_8UC4;
00130 
00131 int CV__s8c1 = CV_8SC1;
00132 int CV__s8c2 = CV_8SC2;
00133 int CV__s8c3 = CV_8SC3;
00134 int CV__s8c4 = CV_8SC4;
00135 
00136 int CV__u16c1 = CV_16UC1;
00137 int CV__u16c2 = CV_16UC2;
00138 int CV__u16c3 = CV_16UC3;
00139 int CV__u16c4 = CV_16UC4;
00140 
00141 int CV__s16c1 = CV_16SC1;
00142 int CV__s16c2 = CV_16SC2;
00143 int CV__s16c3 = CV_16SC3;
00144 int CV__s16c4 = CV_16SC4;
00145 
00146 int CV__s32c1 = CV_32SC1;
00147 int CV__s32c2 = CV_32SC2;
00148 int CV__s32c3 = CV_32SC3;
00149 int CV__s32c4 = CV_32SC4;
00150 
00151 int CV__f32c1 = CV_32FC1;
00152 int CV__f32c2 = CV_32FC2;
00153 int CV__f32c3 = CV_32FC3;
00154 int CV__f32c4 = CV_32FC4;
00155 
00156 int CV__f64c1 = CV_64FC1;
00157 int CV__f64c2 = CV_64FC2;
00158 int CV__f64c3 = CV_64FC3;
00159 int CV__f64c4 = CV_64FC4;
00160 
00161 int CV__auto_step = CV_AUTO_STEP;
00162 
00163 int CV__blur_no_scale = CV_BLUR_NO_SCALE;
00164 int CV__blur = CV_BLUR;
00165 int CV__gaussian = CV_GAUSSIAN;
00166 int CV__median = CV_MEDIAN;
00167 int CV__bilateral = CV_BILATERAL;
00168 
00169 // *CV* routines:
00170 
00171 void CV__draw_chessboard_corners(CV_Image image, CV_Size pattern_size,
00172   CV_Point2D32F_Vector corners, int count, bool pattern_was_found) {
00173     cvDrawChessboardCorners(image,
00174       *pattern_size, corners, count, pattern_was_found);
00175 }
00176 
00177 CV_Image CV__clone_image(CV_Image image) {
00178     return cvCloneImage(image);
00179 }
00180 
00181 //void
00182 //CV__calibrate_camera2(
00183 //  CV_Matrix object_points,
00184 //  CV_Matrix image_points,
00185 //  CV_Matrix point_counts,
00186 //  CV_Size image_size,
00187 //  CV_Matrix camera_matrix,
00188 //  CV_Matrix distortion_coefficients, 
00189 //  CV_Matrix rotation_vectors,
00190 //  CV_Matrix translation_vectors,
00191 //  int flags)
00192 //{
00193 //    cvCalibrateCamera2(object_points, image_points, point_counts,
00194 //      *image_size, camera_matrix, distortion_coefficients, rotation_vectors,
00195 //      translation_vectors, flags);
00196 //}
00197 
00198 int CV__find_chessboard_corners(CV_Image image, CV_Size pattern_size,
00199   CV_Point2D32F_Vector corners, int flags) {
00200     int corner_count;
00201     int result;
00202 
00203     result = cvFindChessboardCorners(image,
00204       *pattern_size, corners, &corner_count, flags);
00205     if (result != 0) {
00206         result = corner_count;
00207     }
00208     return result;
00209 }
00210 
00211 void CV__find_extrinsic_camera_params2(
00212   CV_Matrix object_points,
00213   CV_Matrix image_points,
00214   CV_Matrix camera,
00215   CV_Matrix distortion_coefficients,
00216   CV_Matrix rotation_vector,
00217   CV_Matrix translation_vector,
00218   int use_extrinsic_guess)
00219 {
00220   cvFindExtrinsicCameraParams2(object_points, image_points, camera,
00221     distortion_coefficients, rotation_vector, translation_vector,
00222     use_extrinsic_guess);
00223 }
00224 
00225 int CV__fourcc(char character1, char character2,
00226   char character3, char character4) {
00227     return CV_FOURCC(character1, character2, character3, character4);
00228 }
00229 
00230 int CV__gemm_a_t = CV_GEMM_A_T;
00231 int CV__gemm_b_t = CV_GEMM_B_T;
00232 int CV__gemm_c_t = CV_GEMM_C_T;
00233 
00234 void CV__gemm(CV_Matrix a, CV_Matrix b, double alpha, CV_Matrix c, double beta,
00235   CV_Matrix d,int transpose_a_b_c) {
00236     return cvGEMM(a, b, alpha, c, beta, d, transpose_a_b_c);
00237 }
00238 
00239 
00240 double CV__get_real_2d(CV_Matrix matrix, int row, int column) {
00241     return cvGetReal2D(matrix, row, column);
00242 }
00243 
00244 void CV__init_undistort_map(CV_Matrix camera_matrix, 
00245   CV_Matrix distortion_coefficients, CV_Matrix mapx, CV_Matrix mapy) {
00246     cvInitUndistortMap(camera_matrix, distortion_coefficients, mapx, mapy);
00247 }
00248 
00249 //CV_Matrix
00250 //CV__load(
00251 //  String file_name,
00252 //  CV_Memory_Storage storage,
00253 //  String name,
00254 //  String real_name)
00255 //{
00256 //    char *simple_file_name;
00257 //    char *simple_name;
00258 //    const char *simple_real_name;
00259 //
00260 //    simple_name = (char *)0;
00261 //    simple_real_name = (const char *)0;
00262 //    return cvLoad(file_name, storage, simple_name, &simple_real_name);
00263 //}
00264 
00265 void CV__release_image(CV_Image image) {
00266     cvReleaseImage(&image);
00267 }
00268 
00269 int CV__inter_linear = CV_INTER_LINEAR;
00270 int CV__warp_fill_outliers = CV_WARP_FILL_OUTLIERS;
00271 
00272 void CV__rodrigues2(
00273   CV_Matrix rotation_vector, CV_Matrix rotation_matrix, CV_Matrix jacobian) {
00274     cvRodrigues2(rotation_vector, rotation_matrix, jacobian);
00275 }
00276 
00277 void CV__set_identity(CV_Matrix matrix, CV_Scalar scalar) {
00278     cvSetIdentity(matrix, *scalar);
00279 }
00280 
00281 void CV__set_real_2d(
00282   CV_Matrix matrix, int row, int column, double value) {
00283     cvSetReal2D(matrix, row, column, value);
00284 }
00285 
00286 void CV__set_zero(CV_Matrix matrix) {
00287     cvSetZero(matrix);
00288 }
00289 
00290 int CV__round(double value) {
00291     return cvRound(value);
00292 }
00293 
00294 // Read the calibration file and generate the undistortion maps
00295 // in:
00296 //   calibrate_file_name   -  camera calibration file
00297 //   w h                   -  width and height of images to undistort
00298 // out:
00299 //   mapx, mapy,           - undistortion maps
00300 
00301 int CV__undistortion_setup(String_Const calibrate_file_name,
00302  int width, int height, CV_Image *mapx, CV_Image *mapy) {
00303     double fcx, fcy, ccx, ccy;
00304     double kc[4];
00305   
00306     // Open *calibrate_file_name*:
00307     File file = File__open(calibrate_file_name, "r");
00308     if (file == (File)0) {
00309         File__format(stderr, "Could not open \"%s\"\n", calibrate_file_name);
00310         return -1;
00311     }
00312 
00313     // Scan in the calibration values:
00314     //  format is fc - focal length, cc, principal point, kc distortion vector
00315     int x = fscanf(file, "fc %lf %lf cc %lf %lf kc %lf %lf %lf %lf", 
00316        &fcx, &fcy, &ccx, &ccy, &kc[0], &kc[1], &kc[2], &kc[3]);
00317     if (x != 8) {
00318         File__format(stderr, "Expected 8 parameters got %d\n", x);
00319         return -1;
00320     }
00321     File__close(file);
00322     
00323     // Create *intrisic* matrix:
00324     double intrinsic_vector[9] = {
00325         fcx,   0, ccx,
00326           0, fcy, ccy,
00327           0,   0,   1
00328     }; 
00329     CvMat intrinsic = cvMat(3, 3, CV_64FC1, intrinsic_vector);
00330     //printf("intrinsic matrix\n");
00331     //dumpMat(&intrinsic);
00332 
00333     // Create *distortion* matrix*:
00334     CvMat distortion = cvMat(1, 4, CV_64FC1, kc);
00335     //printf("distortion matrix\n");
00336     //dumpMat(&distortion);
00337 
00338     *mapx = cvCreateImage(cvSize(width, height), IPL_DEPTH_32F, 1);
00339     *mapy = cvCreateImage(cvSize(width, height), IPL_DEPTH_32F, 1);
00340     cvInitUndistortMap(&intrinsic, &distortion, *mapx, *mapy);
00341 
00342     return 0;
00343 }
00344 
00345 // *CV_Image* routines:
00346 
00347 void CV_Image__adaptive_threshold(CV_Image source_image,
00348   CV_Image destination_image, double maximum_value, int adaptive_method,
00349   int threshold_type, int block_size, double parameter1) {
00350     cvAdaptiveThreshold(source_image, destination_image, maximum_value,
00351       adaptive_method, threshold_type, block_size, parameter1);
00352 }
00353 
00354 void CV_Image__blob_draw(
00355   CV_Image image, int x, int y, CV_Scalar color) {
00356     // Draw a small cross at the indicated point.
00357     uchar red = cvRound(color->val[0]);
00358     uchar green = cvRound(color->val[1]);
00359     uchar blue = cvRound(color->val[2]);
00360     uchar *data = (uchar *)image->imageData;
00361     int width_step = image->widthStep;
00362 
00363     // Sanity check the values.
00364     if (x < 2 || y < 2 || x >= (image->width - 2) || y >= (image->height - 2)) {
00365         return;
00366     }
00367 
00368     // Draw away:
00369     for (int i = -2; i <= 2; i++) {
00370         for (int j = -2; j <= 2; j++) {
00371           uchar *pixel = &(data + width_step * (y + j))[(x + i) * 3];
00372           pixel[0] = red; pixel[1] = green; pixel[2] = blue;
00373         }
00374     }
00375 }
00376 
00377 CV_Image CV_Image__create(CV_Size size, unsigned int depth, unsigned int channels) {
00378     return cvCreateImage(*size, depth, channels);
00379 }
00380 
00381 int CV_Image__channels_get(CV_Image image) {
00382     return image->nChannels;
00383 }
00384 
00385 void CV_Image__convert_color(
00386  CV_Image source_image, CV_Image destination_image, int conversion_code) {
00387     cvCvtColor(source_image, destination_image, conversion_code);
00388 }
00389 
00390 void CV_Image__copy(
00391   CV_Image source_image, CV_Image destination_image, CV_Image mask) {
00392     cvCopy(source_image, destination_image, mask);
00393 }
00394 
00395 void CV_Image__cross_draw(
00396   CV_Image image, int x, int y, CV_Scalar color) {
00397     // Draw a small cross at the indicated point.
00398     uchar *pixel;
00399     uchar *pixel_lt;
00400     uchar *pixel_rt;
00401     uchar *pixel_up;
00402     uchar *pixel_dn;
00403     uchar red = cvRound(color->val[0]);
00404     uchar green = cvRound(color->val[1]);
00405     uchar blue = cvRound(color->val[2]);
00406     uchar *data = (uchar *)image->imageData;
00407     int width_step = image->widthStep;
00408 
00409     // Sanity check the values.
00410     if (x < 1 || y < 1 || x >= (image->width - 1) || y >= (image->height - 1)) {
00411         return;
00412     }
00413 
00414     // Get the pixels to be colored.
00415     pixel = &((data + width_step * y))[x * 3];
00416     pixel_lt = &((data + width_step * y))[(x - 1) * 3];
00417     pixel_rt = &((data + width_step * y))[(x + 1) * 3];
00418     pixel_up = &((data + width_step * (y - 1)))[x * 3];
00419     pixel_dn = &((data + width_step * (y + 1)))[x * 3];
00420 
00421     // Draw the cross.
00422     pixel[0] = red; pixel[1] = green; pixel[2] = blue;
00423     pixel_lt[0] = red; pixel_lt[1] = green; pixel_lt[2] = blue;
00424     pixel_rt[0] = red; pixel_rt[1] = green; pixel_rt[2] = blue;
00425     pixel_up[0] = red; pixel_up[1] = green; pixel_up[2] = blue;
00426     pixel_dn[0] = red; pixel_dn[1] = green; pixel_dn[2] = blue;
00427 }
00428 
00429 void CV_Image__draw_contours(CV_Image image, CV_Sequence contour,
00430   CV_Scalar external_color, CV_Scalar hole_color, int maximal_level,
00431   int thickness, int line_type, CV_Point offset) {
00432   cvDrawContours(image, contour, *external_color,
00433     *hole_color, maximal_level, thickness, line_type, *offset);
00434 }
00435 
00436 // {mode} constants:
00437 int CV__retr_external = CV_RETR_EXTERNAL;
00438 int CV__retr_list = CV_RETR_LIST;
00439 int CV__retr_ccomp = CV_RETR_CCOMP;
00440 int CV__retr_tree = CV_RETR_TREE;
00441 
00442 // {method} constants:
00443 int CV__chain_code = CV_CHAIN_CODE;
00444 int CV__chain_approx_none = CV_CHAIN_APPROX_NONE;
00445 int CV__chain_approx_simple = CV_CHAIN_APPROX_SIMPLE;
00446 int CV__chain_approx_tc89_l1 = CV_CHAIN_APPROX_TC89_L1;
00447 int CV__chain_approx_tc89_kcos = CV_CHAIN_APPROX_TC89_KCOS;
00448 int CV__chain_link_runs = CV_LINK_RUNS;
00449 
00450 int CV__calib_cb_adaptive_thresh = CV_CALIB_CB_ADAPTIVE_THRESH;
00451 int CV__calib_cb_normalize_image = CV_CALIB_CB_NORMALIZE_IMAGE;
00452 int CV__calib_cb_filter_quads = CV_CALIB_CB_FILTER_QUADS;
00453 
00454 CV_Sequence CV_Image__find_contours(CV_Image image, CV_Memory_Storage storage,
00455   int header_size, int mode, int method, CV_Point point) {
00456     int result;
00457     CV_Sequence contours;
00458 
00459     contours = (CV_Sequence)0;
00460     result = cvFindContours(image,
00461       storage, &contours, sizeof(CvContour), mode, method, *point);
00462     return contours;
00463 }  
00464 
00465 unsigned int CV_Image__depth_get(CV_Image image) {
00466     return image->depth;
00467 }
00468 
00469 unsigned int CV_Image__fetch3(
00470   CV_Image image, unsigned int x, unsigned int y, unsigned int channel) {
00471     unsigned char *pointer = cvPtr2D(image, y, x, (int *)0);
00472     return pointer[channel];
00473 }
00474 
00475 int CV_Image__gray_fetch(CV_Image image, int x, int y) {
00476     int result = -1;
00477     if (0 <= x && x < image->width && 0 <= y && y < image->height) {
00478         result =
00479           (int)(((uchar *)image->imageData + image->widthStep * y))[x];
00480     }
00481     return result;
00482 }
00483 
00484 void CV_Image__find_corner_sub_pix(CV_Image image, CV_Point2D32F_Vector corners,
00485   int count, CV_Size window, CV_Size zero_zone, CV_Term_Criteria criteria) {
00486     cvFindCornerSubPix(image, corners, count, *window, *zero_zone, *criteria);
00487 }
00488 
00489 void CV_Image__flip(CV_Image from_image, CV_Image to_image, int flip_code) {
00490     cvFlip(from_image, to_image, flip_code);
00491 }
00492 
00493 CV_Image CV_Image__header_create(
00494   CV_Size size, unsigned int depth, unsigned int channels) {
00495     return cvCreateImageHeader(*size, depth, channels);
00496 }
00497 
00498 int CV_Image__height_get(CV_Image image) {
00499     return image->height;
00500 }
00501 
00508 
00509 CV_Image CV_Image__pnm_read(String_Const file_name) {
00510     unsigned int size = String__size(file_name);
00511     assert (String__equal(file_name + size - 4, ".pnm"));
00512     CV_Image image = cvLoadImage(file_name, CV_LOAD_IMAGE_UNCHANGED);
00513     if (image == (CV_Image)0) {
00514         File__format(stderr, "Unable to open file '%s'\n", file_name);
00515         assert(0);
00516     }
00517     return image;
00518 }
00519 
00526 
00527 void CV_Image__pnm_write(CV_Image image, String_Const file_name) {
00528     unsigned int size = String__size(file_name);
00529     assert (String__equal(file_name + size - 4, ".pnm"));
00530     cvSaveImage(file_name, image, (int *)0);
00531 }
00532 
00533 void CV_Image__remap(CV_Image source_image, CV_Image destination_image,
00534   CV_Image map_x, CV_Image map_y, int flags, CV_Scalar fill_value) {
00535     cvRemap(source_image,
00536       destination_image, map_x, map_y, flags, *fill_value);
00537 }
00538 
00539 void CV_Image__smooth(CV_Image source_image, CV_Image destination_image,
00540   int smooth_type, int parameter1, int parameter2,
00541   double parameter3, double parameter4) {
00542     cvSmooth(source_image, destination_image, smooth_type, parameter1,
00543       parameter2, parameter3, parameter4);
00544 }
00545 
00546 void CV_Image__store3(
00547   CV_Image image, unsigned int x, unsigned int y, unsigned int channel, unsigned int value) {
00548     unsigned char *pointer = cvPtr2D(image, y, x, (int *)0);
00549     pointer[channel] = (unsigned char)value;
00550 }
00551 
00562 
00563 CV_Image CV_Image__tga_read(CV_Image image, String_Const tga_file_name) {
00564     // Open *tga_in_file*:
00565     File tga_in_file = File__open(tga_file_name, "rb");
00566     if (tga_in_file == (File)0) {
00567         File__format(stderr,
00568           "Unable to open '%s' for reading\n", tga_file_name);
00569         assert (0);
00570     }
00571 
00572     // Read .tga header from *tga_in_file*:
00573     File__byte_read(tga_in_file);                       // identsize
00574     File__byte_read(tga_in_file);                       // colourmaptype
00575     unsigned int image_type =
00576       File__byte_read(tga_in_file);                    // imagetype (3=>raw b&w)
00577     File__little_endian_short_read(tga_in_file);        // colourmapstart
00578     File__little_endian_short_read(tga_in_file);        // colourmaplength
00579     File__byte_read(tga_in_file);                       // colourmapbits
00580     File__little_endian_short_read(tga_in_file);        // xstart
00581     File__little_endian_short_read(tga_in_file);        // ystart
00582     unsigned int width =
00583       File__little_endian_short_read(tga_in_file);      // width
00584     unsigned int height =
00585       File__little_endian_short_read(tga_in_file);      // height
00586     unsigned int bpp = File__byte_read(tga_in_file);    // bits per pixel
00587     File__byte_read(tga_in_file);                       // descriptor
00588 
00589     // Compare {image_type}, {bpp}, {width} and {height} with {image}.
00590     if (image != (CV_Image)0 && (unsigned int)image->width == width &&
00591       (unsigned int)image->height == height && (unsigned int)image->depth == 8) {
00592         // {width}, {height}, and {depth} match {image}:
00593         unsigned int channels = (unsigned int)image->nChannels;
00594         if (image_type == 3 && channels == 1 && bpp == 8) {
00595             // We have a gray mode .tga match; do nothing:
00596         } else if (image_type == 2 && channels == 3 && bpp == 24) {
00597             // We have a color mode .tga file; do nothing:
00598         } else {
00599             // No match:
00600             CV__release_image(image);
00601             image = (CV_Image)0;
00602         }
00603     } else {
00604         CV__release_image(image);
00605         image = (CV_Image)0;
00606     }
00607     // If {image} is not equal to {null@CV_Image} we can reuse {image}:
00608 
00609     // Figure out whether .tga file is gray scale or color:
00610     bool gray_mode = (bool)0;
00611     if (image_type == 3 && bpp == 8) {
00612         gray_mode = (bool)1;
00613     } else if (image_type == 2 && bpp == 24) {
00614         // Color mode:
00615         gray_mode = (bool)0;
00616     } else {
00617         // Something else:
00618         File__format(stderr, "'%s' has image type=%d and bpp=%d\n",
00619           tga_file_name, image_type, bpp);
00620         assert (0);
00621     }
00622 
00623     // Allocate a new {image} if we need to:
00624     if (image == (CV_Image)0) {
00625         CV_Size size = CV_Size__create((int)width, (int)height);
00626         if (gray_mode) {
00627             image = CV_Image__create(size, 8, 1);
00628         } else {
00629             image = CV_Image__create(size, 8, 3);
00630         }
00631     }
00632 
00633     // Read the .tga data into {image}:
00634     for (unsigned int row = 0; row < height; row++) {
00635         unsigned int j = height - row - 1;
00636         for (unsigned int column = 0; column < width; column++) {
00637             unsigned int i = column;
00638             if (gray_mode) {
00639                 unsigned int gray = fgetc(tga_in_file);
00640                 CV_Image__store3(image, column, row, 0, gray);
00641             } else {
00642                 //unsigned int red = File__byte_read(tga_in_file);
00643                 //unsigned int green = File__byte_read(tga_in_file);
00644                 //unsigned int blue = File__byte_read(tga_in_file);
00645                 unsigned int red = fgetc(tga_in_file);
00646                 unsigned int green = fgetc(tga_in_file);
00647                 unsigned int blue = fgetc(tga_in_file);
00648                 unsigned char *pointer = cvPtr2D(image, row, column, (int *)0);
00649                 pointer[0] = red;
00650                 pointer[1] = green;
00651                 pointer[2] = blue;
00652                 //CV_Image__store3(image, i, j, 0, red);
00653                 //CV_Image__store3(image, i, j, 1, green);
00654                 //CV_Image__store3(image, i, j, 2, blue);
00655             }
00656         }
00657     }
00658 
00659     // Close {tga_in_file}:
00660     File__close(tga_in_file);
00661 
00662     return image;
00663 }
00664 
00671 
00672 void CV_Image__tga_write(CV_Image image, String_Const file_name) {
00673     unsigned int channels = (unsigned int)image->nChannels;
00674     unsigned int depth = (unsigned int)image->depth;
00675     unsigned int height = (unsigned int)image->height;
00676     unsigned int width = (unsigned int)image->width;
00677     assert (depth == 8);
00678 
00679     unsigned int bpp = 0;
00680     unsigned int image_type = 0;        // 2=>color; 3=>b&w:
00681     bool gray_mode = (bool)0;
00682     if (channels == 1) {
00683         // Gray scale:
00684         bpp = 8;
00685         gray_mode = (bool)1;
00686         image_type = 3;
00687     } else if (channels == 3) {
00688         // Color:
00689         bpp = 24;
00690         gray_mode = (bool)0;
00691         image_type = 2;
00692     } else {
00693         assert (0);
00694     }
00695 
00696     // Open {file_name} file for writing:
00697     File tga_out_file = File__open(file_name, "wb");
00698     if (tga_out_file == (File)0) {
00699         File__format(stderr, "Could not open '%s for writing.\n", file_name);
00700         assert (0);
00701     }
00702 
00703     // Write .tga header:
00704     File__byte_write(tga_out_file, 0);                  // identsize
00705     File__byte_write(tga_out_file, 0);                  // colourmaptype
00706     File__byte_write(tga_out_file, image_type);         // type (3=b&w)
00707     File__little_endian_short_write(tga_out_file, 0);   // colormapstart
00708     File__little_endian_short_write(tga_out_file, 0);   // colourmaplen
00709     File__byte_write(tga_out_file, 0);                  // colourmapbits
00710     File__little_endian_short_write(tga_out_file, 0);   // xstart
00711     File__little_endian_short_write(tga_out_file, 0);   // ystart
00712     File__little_endian_short_write(tga_out_file, width); // width
00713     File__little_endian_short_write(tga_out_file, height); //height
00714     File__byte_write(tga_out_file, bpp);                // bits/pixel
00715     File__byte_write(tga_out_file, 0);                  // descriptor
00716 
00717     // Write out the .tga file data:
00718     for (unsigned int row = 0; row < height; row++) {
00719         unsigned int j = height - row - 1;
00720         for (unsigned int column = 0; column < width; column++) {
00721             unsigned int i = column;
00722             if (gray_mode) {
00723                 unsigned int gray = CV_Image__fetch3(image, i, j, 0);
00724                 File__byte_write(tga_out_file, gray);
00725             } else {
00726                 unsigned int index = height - row - 1;
00727                 unsigned int red = CV_Image__fetch3(image, i, j, 0);
00728                 unsigned int green = CV_Image__fetch3(image, i, j, 1);
00729                 unsigned int blue = CV_Image__fetch3(image, i, j, 2);
00730                 File__byte_write(tga_out_file, red);
00731                 File__byte_write(tga_out_file, green);
00732                 File__byte_write(tga_out_file, blue);
00733             }
00734         }
00735     }
00736 
00737     // Close the .tga file:
00738     File__close(tga_out_file);
00739 }
00740 
00741 int CV_Image__width_get(CV_Image image) {
00742     return (unsigned int)image->width;
00743 }
00744 
00745 // *CV_Matrix* routines:
00746 
00747 int CV_Matrix__columns_get(CV_Matrix matrix) {
00748     return matrix->cols;
00749 }
00750 
00751 int CV_Matrix__rows_get(CV_Matrix matrix) {
00752     return matrix->rows;
00753 }
00754 
00755 void CV_Matrix__save(CV_Matrix matrix, const char * file_name) {
00756     CvAttrList attributes;
00757 
00758     attributes = cvAttrList((const char **)0, (CvAttrList *)0);
00759     cvSave(file_name,
00760       matrix, (const char *)0, (const char *)0, attributes);
00761 }
00762 
00763 // *CV_Memory_Storage* routines:
00764 
00765 void CV_Memory_Storage__clear(CV_Memory_Storage storage) {
00766     cvClearMemStorage(storage);
00767 }
00768 
00769 CV_Memory_Storage CV_Memory_Storage__create(int block_size) {
00770     return cvCreateMemStorage(block_size);
00771 }
00772 
00773 // *CV_Point* routines:
00774 
00775 CV_Point CV_Point__create(int x, int y) {
00776     unsigned int malloc_bytes = sizeof *((CV_Point)0);
00777     // (void)printf("CV_Point__create: malloc_bytes=%d\n", malloc_bytes);
00778     CV_Point point = (CV_Point) malloc(sizeof *((CV_Point *)0) );
00779 
00780     point->x = x;
00781     point->y = y;
00782     return point;
00783 }
00784 
00785 int CV_Point__x_get(CV_Point point) {
00786     return point->x;
00787 }
00788 
00789 void CV_Point__x_set(CV_Point point, int x) {
00790     point->x = x;
00791 }
00792 
00793 int CV_Point__y_get(CV_Point point) {
00794     return point->y;
00795 }
00796 
00797 void CV_Point__y_set(CV_Point point, int y) {
00798     point->y = y;
00799 }
00800 
00801 // *CV_Point2D32F* routines:
00802 
00803 CV_Point2D32F CV_Point2D32F__create(double x, double y) {
00804     unsigned int malloc_bytes = sizeof *((CV_Point2D32F)0);
00805     // (void)printf("CV_Point2D32F__create: malloc_bytes=%d\n",
00806     //     malloc_bytes);
00807     CV_Point2D32F point = (CV_Point2D32F)malloc(malloc_bytes);
00808 
00809     point->x = x;
00810     point->y = y;
00811     return point;
00812 }
00813 
00814 double CV_Point2D32F__x_get(CV_Point2D32F point) {
00815     return point->x;
00816 }
00817 
00818 void CV_Point2D32F__x_set(CV_Point2D32F point, double x) {
00819     point->x = x;
00820 }
00821 
00822 double CV_Point2D32F__y_get(CV_Point2D32F point) {
00823     return point->y;
00824 }
00825 
00826 void CV_Point2D32F__y_set(CV_Point2D32F point, double y) {
00827     point->y = y;
00828 }
00829 
00830 void CV_Point2D32F__point_set(CV_Point2D32F point2d32f, CV_Point point) {
00831     int x = CV_Point__x_get(point);
00832     int y = CV_Point__y_get(point);
00833     (void)CV_Point2D32F__x_set(point2d32f, (double)x);
00834     (void)CV_Point2D32F__y_set(point2d32f, (double)y);
00835 }
00836 
00837 // *CV_Point2D32F_Vector* routines:
00838 
00839 CV_Point2D32F_Vector CV_Point2D32F_Vector__create(unsigned int size) {
00840     unsigned int malloc_bytes = size * sizeof *((CV_Point2D32F)0);
00841     // (void)printf("CV_Point2D32F_Vector__create: size=%d malloc_bytes=%d\n",
00842     //   size, malloc_bytes);
00843     CV_Point2D32F vector = (CV_Point2D32F)malloc(malloc_bytes);
00844     unsigned int index;
00845 
00846     for (index = 0; index < size; index++) {
00847         vector[index].x = 0.0;
00848         vector[index].y = 0.0;
00849     }
00850     return vector;
00851 }
00852 
00853 CV_Point2D32F CV_Point2D32F_Vector__fetch1(
00854   CV_Point2D32F_Vector vector,  unsigned int index) {
00855     return &vector[index];
00856 }
00857 
00858 // CV_Scalar *routines*:
00859 
00860 CV_Scalar CV_Scalar__create(
00861   double value0, double value1, double value2, double value3) {
00862     CV_Scalar scalar = Memory__new(CV_Scalar, "CV_Scalar__create");
00863     scalar->val[0] = value0;
00864     scalar->val[1] = value1;
00865     scalar->val[2] = value2;
00866     scalar->val[3] = value3;
00867     return scalar;
00868 }
00869 
00870 void CV_Scalar__free(CV_Scalar cv_scalar) {
00871     Memory__free((Memory)cv_scalar);
00872 }
00873 
00874 // This routine will return a {CV_Scalar} that encodes {red}, {green},
00875 // and {blue} as a color.
00876 
00877 CV_Scalar CV_Scalar__rgb(double red, double green, double blue) {
00878     return CV_Scalar__create(blue, green, red, 0.0);
00879 }
00880 
00881 // *CV_Sequence* routines:
00882 
00883 int CV__poly_approx_dp = CV_POLY_APPROX_DP;
00884 
00885 CV_Sequence CV_Sequence__approximate_polygon(CV_Sequence contour,
00886   int header_size, CV_Memory_Storage storage, int method,
00887   int parameter1, double parameter2) {
00888     //(void)printf("sizeof=%d method=%d param1=%d\n",
00889     //  sizeof(CvContour), method, parameter1);
00890     return cvApproxPoly(contour,
00891       sizeof(CvContour), storage, method, parameter1, parameter2);
00892 }
00893 
00894 double CV_Sequence__arc_length(
00895   CV_Sequence contour, CV_Slice slice, int is_closed) {
00896     return cvArcLength(contour, *slice, is_closed);
00897 }    
00898 
00899 bool CV_Sequence__check_contour_convexity(CV_Sequence contour) {
00900     return (bool)(cvCheckContourConvexity(contour) ? 1 : 0);
00901 }
00902 
00903 double CV_Sequence__contour_area(
00904   CV_Sequence contour, CV_Slice slice, int oriented) {
00905     return cvContourArea(contour, *slice, oriented);
00906 }
00907 
00908 CV_Sequence CV_Sequence__next_get(CV_Sequence sequence) {
00909     return sequence->h_next;
00910 }
00911 
00912 CV_Point CV_Sequence__point_fetch1(CV_Sequence sequence, unsigned int index) {
00913     return (CV_Point)cvGetSeqElem(sequence, index);
00914 }
00915 
00916 int CV_Sequence__total_get(CV_Sequence sequence) {
00917     return sequence->total;
00918 }
00919 
00920 // *CV_Size* routines:
00921 
00922 CV_Size CV_Size__create(int width, int height) {
00923     CV_Size size = Memory__new(CV_Size, "CV_Size__create");
00924     size->width = (int)width;
00925     size->height = (int)height;
00926     return size;
00927 }
00928 
00929 extern void CV_Size__free(CV_Size cv_size) {
00930     Memory__free((Memory)cv_size);
00931 }
00932 
00933 // *CV_Slice* routines:
00934 CV_Slice CV_Slice__create(int start_index, int end_index) {
00935     unsigned int malloc_bytes = sizeof *((CV_Slice)0);
00936     // (void)printf("CV_Slice__create: malloc_bytes=%d\n", malloc_bytes);
00937     CV_Slice slice = (CV_Slice)malloc(malloc_bytes);
00938 
00939     slice->start_index = start_index;
00940     slice->end_index = end_index;
00941     return slice;
00942 }
00943 
00944 // *CV_Term* rouitines:
00945 int CV__term_criteria_iterations = CV_TERMCRIT_ITER;
00946 int CV__term_criteria_eps = CV_TERMCRIT_EPS;
00947 
00948 CV_Term_Criteria CV_Term_Criteria__create(
00949   int type, int maximum_iterations, double epsilon) {
00950     unsigned int malloc_bytes = sizeof *((CV_Term_Criteria)0);
00951     // (void)printf("CV_Term_Criteria__create: malloc_bytes=%d\n",
00952     //   malloc_bytes);
00953     CV_Term_Criteria term_criteria = (CV_Term_Criteria)malloc(malloc_bytes);
00954 
00955     term_criteria->type = type;
00956     term_criteria->max_iter = maximum_iterations;
00957     term_criteria->epsilon = epsilon;
00958     return term_criteria;
00959 }
00960 


fiducial_lib
Author(s): Wayne Gramlich
autogenerated on Thu Jun 6 2019 18:08:04