5 #include <opencv/highgui.h> 173 cvDrawChessboardCorners(image,
174 *pattern_size, corners, count, pattern_was_found);
178 return cvCloneImage(image);
203 result = cvFindChessboardCorners(image,
204 *pattern_size, corners, &corner_count, flags);
206 result = corner_count;
218 int use_extrinsic_guess)
220 cvFindExtrinsicCameraParams2(object_points, image_points, camera,
221 distortion_coefficients, rotation_vector, translation_vector,
222 use_extrinsic_guess);
226 char character3,
char character4) {
227 return CV_FOURCC(character1, character2, character3, character4);
236 return cvGEMM(a, b, alpha, c, beta, d, transpose_a_b_c);
241 return cvGetReal2D(matrix, row, column);
246 cvInitUndistortMap(camera_matrix, distortion_coefficients, mapx, mapy);
266 cvReleaseImage(&image);
274 cvRodrigues2(rotation_vector, rotation_matrix, jacobian);
278 cvSetIdentity(matrix, *scalar);
282 CV_Matrix matrix,
int row,
int column,
double value) {
283 cvSetReal2D(matrix, row, column, value);
291 return cvRound(value);
303 double fcx, fcy, ccx, ccy;
308 if (file == (
File)0) {
309 File__format(stderr,
"Could not open \"%s\"\n", calibrate_file_name);
315 int x = fscanf(file,
"fc %lf %lf cc %lf %lf kc %lf %lf %lf %lf",
316 &fcx, &fcy, &ccx, &ccy, &kc[0], &kc[1], &kc[2], &kc[3]);
318 File__format(stderr,
"Expected 8 parameters got %d\n", x);
324 double intrinsic_vector[9] = {
329 CvMat intrinsic = cvMat(3, 3, CV_64FC1, intrinsic_vector);
334 CvMat distortion = cvMat(1, 4, CV_64FC1, kc);
338 *mapx = cvCreateImage(cvSize(width, height), IPL_DEPTH_32F, 1);
339 *mapy = cvCreateImage(cvSize(width, height), IPL_DEPTH_32F, 1);
340 cvInitUndistortMap(&intrinsic, &distortion, *mapx, *mapy);
348 CV_Image destination_image,
double maximum_value,
int adaptive_method,
349 int threshold_type,
int block_size,
double parameter1) {
350 cvAdaptiveThreshold(source_image, destination_image, maximum_value,
351 adaptive_method, threshold_type, block_size, parameter1);
357 uchar red = cvRound(color->val[0]);
358 uchar green = cvRound(color->val[1]);
359 uchar blue = cvRound(color->val[2]);
360 uchar *data = (uchar *)image->imageData;
361 int width_step = image->widthStep;
364 if (x < 2 || y < 2 || x >= (image->width - 2) || y >= (image->height - 2)) {
369 for (
int i = -2; i <= 2; i++) {
370 for (
int j = -2; j <= 2; j++) {
371 uchar *pixel = &(data + width_step * (y + j))[(x + i) * 3];
372 pixel[0] = red; pixel[1] = green; pixel[2] = blue;
378 return cvCreateImage(*size, depth, channels);
382 return image->nChannels;
387 cvCvtColor(source_image, destination_image, conversion_code);
392 cvCopy(source_image, destination_image, mask);
403 uchar red = cvRound(color->val[0]);
404 uchar green = cvRound(color->val[1]);
405 uchar blue = cvRound(color->val[2]);
406 uchar *data = (uchar *)image->imageData;
407 int width_step = image->widthStep;
410 if (x < 1 || y < 1 || x >= (image->width - 1) || y >= (image->height - 1)) {
415 pixel = &((data + width_step * y))[x * 3];
416 pixel_lt = &((data + width_step * y))[(x - 1) * 3];
417 pixel_rt = &((data + width_step * y))[(x + 1) * 3];
418 pixel_up = &((data + width_step * (y - 1)))[x * 3];
419 pixel_dn = &((data + width_step * (y + 1)))[x * 3];
422 pixel[0] = red; pixel[1] = green; pixel[2] = blue;
423 pixel_lt[0] = red; pixel_lt[1] = green; pixel_lt[2] = blue;
424 pixel_rt[0] = red; pixel_rt[1] = green; pixel_rt[2] = blue;
425 pixel_up[0] = red; pixel_up[1] = green; pixel_up[2] = blue;
426 pixel_dn[0] = red; pixel_dn[1] = green; pixel_dn[2] = blue;
431 int thickness,
int line_type,
CV_Point offset) {
432 cvDrawContours(image, contour, *external_color,
433 *hole_color, maximal_level, thickness, line_type, *offset);
455 int header_size,
int mode,
int method,
CV_Point point) {
460 result = cvFindContours(image,
461 storage, &contours,
sizeof(CvContour), mode, method, *point);
470 CV_Image image,
unsigned int x,
unsigned int y,
unsigned int channel) {
471 unsigned char *pointer = cvPtr2D(image, y, x, (
int *)0);
472 return pointer[channel];
477 if (0 <= x && x < image->width && 0 <= y && y < image->height) {
479 (int)(((uchar *)image->imageData + image->widthStep * y))[x];
486 cvFindCornerSubPix(image, corners, count, *window, *zero_zone, *criteria);
490 cvFlip(from_image, to_image, flip_code);
494 CV_Size size,
unsigned int depth,
unsigned int channels) {
495 return cvCreateImageHeader(*size, depth, channels);
499 return image->height;
512 CV_Image image = cvLoadImage(file_name, CV_LOAD_IMAGE_UNCHANGED);
514 File__format(stderr,
"Unable to open file '%s'\n", file_name);
530 cvSaveImage(file_name, image, (
int *)0);
535 cvRemap(source_image,
536 destination_image, map_x, map_y, flags, *fill_value);
540 int smooth_type,
int parameter1,
int parameter2,
541 double parameter3,
double parameter4) {
542 cvSmooth(source_image, destination_image, smooth_type, parameter1,
543 parameter2, parameter3, parameter4);
547 CV_Image image,
unsigned int x,
unsigned int y,
unsigned int channel,
unsigned int value) {
548 unsigned char *pointer = cvPtr2D(image, y, x, (
int *)0);
549 pointer[channel] = (
unsigned char)value;
566 if (tga_in_file == (
File)0) {
568 "Unable to open '%s' for reading\n", tga_file_name);
575 unsigned int image_type =
584 unsigned int height =
590 if (image != (
CV_Image)0 && (
unsigned int)image->width == width &&
591 (
unsigned int)image->height == height && (
unsigned int)image->depth == 8) {
593 unsigned int channels = (
unsigned int)image->nChannels;
594 if (image_type == 3 && channels == 1 && bpp == 8) {
596 }
else if (image_type == 2 && channels == 3 && bpp == 24) {
610 bool gray_mode = (bool)0;
611 if (image_type == 3 && bpp == 8) {
613 }
else if (image_type == 2 && bpp == 24) {
618 File__format(stderr,
"'%s' has image type=%d and bpp=%d\n",
619 tga_file_name, image_type, bpp);
634 for (
unsigned int row = 0; row < height; row++) {
635 unsigned int j = height - row - 1;
636 for (
unsigned int column = 0; column < width; column++) {
637 unsigned int i = column;
639 unsigned int gray = fgetc(tga_in_file);
645 unsigned int red = fgetc(tga_in_file);
646 unsigned int green = fgetc(tga_in_file);
647 unsigned int blue = fgetc(tga_in_file);
648 unsigned char *pointer = cvPtr2D(image, row, column, (
int *)0);
673 unsigned int channels = (
unsigned int)image->nChannels;
674 unsigned int depth = (
unsigned int)image->depth;
675 unsigned int height = (
unsigned int)image->height;
676 unsigned int width = (
unsigned int)image->width;
679 unsigned int bpp = 0;
680 unsigned int image_type = 0;
681 bool gray_mode = (bool)0;
687 }
else if (channels == 3) {
698 if (tga_out_file == (
File)0) {
699 File__format(stderr,
"Could not open '%s for writing.\n", file_name);
718 for (
unsigned int row = 0; row < height; row++) {
719 unsigned int j = height - row - 1;
720 for (
unsigned int column = 0; column < width; column++) {
721 unsigned int i = column;
726 unsigned int index = height - row - 1;
742 return (
unsigned int)image->width;
756 CvAttrList attributes;
758 attributes = cvAttrList((
const char **)0, (CvAttrList *)0);
760 matrix, (
const char *)0, (
const char *)0, attributes);
766 cvClearMemStorage(storage);
770 return cvCreateMemStorage(block_size);
776 unsigned int malloc_bytes =
sizeof *((
CV_Point)0);
840 unsigned int malloc_bytes = size *
sizeof *((
CV_Point2D32F)0);
846 for (index = 0; index < size; index++) {
847 vector[
index].x = 0.0;
848 vector[
index].y = 0.0;
855 return &vector[
index];
861 double value0,
double value1,
double value2,
double value3) {
863 scalar->val[0] = value0;
864 scalar->val[1] = value1;
865 scalar->val[2] = value2;
866 scalar->val[3] = value3;
887 int parameter1,
double parameter2) {
890 return cvApproxPoly(contour,
891 sizeof(CvContour), storage, method, parameter1, parameter2);
896 return cvArcLength(contour, *slice, is_closed);
900 return (
bool)(cvCheckContourConvexity(contour) ? 1 : 0);
905 return cvContourArea(contour, *slice, oriented);
909 return sequence->h_next;
913 return (
CV_Point)cvGetSeqElem(sequence, index);
917 return sequence->total;
924 size->width = (int)width;
925 size->height = (int)height;
935 unsigned int malloc_bytes =
sizeof *((
CV_Slice)0);
939 slice->start_index = start_index;
940 slice->end_index = end_index;
949 int type,
int maximum_iterations,
double epsilon) {
955 term_criteria->type = type;
956 term_criteria->max_iter = maximum_iterations;
957 term_criteria->epsilon = epsilon;
958 return term_criteria;
void CV_Point2D32F__x_set(CV_Point2D32F point, double x)
void CV__init_undistort_map(CV_Matrix camera_matrix, CV_Matrix distortion_coefficients, CV_Matrix mapx, CV_Matrix mapy)
void File__byte_write(File file, unsigned int byte)
Write byte ot file.
CvTermCriteria * CV_Term_Criteria
int CV__fourcc(char character1, char character2, char character3, char character4)
CV_Memory_Storage CV_Memory_Storage__create(int block_size)
int CV_Matrix__rows_get(CV_Matrix matrix)
CV_Image CV_Image__tga_read(CV_Image image, String_Const tga_file_name)
Read in a .tga file.
CV_Image CV__clone_image(CV_Image image)
void CV_Image__copy(CV_Image source_image, CV_Image destination_image, CV_Image mask)
int CV_Sequence__total_get(CV_Sequence sequence)
void Memory__free(Memory memory)
Releases the storage associated with memory.
unsigned int CV_Image__depth_get(CV_Image image)
void File__close(File file)
Closes file.
void CV_Memory_Storage__clear(CV_Memory_Storage storage)
int CV__thresh_binary_inv
double CV_Point2D32F__y_get(CV_Point2D32F point)
void CV__gemm(CV_Matrix a, CV_Matrix b, double alpha, CV_Matrix c, double beta, CV_Matrix d, int transpose_a_b_c)
void CV_Image__smooth(CV_Image source_image, CV_Image destination_image, int smooth_type, int parameter1, int parameter2, double parameter3, double parameter4)
int CV__load_image_unchanged
void CV__set_zero(CV_Matrix matrix)
unsigned int File__little_endian_short_read(File file)
Read a little endian short (16-bits) from file.
CV_Point2D32F CV_Point2D32F__create(double x, double y)
int CV__load_image_any_depth
int CV_Point__y_get(CV_Point point)
void CV_Matrix__save(CV_Matrix matrix, const char *file_name)
int CV__adaptive_thresh_mean_c
int CV_Point__x_get(CV_Point point)
void CV_Point2D32F__point_set(CV_Point2D32F point2d32f, CV_Point point)
void CV__set_identity(CV_Matrix matrix, CV_Scalar scalar)
CvPoint2D32f * CV_Point2D32F
FILE * File
FILE is a file I/O object.
CV_Sequence CV_Sequence__approximate_polygon(CV_Sequence contour, int header_size, CV_Memory_Storage storage, int method, int parameter1, double parameter2)
void CV_Image__find_corner_sub_pix(CV_Image image, CV_Point2D32F_Vector corners, int count, CV_Size window, CV_Size zero_zone, CV_Term_Criteria criteria)
void CV_Image__tga_write(CV_Image image, String_Const file_name)
Write image out to file_name in .tga format.
CV_Sequence CV_Image__find_contours(CV_Image image, CV_Memory_Storage storage, int header_size, int mode, int method, CV_Point point)
int CV__chain_approx_tc89_kcos
CV_Term_Criteria CV_Term_Criteria__create(int type, int maximum_iterations, double epsilon)
CV_Image CV_Image__pnm_read(String_Const file_name)
Reads in a CV_Image in from the .pnm file named file_name.
void CV_Slice__Initialize(void)
void CV_Scalar__free(CV_Scalar cv_scalar)
int CV__load_image_gray_scale
CvPoint2D32f * CV_Point2D32F_Vector
int CV__term_criteria_iterations
int CV_Image__width_get(CV_Image image)
int CV__calib_cb_adaptive_thresh
CvMemStorage * CV_Memory_Storage
#define Memory__new(Type, from)
Allocate a Type object from the heap.
void File__little_endian_short_write(File file, unsigned int xshort)
Write 16-bit xshort to file in little endian format.
void File__format(File file, String_Const format,...)
will write format out to file with all patterns that start with "%" replaced by formatted versions of...
CV_Image CV_Image__create(CV_Size size, unsigned int depth, unsigned int channels)
CV_Point2D32F CV_Point2D32F_Vector__fetch1(CV_Point2D32F_Vector vector, unsigned int index)
unsigned int File__byte_read(File file)
Read a byte from file.
CV_Point CV_Sequence__point_fetch1(CV_Sequence sequence, unsigned int index)
void CV_Image__blob_draw(CV_Image image, int x, int y, CV_Scalar color)
CV_Slice CV_Slice__create(int start_index, int end_index)
CV_Scalar CV_Scalar__rgb(double red, double green, double blue)
void CV_Image__adaptive_threshold(CV_Image source_image, CV_Image destination_image, double maximum_value, int adaptive_method, int threshold_type, int block_size, double parameter1)
double CV__get_real_2d(CV_Matrix matrix, int row, int column)
void CV_Image__remap(CV_Image source_image, CV_Image destination_image, CV_Image map_x, CV_Image map_y, int flags, CV_Scalar fill_value)
int CV_Image__gray_fetch(CV_Image image, int x, int y)
int CV_Image__height_get(CV_Image image)
void CV_Image__convert_color(CV_Image source_image, CV_Image destination_image, int conversion_code)
bool CV_Sequence__check_contour_convexity(CV_Sequence contour)
int CV_Matrix__columns_get(CV_Matrix matrix)
void CV__find_extrinsic_camera_params2(CV_Matrix object_points, CV_Matrix image_points, CV_Matrix camera, CV_Matrix distortion_coefficients, CV_Matrix rotation_vector, CV_Matrix translation_vector, int use_extrinsic_guess)
int CV__round(double value)
int CV__term_criteria_eps
int CV__warp_fill_outliers
CV_Point CV_Point__create(int x, int y)
int CV__chain_approx_none
int CV__load_image_any_color
void * Memory
Memory is a pointer to memory.
int CV__calib_cb_normalize_image
CV_Sequence CV_Sequence__next_get(CV_Sequence sequence)
int CV__chain_approx_simple
void CV_Image__store3(CV_Image image, unsigned int x, unsigned int y, unsigned int channel, unsigned int value)
File File__open(String_Const file_name, String_Const flags)
will open file_name using flags to specify read/write options.
void CV__draw_chessboard_corners(CV_Image image, CV_Size pattern_size, CV_Point2D32F_Vector corners, int count, bool pattern_was_found)
void CV_Point2D32F__y_set(CV_Point2D32F point, double y)
int CV__adaptive_thresh_gaussian_c
CV_Point2D32F_Vector CV_Point2D32F_Vector__create(unsigned int size)
int CV__find_chessboard_corners(CV_Image image, CV_Size pattern_size, CV_Point2D32F_Vector corners, int flags)
double CV_Sequence__arc_length(CV_Sequence contour, CV_Slice slice, int is_closed)
CV_Size CV_Size__create(int width, int height)
int CV__chain_approx_tc89_l1
void CV_Size__free(CV_Size cv_size)
const char * String_Const
double CV_Sequence__contour_area(CV_Sequence contour, CV_Slice slice, int oriented)
void CV_Image__cross_draw(CV_Image image, int x, int y, CV_Scalar color)
unsigned int CV_Image__fetch3(CV_Image image, unsigned int x, unsigned int y, unsigned int channel)
int CV__calib_cb_filter_quads
CV_Image CV_Image__header_create(CV_Size size, unsigned int depth, unsigned int channels)
CV_Scalar CV_Scalar__create(double value0, double value1, double value2, double value3)
void CV_Image__pnm_write(CV_Image image, String_Const file_name)
Writes image out to .pnm file named file_name.
void CV__rodrigues2(CV_Matrix rotation_vector, CV_Matrix rotation_matrix, CV_Matrix jacobian)
void CV_Image__draw_contours(CV_Image image, CV_Sequence contour, CV_Scalar external_color, CV_Scalar hole_color, int maximal_level, int thickness, int line_type, CV_Point offset)
double CV_Point2D32F__x_get(CV_Point2D32F point)
unsigned int String__size(String_Const string)
Returns the size of string.
int CV__undistortion_setup(String_Const calibrate_file_name, int width, int height, CV_Image *mapx, CV_Image *mapy)
void CV_Point__y_set(CV_Point point, int y)
bool String__equal(String_Const string1, String_Const string2)
Returns true if string1 equals string2.
static CvSlice whole_sequence
void CV__set_real_2d(CV_Matrix matrix, int row, int column, double value)
void CV_Point__x_set(CV_Point point, int x)
int CV_Image__channels_get(CV_Image image)
void CV__release_image(CV_Image image)
void CV_Image__flip(CV_Image from_image, CV_Image to_image, int flip_code)