Fiducials.cpp
Go to the documentation of this file.
1 // Copyright (c) 2013-2014 by Wayne C. Gramlich. All rights reserved.
2 
3 #include <assert.h>
4 #include <sys/time.h>
5 #include <angles/angles.h>
6 
7 #include <opencv2/highgui/highgui_c.h>
8 
9 #include "CRC.hpp"
10 #include "CV.hpp"
11 #include "File.hpp"
12 #include "FEC.hpp"
13 #include "Fiducials.hpp"
14 #include "String.hpp"
15 #include "Location.hpp"
16 
17 // Introduction:
18 //
19 // This code body takes a camera image that contains one or more fiducial
20 // tag images and computes an estimated location and orientation for the
21 // image camera. This computation is done in conjunction with a map that
22 // contains the best estimate of the locations of each of the fiducial tags.
23 // In short:
24 //
25 // Image_Location = F(Image, Map)
26 //
27 // To further complicate things, in fact, the Map is updated as
28 // side effect of computing the current location. In the literature,
29 // this is call SLAM, for Simultaneous Localization And Mapping.
30 // Thus, what is really going on is:
31 //
32 // (Image_Location, Map') = F(Image, Map)
33 //
34 // where Map' is the updated map.
35 //
36 // Despite the fact that the map is being updated, it best to treat the
37 // localization computation different from the Map updating computation.
38 // Thus, what is really going on is:
39 //
40 // Image_Location = F(Image, Map)
41 //
42 // Map' = G(Image, Map)
43 //
44 // where F is the localization function, and G is the map update function.
45 //
46 // The sections below are entitled:
47 //
48 // * Tag Geometry
49 // * Coordinate Systems
50 // * Map Organization
51 // * Image Tags
52 // * Localization Computation
53 // * Fusing with Dead Reckoning
54 // * Mapping into Robot Coordinates
55 // * Coordinate Space Transforms
56 //
57 // Tag Geometry:
58 //
59 // A tag consists of a 12 x 12 matrix of bits that encodes 64-bits of
60 // information in an 8 x 8 data matrix. The outermost square of the matrix
61 // is set to zeros (white squares) and the next level in is 1's
62 // (black squares). When viewed in an upright form printed on paper
63 // it looks as follows (-- = zero, XX = one, ## = bit number):
64 //
65 // -- -- -- -- -- -- -- -- -- -- -- --
66 // -- XX XX XX XX XX XX XX XX XX XX --
67 // -- XX 56 57 58 59 60 61 62 63 XX --
68 // -- XX 48 49 50 51 52 53 54 55 XX --
69 // -- XX 40 41 42 43 44 45 45 47 XX --
70 // -- XX 32 33 34 35 36 37 38 39 XX --
71 // -- XX 24 25 26 27 28 29 30 31 XX --
72 // -- XX 16 17 18 19 20 21 22 23 XX --
73 // -- XX 08 09 10 11 12 13 14 15 XX --
74 // -- XX 00 01 02 03 04 05 06 07 XX --
75 // -- XX XX XX XX XX XX XX XX XX XX --
76 // -- -- -- -- -- -- -- -- -- -- -- --
77 //
78 // Coordinate Systems:
79 //
80 // When it comes to performing the image analysis of a picture to
81 // compute image camera location and twist there are three coordinate
82 // systems to consider -- the floor, camera, and robot coordinate systems:
83 //
84 // - The floor coordinate system is a right handed cartesian
85 // coordinate system where one point on the floor is the
86 // origin. The X and Y axes are separated by a 90 degree
87 // angle and X axis can be oriented to aligned with either a
88 // building feature or an east-west line of latitude or
89 // whatever the user chooses. Conceptually, the floor is
90 // viewed from the top looking down. As long as all length
91 // measurements are performed using the same units, the
92 // choice of length unit does not actually matter (e.g.
93 // meter, centimeter, millimeter, inch, foot, etc.)
94 //
95 // - The image coordinate system is another right handed cartesian
96 // coordinate system that is used to locate the individual
97 // pixels in the image. The image is one of the common image
98 // format sizes (320 x 240, 640 x 480, etc.) For this system,
99 // the origin is selected to be the lower left pixel of the
100 // image. For 640 x 480 image, the lower left coordinate is
101 // (0, 0) and the upper right pixel coordinate is (639, 479).
102 //
103 // While most computer imaging packages (e.g. OpenCV) typically
104 // use a left-handed coordinate system where the origin is in
105 // the upper left, we will apply a transformation that causes
106 // the origin to be placed in the lower left. All distances are
107 // measured in units of pixels. The reason for using a right
108 // handed coordinate system is because trigonometric functions
109 // are implicitly right-handed.
110 //
111 // - The robot coordinate system is another right handed cartesian
112 // coordinate system where the origin is located in the center
113 // between the two drive wheels. The X axis of the robot
114 // coordinate system goes through the front of the robot.
115 // Realistically, the robot coordinate system is not part
116 // of the algorithms, instead this coordinate system is called
117 // out just to point out that it is there.
118 //
119 // Map Organization:
120 //
121 // Conceptually there a bunch of square fiducial tags (hereafter called
122 // just tags) scattered on the floor. (Yes, we know they are actually
123 // on the ceiling, we'll deal with that detail later.) There is a map
124 // that records for each tag, the following information in an ordered
125 // quintuple:
126 //
127 // (mtid, mtx, mty, mttw, mtdiag)
128 //
129 // where:
130 //
131 // mtid (Map Tag IDentifier) is the tag identifier (a number between
132 // 0 and 2^16-1),
133 // mtx (Map Tag X) is the x coordinate of the tag center in
134 // floor coordinates,
135 // mty (Map Tag Y) is the y coordinate of the tag center in
136 // floor coordinates,
137 // mttw (Map Tag TWist) is the angle (twist) of the bottom
138 // tag edge and the floor X axis, and
139 // mtdiag (Map Tag DIAGonal) is the length of a tag diagonal
140 // (both diagonals of a square have the same length) in
141 // in floor coordinates.
142 //
143 // Eventually, the quintuple should probably be upgraded to 1) an
144 // identifier, 2) an X/Y/Z location and 3) a W/X/Y/Z quaternion of
145 // for the tag orientation. That will come later. For now we will
146 // just use the quintuple.
147 //
148 // Conceptually, the floor is printed out on a large sheet of paper
149 // with all tags present. The camera image is printed out on a piece
150 // of translucent material (e.g. acetate) with the same dimensions
151 // as the floor sheet. This translucent image is placed on the floor
152 // sheet and moved around until the image tag(s) align with the
153 // corresponding tag(s) on the floor sheet. The center of translucent
154 // image is now sitting directly on top of the image location on the
155 // floor sheet. The amount of "twist" on the image relate to the
156 // floor coordinate system complete the location computation.
157 // Hopefully, this mental image of what we are trying to accomplish
158 // will help as you wade through the math below.
159 //
160 // Conceptually, the camera is going to be placed a fixed distance
161 // above the floor and take an image of rectangular area of the floor.
162 // For each tag in the image, the image processing algorithm
163 // computes the following:
164 //
165 // (camx, camy, camtw)
166 //
167 // where:
168 //
169 // camx (CAMera X) is the camera center X coordinate in the
170 // floor coordinate system,
171 // camy (CAMera Y) is the camera center Y coordinate in the
172 // floor coordinate system, and
173 // camtw (CAMera TWist) is the angle (twist) of the rectangle bottom
174 // tag edge with respect to the floor coordinate system X axis.
175 //
176 // If there are multiple tags present in the image, there will be
177 // multiple (camx, camy, camtw) triples computed. These triples
178 // should all be fairly close to one another. There is a final
179 // fusion step that fuses them all together into a single result.
180 //
181 // Image Tags:
182 //
183 // In each image there may be zero, one or more visible tags. If
184 // there are zero tags present, there is nothing to work with and
185 // the camera location can not be computed. When there are one or
186 // more tags, we tag detection algorithm computes the following
187 // information:
188 //
189 // (tid, tc0, tc1, tc2, tc3)
190 //
191 // tid (Tag IDentifier) is the tag identifier,
192 // tc0 (Tag Corner 0) is actually (tc0x, tc0y) the location
193 // if the tag corner 0 in image coordinated,
194 // tc1 (Tag Corner 1) is actually (tc0x, tc0y) the location
195 // if the tag corner 0 in image coordinated,
196 // tc2 (Tag Corner 2) is actually (tc0x, tc0y) the location
197 // if the tag corner 0 in image coordinated, and
198 // tc3 (Tag Corner 3) is actually (tc0x, tc0y) the location
199 // if the tag corner 0 in image coordinated.
200 //
201 // The 4 tag corners go in a clockwise direction around the tag
202 // (when viewed from above, of course.) The tag looks as follows
203 // in ASCII art:
204 //
205 // +Y
206 // ^
207 // |
208 // | tc2 tc3
209 // | ** ** ** ** ** ** ** **
210 // | ** ** ** ** ** ** ** **
211 // | ** ** ** ** ** ** ** **
212 // | ** ** ** ** ** ** ** **
213 // | ** ** ** ** ** ** ** **
214 // | ** ** ** ** ** ** ** **
215 // | 15 14 13 12 11 10 9 8
216 // | 7 6 5 4 3 2 1 0
217 // | tc1 tc0
218 // |
219 // +--------------------------------> +X
220 //
221 // Localization Computation:
222 //
223 // The localization algorithm operates as follows:
224 //
225 // foreach tag in image:
226 // (tid, tc0, tc1, tc2, tc3) = tag_extract(image)
227 // (mtid, mtx, mty, mttw, mtdiag) = Map(tid)
228 // (camx, camy, camtw) = F(tc0, tc1, tc2, tc3, mtx, mty, mttw, mtdiag)
229 //
230 // Now let's get into the detail of the localization function F().
231 //
232 // Using (tc0, tc1, tc2, tc3), we compute the following:
233 //
234 // tagctrx (TAG CenTeR X) is the tag center X coordinate in
235 // image coordinates,
236 // tagctry (TAG CenTeR y) is the tag center X coordinate in
237 // image coordinates,
238 // tagdiag (TAG DIAGonal) is the average diagonal length in image
239 // coordinates,
240 // tagtw (TAG TWist) is the angle of the lower tag edge with
241 // respect to the image coordinate X axis.
242 //
243 // These values are computed as follows:
244 //
245 // tagctrx = (tc0x + tc1x + tc2x + tc3x) / 4 # The average of the X's
246 // tagctry = (tc0y + tc1y + tc2y + ct3y) / 4 # The average of the Y's
247 // tagdiag1 = sqrt( (tc0x-tc2x)^2 + (tc0y-tc2y)^2) ) # First diagonal
248 // tagdiag2 = sqrt( (tc1x-tc3x)^2 + (tc1y-tc3y)^2) ) # Second diagonal
249 // tagdiag = (tagdiag1 + tagdiag2) / 2 # Avg. of both diagonals
250 // tagtw = arctangent2(tc0y - tc1y, tc0x - tc1y) # Bottom tag edge angle
251 //
252 // The image center is defined as:
253 //
254 // (imgctrx, imgctry)
255 //
256 // where
257 //
258 // imgctrx (IMG CenTeR X) is the image center X coordinate in image
259 // coordinates, and
260 // imgctry (IMG CenTeR Y) is the image center Y coordinate in image
261 // coordinates.
262 //
263 // for an image that is 640 x 480, the image center is (320, 240).
264 // (Actually, it should be (319.5, 239.5).)
265 //
266 // Using the image center the following values are computed:
267 //
268 // tagdist (TAG DISTance) is the distance from the tag center to
269 // image center in image coordinates, and
270 // tagbear (TAG BEARing) is the angle from the tag center to the
271 // image center in image coordinates.
272 //
273 // These two values are computed as:
274 //
275 // tagdist = sqrt( (imgctrx - tagctrx)^2 + (imgctry - tagctry)^2) )
276 // tagbear = arctangent2( imgctry - tagctry, imgctrx - tagctry)
277 //
278 // tagdist is in image coordinate space and we will need the same distance
279 // in floor coordinate space. This is done using tagdiag and mtd (the
280 // map tag diagonal length.)
281 //
282 // flrtagdist = tagdist * (mtd / tagdiag )
283 //
284 // where flrtagdist stands for FLooR TAG DISTance.
285 //
286 // Now we need to compute to angles that are measured relative to the
287 // floor X axis:
288 //
289 // camtw (CAMera TWist) is the direction that the camera X axis points
290 // relative to the floor X Axis, and
291 // cambear (CAMera BEARing) is the direction to the camera center relative
292 // to the floor X Axis.
293 //
294 // camtw and cambear are computed as:
295 //
296 // camtw = mttw - tagtw
297 //
298 // cambear = camtw + tagbear
299 //
300 // Now camx, and camy are computed as follows:
301 //
302 // camx = mtx + flrtagdist * cos(cambear)
303 // camy = mty + flrtagdist * sin(cambear)
304 //
305 // Thus, the final result of (camx, camy, ctw) has been determined.
306 //
307 // Mapping into Robot Coordinates:
308 //
309 // Once we know the camera location and orientation,
310 // (camx, camy, camtw), we need to compute the ordered triple:
311 //
312 // (rx, ry, rbear)
313 //
314 // where
315 //
316 // rx (Robot X) is the X coordinate of the robot center in
317 // floor coordinates,
318 // ry (Robot Y) is the Y coordinate of the robot center in
319 // floor coordinates, and
320 // rbear (Robot BEARing) is the bearing angle of the robot X axis
321 // to the floor coordinate X axis.
322 //
323 // These values are computed as a function:
324 //
325 // (rx, ry, rbear) = F( (camx, camy, camtw) )
326 //
327 // There are two constants needed to do this computation:
328 //
329 // robdist (ROBot DISTance) is the distance from the camera
330 // center to the robot center in floor coordinates, and
331 // robcamtw (ROBot CAMera TWist) is the angle from the angle from
332 // camera X axis to the robot X axis.
333 //
334 // Both robdist and robcamtw are constants that can be directly measured
335 // from the camera placement relative to the robot origin.
336 //
337 // Now (rx, ry, rtw) can be computed as follows:
338 //
339 // rtw = camtw + robcamtw
340 // rx = camx + robdist * cos(rcamtw)
341 // ry = camy + robdist * sin(rcamtw)
342 //
343 // That covers the localization processing portion of the algorithm.
344 //
345 // Fusing with Dead Reckoning:
346 //
347 // The robot dead reckoning system keeps track of the robot position
348 // using wheel encoders. These values are represented in the ordered
349 // triple:
350 //
351 // (ex, ey, etw)
352 //
353 // where
354 //
355 // ex (Encoder X) is the robot X coordinate in floor coordinates,
356 // ey (Encoder Y) is the robot Y coordinate in floor coordinates, and
357 // etw (Encoder TWist) is the robot X axis twist relative to the
358 // floor coordinate X axis.
359 //
360 // (rx, ry, rtw) and (ex, ey, etw) are supposed to be the same. Over
361 // time, small errors will accumulate in the computation of (ex, ey, etw).
362 // (rx, ry, rtw) can be used to reset (ex, ey, etw).
363 //
364 // Coordinate Space Transforms:
365 //
366 // That pretty much summarizes what the basic algorithm does.
367 //
368 // What remains is to do the transformations that place the tags
369 // on the ceiling. There are three transformations.
370 //
371 // tags lift The tags are lifted straight up from the floor
372 // to the ceiling. The person looking on down
373 // from above would see no changes in tag position
374 // or orientation (ignoring parallax issues.)
375 //
376 // camera flip The camera is rotated 180 degrees around the
377 // camera X axis. The causes the Y axis to change
378 // its sign.
379 //
380 // image framing For historical reasons, the camera image API
381 // provides the camera image with the image origin
382 // in upper left hand corner, whereas the all of
383 // the math above assumes that image origin is
384 // in the lower left corner. It turns out this
385 // is just changes the Y axis sign again.
386 //
387 // The bottom line is that the "camera flip" and the "image framing"
388 // transformation cancel one another out. Thus, the there is no
389 // work needed to tweak the equations above.
390 
409 
410 void Fiducials__fiducial_announce(void *announce_object,
411  int id, int direction, double world_diagonal,
412  double x1, double y1, double x2, double y2,
413  double x3, double y3, double x4, double y4) {
414  File__format(stderr,
415  "Fiducial: id=%d dir=%d diag=%.2f (%.2f,%.2f), " /* + */
416  "(%.2f,%.2f), (%.2f,%.2f), (%.2f,%.2f)",
417  id, direction, world_diagonal, x1, y1, x2, y2, x3, y3, x4, y4);
418 }
419 
426 
428 {
429  fiducials->original_image = image;
430 }
431 
448 
449 //FIXME: Is there any point to having *show* set to false???!!!
450 
451 void Fiducials__image_show(Fiducials fiducials, bool show) {
452  // Grab some values out of *fiduicals*:
453  CV_Image debug_image = fiducials->debug_image;
454  CV_Image original_image = fiducials->original_image;
455 
456  // Create the window we need:
457  String_Const window_name = "Example1";
458  if (show) {
459  cvNamedWindow(window_name, CV__window_auto_size);
460  }
461 
462  // Processing *original_image* with different options
463  // for each time through the loop:
464  unsigned int debug_index = 0;
465  unsigned int previous_debug_index = debug_index;
466  bool done = (bool)0;
467  while (!done) {
468  // Process {gray_image}; a debug image lands in {debug_image}:
469  Fiducials__process(fiducials);
470 
471  // Display either *original_image* or *debug_image*:
472  if (show) {
473  cvShowImage(window_name, debug_image);
474  }
475 
476  // Get a *control_character* from the user:
477  char control_character = '\0';
478  if (show) {
479  control_character = (char)(cvWaitKey(0) & 0xff);
480  }
481 
482  // Dispatch on *control_character*:
483  switch (control_character) {
484  case '\33':
485  //# Exit program:
486  done = (bool)1;
487  File__format(stderr, "done\n");
488  break;
489  case '+':
490  //# Increment {debug_index}:
491  debug_index += 1;
492  break;
493  case '-':
494  // Decrement {debug_index}:
495  if (debug_index > 0) {
496  debug_index -= 1;
497  }
498  break;
499  case '<':
500  // Set {debug_index} to beginning:
501  debug_index = 0;
502  break;
503  case '>':
504  // Set {debug_index} to end:
505  debug_index = 100;
506  break;
507  case 'b':
508  // Toggle image blur:
509  fiducials->blur = !fiducials->blur;
510  File__format(stderr, "blur = %d\n", fiducials->blur);
511  break;
512  case 'f':
513  // Toggle image blur:
514  fiducials->y_flip = !fiducials->y_flip;
515  File__format(stderr, "y_flip = %d\n", fiducials->y_flip);
516  break;
517  default:
518  // Deal with unknown {control_character}:
519  if ((unsigned int)control_character <= 127) {
520  File__format(stderr,
521  "Unknown control character %d\n", control_character);
522  }
523  break;
524  }
525 
526  // Update *debug_index* in *fiducials*:
527  fiducials->debug_index = debug_index;
528 
529  // Show user *debug_index* if it has changed:
530  if (debug_index != previous_debug_index) {
531  File__format(stderr,
532  "****************************debug_index = %d\n", debug_index);
533  previous_debug_index = debug_index;
534  }
535  }
536 
537  // Release storage:
538  CV__release_image(original_image);
539  if (show) {
540  cvDestroyWindow(window_name);
541  }
542 }
543 
551 
552 //FIXME: Change this code so that the image size is determined from
553 // the first image that is processed. This allows the image size
554 // to change in midstream!!!
555 
557  CV_Image original_image, Fiducials_Create fiducials_create)
558 {
559  // Create *image_size*:
560  unsigned int width = CV_Image__width_get(original_image);
561  unsigned int height = CV_Image__height_get(original_image);
562  CV_Size image_size = CV_Size__create(width, height);
564 
565  // Grab some values from *fiducials_create*:
566  String_Const fiducials_path = fiducials_create->fiducials_path;
567  Memory announce_object = fiducials_create->announce_object;
568  Fiducials_Fiducial_Announce_Routine fiducial_announce_routine =
569  fiducials_create->fiducial_announce_routine;
570  String_Const log_file_name = fiducials_create->log_file_name;
571  // Get *log_file* open if *log_file_name* is not null:
572  File log_file = stderr;
573  if (log_file_name != (String_Const)0) {
574  String full_log_file_name =
575  String__format("%s/%s", fiducials_path, log_file_name);
576  log_file = File__open(log_file_name, "w");
577  String__free(full_log_file_name);
578  }
579  File__format(log_file, "CV width=%d CV height = %d\n", width, height);
580 
581  int term_criteria_type =
583 
584  // The north/west/south/east mappings must reside in static
585  // memory rather than on the stack:
586 
587  static int north_mapping_flipped[64] = {
588  //corner1 corner0
589  7, 6, 5, 4, 3, 2, 1, 0,
590  15, 14, 13, 12, 11, 10, 9, 8,
591  23, 22, 21, 20, 19, 18, 17, 16,
592  31, 30, 29, 28, 27, 26, 25, 24,
593  39, 38, 37, 36, 35, 34, 33, 32,
594  47, 46, 45, 44, 43, 42, 41, 40,
595  55, 54, 53, 52, 51, 50, 49, 48,
596  63, 62, 61, 60, 59, 58, 57, 56,
597  //corner2 corner3
598  };
599 
600  static int west_mapping_flipped[64] = {
601  //corner1 corner0
602  63, 55, 47, 39, 31, 23, 15, 7,
603  62, 54, 46, 38, 30, 22, 14, 6,
604  61, 53, 45, 37, 29, 21, 13, 5,
605  60, 52, 44, 36, 28, 20, 12, 4,
606  59, 51, 43, 35, 27, 19, 11, 3,
607  58, 50, 42, 34, 26, 18, 10, 2,
608  57, 49, 41, 33, 25, 17, 9, 1,
609  56, 48, 40, 32, 24, 16, 8, 0,
610  //corner2 corner3
611  };
612 
613  static int south_mapping_flipped[64] = {
614  //corner1 corner0
615  56, 57, 58, 59, 60, 61, 62, 63,
616  48, 49, 50, 51, 52, 53, 54, 55,
617  40, 41, 42, 43, 44, 45, 46, 47,
618  32, 33, 34, 35, 36, 37, 38, 39,
619  24, 25, 26, 27, 28, 29, 30, 31,
620  16, 17, 18, 19, 20, 21, 22, 23,
621  8, 9, 10, 11, 12, 13, 14, 15,
622  0, 1, 2, 3, 4, 5, 6, 7,
623  //corner2 corner3
624  };
625 
626  static int east_mapping_flipped[64] = {
627  //corner1 corner0
628  0, 8, 16, 24, 32, 40, 48, 56,
629  1, 9, 17, 25, 33, 41, 49, 57,
630  2, 10, 18, 26, 34, 42, 50, 58,
631  3, 11, 19, 27, 35, 43, 51, 59,
632  4, 13, 20, 28, 36, 44, 52, 60,
633  5, 13, 21, 29, 37, 45, 53, 61,
634  6, 14, 22, 30, 38, 46, 54, 62,
635  7, 15, 23, 31, 39, 47, 55, 63,
636  //corner2 corner3
637  };
638 
639  // The north/west/south/east mappings must reside in static
640  // memory rather than on the stack:
641 
642  static int *mappings[4] = {
643  &north_mapping_flipped[0],
644  &west_mapping_flipped[0],
645  &south_mapping_flipped[0],
646  &east_mapping_flipped[0],
647  };
648 
649  //for (unsigned int index = 0; index < 4; index++) {
650  // File__format(log_file, "mappings[%d]=0x%x\n", index, mappings[index]);
651  //}
652 
653  CV_Image map_x = (CV_Image)0;
654  CV_Image map_y = (CV_Image)0;
655 
656  Fiducials_Results results =
657  Memory__new(Fiducials_Results, "Fiducials__create");
658  results->map_changed = (bool)0;
659 
660  // Create and load *fiducials*:
661  Fiducials fiducials = Memory__new(Fiducials, "Fiducials__create");
662  fiducials = new(fiducials) Fiducials__Struct();
663  if (fiducial_announce_routine != NULL)
664  fiducials->fiducial_announce_routine = fiducial_announce_routine;
665  else
667  fiducials->announce_object = announce_object;
668  fiducials->blue = CV_Scalar__rgb(0.0, 0.0, 1.0);
669  fiducials->blur = (bool)0;
670  fiducials->corners = CV_Point2D32F_Vector__create(4);
671  fiducials->cyan = CV_Scalar__rgb(0.0, 1.0, 1.0);
672  fiducials->debug_image = CV_Image__create(image_size, CV__depth_8u, 3);
673  fiducials->debug_index = 0;
674  fiducials->edge_image = CV_Image__create(image_size, CV__depth_8u, 1);
675  fiducials->fec = FEC__create(8, 4, 4);
676  fiducials->gray_image = CV_Image__create(image_size, CV__depth_8u, 1);
677  fiducials->green = CV_Scalar__rgb(0.0, 255.0, 0.0);
678  fiducials->image_size = image_size;
679  fiducials->last_x = 0.0;
680  fiducials->last_y = 0.0;
681  fiducials->log_file = log_file;
682  fiducials->map_x = map_x;
683  fiducials->map_y = map_y;
684  fiducials->mappings = &mappings[0];
685  fiducials->origin = CV_Point__create(0, 0);
686  fiducials->original_image = original_image;
687  fiducials->path = fiducials_path;
688  fiducials->purple = CV_Scalar__rgb(255.0, 0.0, 255.0);
689  fiducials->red = CV_Scalar__rgb(255.0, 0.0, 0.0);
691  fiducials->results = results;
693  fiducials->size_5x5 = CV_Size__create(5, 5);
694  fiducials->size_m1xm1 = CV_Size__create(-1, -1);
695  fiducials->sequence_number = 0;
696  fiducials->storage = storage;
697  fiducials->temporary_gray_image =
698  CV_Image__create(image_size, CV__depth_8u, 1);
699  fiducials->weights_index = 0;
700  fiducials->term_criteria =
701  CV_Term_Criteria__create(term_criteria_type, 5, 0.2);
702  fiducials->y_flip = (bool)0;
703  fiducials->black = CV_Scalar__rgb(0, 0, 0);
704 
705  return fiducials;
706 }
707 
712 
713 void Fiducials__free(Fiducials fiducials) {
714  // Free up some *CV_Scalar* colors:
715  CV_Scalar__free(fiducials->blue);
716  CV_Scalar__free(fiducials->cyan);
717  CV_Scalar__free(fiducials->green);
718  CV_Scalar__free(fiducials->purple);
719  CV_Scalar__free(fiducials->red);
720  CV_Scalar__free(fiducials->black);
721 
722  // Free up some *SV_Size* objects:
723  CV_Size__free(fiducials->image_size);
724  CV_Size__free(fiducials->size_5x5);
725  CV_Size__free(fiducials->size_m1xm1);
726 
727  // Finally release *fiducials*:
728  Memory__free((Memory)fiducials);
729 }
730 
736 
738 }
739 
747 
749  // Clear *storage*:
750  CV_Memory_Storage storage = fiducials->storage;
751  CV_Memory_Storage__clear(storage);
752 
753  // Grab some values from *fiducials*:
754  CV_Image debug_image = fiducials->debug_image;
755  unsigned int debug_index = fiducials->debug_index;
756  CV_Image edge_image = fiducials->edge_image;
757  CV_Image gray_image = fiducials->gray_image;
758  File log_file = fiducials->log_file;
759  CV_Image original_image = fiducials->original_image;
760  Fiducials_Results results = fiducials->results;
761  CV_Image temporary_gray_image = fiducials->temporary_gray_image;
762 
763  // For *debug_level* 0, we show the original image in color:
764  if (debug_index == 0) {
765  CV_Image__copy(original_image, debug_image, (CV_Image)0);
766  }
767 
768  // Convert from color to gray scale:
769  int channels = CV_Image__channels_get(original_image);
770 
771  // Deal with *debug_index* 0:
772  if (debug_index == 0) {
773  if (channels == 3) {
774  // Original image is color, so a simple copy will work:
775  CV_Image__copy(original_image, debug_image, (CV_Image)0);
776  } else if (channels == 1) {
777  // Original image is gray, so we have to convert back to "color":
778  CV_Image__convert_color(original_image,
779  debug_image, CV__gray_to_rgb);
780  }
781  }
782 
783  // Convert *original_image* to gray scale:
784  if (channels == 3) {
785  // Original image is color, so we need to convert to gray scale:
786  CV_Image__convert_color(original_image, gray_image, CV__rgb_to_gray);
787  } else if (channels == 1) {
788  // Original image is gray, so a simple copy will work:
789  CV_Image__copy(original_image, gray_image, (CV_Image)0);
790  } else {
791  assert(0);
792  }
793 
794  // Show results of gray scale converion for *debug_index* 1:
795  if (debug_index == 1) {
796  CV_Image__convert_color(gray_image, debug_image, CV__gray_to_rgb);
797  }
798 
799  // Preform undistort if available:
800  if (fiducials->map_x != (CV_Image)0) {
801  int flags = CV_INTER_NN | CV_WARP_FILL_OUTLIERS;
802  CV_Image__copy(gray_image, temporary_gray_image, (CV_Image)0);
803  CV_Image__remap(temporary_gray_image, gray_image,
804  fiducials->map_x, fiducials->map_y, flags, fiducials->black);
805  }
806 
807  // Show results of undistort:
808  if (debug_index == 2) {
809  CV_Image__convert_color(gray_image, debug_image, CV__gray_to_rgb);
810  }
811 
812  // Perform Gaussian blur if requested:
813  if (fiducials->blur) {
814  CV_Image__smooth(gray_image, gray_image, CV__gaussian, 3, 0, 0.0, 0.0);
815  }
816 
817  // Show results of Gaussian blur for *debug_index* 2:
818  if (debug_index == 3) {
819  CV_Image__convert_color(gray_image, debug_image, CV__gray_to_rgb);
820  }
821 
822  // Perform adpative threshold:
823  CV_Image__adaptive_threshold(gray_image, edge_image, 255.0,
825 
826  // Show results of adaptive threshold for *debug_index* 3:
827  if (debug_index == 4) {
828  CV_Image__convert_color(edge_image, debug_image, CV__gray_to_rgb);
829  }
830 
831  // Find the *edge_image* *contours*:
832  CV_Point origin = fiducials->origin;
833  int header_size = 128;
834  CV_Sequence contours = CV_Image__find_contours(edge_image, storage,
835  header_size, CV__retr_list, CV__chain_approx_simple, origin);
836  if (contours == (CV_Sequence)0) {
837  File__format(log_file, "no contours found\n");
838  }
839 
840  // For *debug_index* 4, show the *edge_image* *contours*:
841  if (debug_index == 5) {
842  //File__format(log_file, "Draw red contours\n");
843  CV_Scalar red = fiducials->red;
844  CV_Image__convert_color(gray_image, debug_image, CV__gray_to_rgb);
845  CV_Image__draw_contours(debug_image,
846  contours, red, red, 2, 2, 8, origin);
847  }
848 
849  // For the remaining debug steps, we use the original *gray_image*:
850  if (debug_index >= 5) {
851  CV_Image__convert_color(gray_image, debug_image, CV__gray_to_rgb);
852  }
853 
854  // Iterate over all of the *contours*:
855  unsigned int contours_count = 0;
856  for (CV_Sequence contour = contours; contour != (CV_Sequence)0;
857  contour = CV_Sequence__next_get(contour)) {
858  // Keep a count of total countours:
859  contours_count += 1;
860  //File__format(log_file, "contours_count=%d\n", contours_count);
861 
862  static CvSlice whole_sequence;
864  whole_sequence = CV_WHOLE_SEQ;
865 
866  // Perform a polygon approximation of {contour}:
867  int arc_length =
868  (int)(CV_Sequence__arc_length(contour, CV__whole_seq, 1) * 0.02);
869  CV_Sequence polygon_contour =
871  header_size, storage, CV__poly_approx_dp, arc_length, 0.0);
872  if (debug_index == 6) {
873  //File__format(log_file, "Draw green contours\n");
874  CV_Scalar green = fiducials->green;
875  CV_Image__draw_contours(debug_image,
876  polygon_contour, green, green, 2, 2, 1, origin);
877  }
878 
879  // If we have a 4-sided polygon with an area greater than 500 square
880  // pixels, we can explore to see if we have a tag:
881  if (CV_Sequence__total_get(polygon_contour) == 4 &&
882  fabs(CV_Sequence__contour_area(polygon_contour,
883  CV__whole_seq, 0)) > 500.0 &&
884  CV_Sequence__check_contour_convexity(polygon_contour)) {
885  // For debugging, display the polygons in red:
886  //File__format(log_file, "Have 4 sides > 500i\n");
887 
888  // Just show the fiducial outlines for *debug_index* of 6:
889  if (debug_index == 7) {
890  CV_Scalar red = fiducials->red;
891  CV_Image__draw_contours(debug_image,
892  polygon_contour, red, red, 2, 2, 1, origin);
893  }
894 
895  // Copy the 4 corners from {poly_contour} to {corners}:
896  CV_Point2D32F_Vector corners = fiducials->corners;
897  for (unsigned int index = 0; index < 4; index++) {
898  CV_Point2D32F corner =
900  CV_Point point =
901  CV_Sequence__point_fetch1(polygon_contour, index);
902  CV_Point2D32F__point_set(corner, point);
903 
904  if (debug_index == 7) {
905  //File__format(log_file,
906  // "point[%d] x:%f y:%f\n", index, point->x, point->y);
907  }
908  }
909 
910  // Now find the sub pixel corners of {corners}:
911  CV_Image__find_corner_sub_pix(gray_image, corners, 4,
912  fiducials->size_5x5, fiducials->size_m1xm1,
913  fiducials->term_criteria);
914 
915  // Ensure that the corners are in a counter_clockwise direction:
917 
918  // For debugging show the 4 corners of the possible tag where
919  //corner0=red, corner1=green, corner2=blue, corner3=purple:
920  if (debug_index == 8) {
921  for (unsigned int index = 0; index < 4; index++) {
922  CV_Point point =
923  CV_Sequence__point_fetch1(polygon_contour, index);
924  int x = CV_Point__x_get(point);
925  int y = CV_Point__y_get(point);
926  CV_Scalar color = (CV_Scalar)0;
927  String_Const text = (String)0;
928  switch (index) {
929  case 0:
930  color = fiducials->red;
931  text = "red";
932  break;
933  case 1:
934  color = fiducials->green;
935  text = "green";
936  break;
937  case 2:
938  color = fiducials->blue;
939  text = "blue";
940  break;
941  case 3:
942  color = fiducials->purple;
943  text = "purple";
944  break;
945  default:
946  assert(0);
947  }
948  CV_Image__cross_draw(debug_image, x, y, color);
949  File__format(log_file,
950  "poly_point[%d]=(%d:%d) %s\n", index, x, y, text);
951  }
952  }
953 
954  // Compute the 8 reference points for deciding whether the
955  // polygon is "tag like" in its borders:
956  CV_Point2D32F_Vector references =
957  Fiducials__references_compute(fiducials, corners);
958 
959  // Now sample the periphery of the tag and looking for the
960  // darkest white value (i.e. minimum) and the lightest black
961  // value (i.e. maximum):
962  //int white_darkest =
963  // CV_Image__points_minimum(gray_image, references, 0, 3);
964  //int black_lightest =
965  // CV_Image__points_maximum(gray_image, references, 4, 7);
966  int white_darkest =
967  Fiducials__points_minimum(fiducials, references, 0, 3);
968  int black_lightest =
969  Fiducials__points_maximum(fiducials, references, 4, 7);
970 
971  // {threshold} should be smack between the two:
972  int threshold = (white_darkest + black_lightest) / 2;
973 
974  // For debugging, show the 8 points that are sampled around the
975  // the tag periphery to even decide whether to do further testing.
976  // Show "black" as green crosses, and "white" as green crosses:
977  if (debug_index == 9) {
978  CV_Scalar red = fiducials->red;
979  CV_Scalar green = fiducials->green;
980  for (unsigned int index = 0; index < 8; index++) {
981  CV_Point2D32F reference =
982  CV_Point2D32F_Vector__fetch1(references, index);
983  int x = CV__round(CV_Point2D32F__x_get(reference));
984  int y = CV__round(CV_Point2D32F__y_get(reference));
985  //int value =
986  // CV_Image__point_sample(gray_image, reference);
987  int value =
988  Fiducials__point_sample(fiducials, reference);
989  CV_Scalar color = red;
990  if (value < threshold) {
991  color = green;
992  }
993  CV_Image__cross_draw(debug_image, x, y, color);
994  File__format(log_file, "ref[%d:%d]:%d\n", x, y, value);
995  }
996  }
997 
998  // If we have enough contrast keep on trying for a tag match:
999  if (black_lightest < white_darkest) {
1000  // We have a tag to try:
1001 
1002  // Now it is time to read all the bits of the tag out:
1003  CV_Point2D32F_Vector sample_points = fiducials->sample_points;
1004 
1005  // Now compute the locations to sample for tag bits:
1006  Fiducials__sample_points_compute(corners, sample_points);
1007 
1008  // Extract all 64 tag bit values:
1009  bool *tag_bits = &fiducials->tag_bits[0];
1010  for (unsigned int index = 0; index < 64; index++) {
1011  // Grab the pixel value and convert into a {bit}:
1012  CV_Point2D32F sample_point =
1013  CV_Point2D32F_Vector__fetch1(sample_points, index);
1014  //int value =
1015  // CV_Image__point_sample(gray_image, sample_point);
1016  int value =
1017  Fiducials__point_sample(fiducials, sample_point);
1018  int bit = (value < threshold);
1019  tag_bits[index] = bit;
1020 
1021  // For debugging:
1022  if (debug_index == 10) {
1023  CV_Scalar red = fiducials->red;
1024  CV_Scalar green = fiducials->green;
1025  // Show white bits as {red} and black bits as {green}:
1026  CV_Scalar color = red;
1027  if (bit) {
1028  color = green;
1029  }
1030 
1031  // Show where bit 0 and 7 are:
1032  //if (index == 0) {
1033  // // Bit 0 is {cyan}:
1034  // color = cyan;
1035  //}
1036  //if (index == 7) {
1037  // // Bit 7 is {blue}:
1038  // color = blue;
1039  //}
1040 
1041  // Now splat a cross of {color} at ({x},{y}):
1042  int x =
1043  CV__round(CV_Point2D32F__x_get(sample_point));
1044  int y =
1045  CV__round(CV_Point2D32F__y_get(sample_point));
1046  CV_Image__cross_draw(debug_image, x, y, color);
1047  }
1048  }
1049 
1050  //tag_bits :@= extractor.tag_bits
1051  //bit_field :@= extractor.bit_field
1052  //tag_bytes :@= extractor.tag_bytes
1053 
1054  // Now we iterate through the 4 different mapping
1055  // orientations to see if any one of the 4 mappings match:
1056  int **mappings = fiducials->mappings;
1057  unsigned int mappings_size = 4;
1058  for (unsigned int direction_index = 0;
1059  direction_index < mappings_size; direction_index++) {
1060  // Grab the mapping:
1061  int *mapping = mappings[direction_index];
1062  //File__format(log_file,
1063  // "mappings[%d]:0x%x\n", direction_index, mapping);
1064 
1065 
1066  int mapped_bits[64];
1067  for (unsigned int i = 0; i < 64; i++) {
1068  mapped_bits[mapping[i]] = tag_bits[i];
1069  }
1070 
1071  // Fill in tag bytes;
1072  unsigned int tag_bytes[8];
1073  for (unsigned int i = 0; i < 8; i++) {
1074  unsigned int byte = 0;
1075  for (unsigned int j = 0; j < 8; j++) {
1076  if (mapped_bits[(i<<3) + j]) {
1077  //byte |= 1 << j;
1078  byte |= 1 << (7 - j);
1079  }
1080  }
1081  tag_bytes[i] = byte;
1082  }
1083  if (debug_index == 11) {
1084  File__format(log_file,
1085  "dir=%d Tag[0]=0x%x Tag[1]=0x%x\n",
1086  direction_index, tag_bytes[0], tag_bytes[1]);
1087  }
1088 
1089  // Now we need to do some FEC (Forward Error Correction):
1090  FEC fec = fiducials->fec;
1091  if (FEC__correct(fec, tag_bytes, 8)) {
1092  // We passed FEC:
1093  if (debug_index == 11) {
1094  File__format(log_file, "FEC correct\n");
1095  }
1096 
1097  // Now see if the two CRC's match:
1098  unsigned int computed_crc = CRC__compute(tag_bytes, 2);
1099  unsigned int tag_crc = (tag_bytes[3] << 8) | tag_bytes[2];
1100  if (computed_crc == tag_crc) {
1101  // Yippee!!! We have a tag:
1102  // Compute {tag_id} from the the first two bytes
1103  // of {tag_bytes}:
1104  unsigned int tag_id =
1105  (tag_bytes[1] << 8) | tag_bytes[0];
1106 
1107  if (debug_index == 11) {
1108  File__format(log_file,
1109  "CRC correct, Tag=%d\n", tag_id);
1110  }
1111 
1112  double vertices[4][2];
1113  for (unsigned int index = 0; index < 4; index++) {
1115  vertices[index][0] = pt->x;
1116  vertices[index][1] = pt->y;
1117  }
1118  fiducials->fiducial_announce_routine(
1119  fiducials->announce_object, tag_id,
1120  direction_index, 0.0,
1121  vertices[0][0], vertices[0][1],
1122  vertices[1][0], vertices[1][1],
1123  vertices[2][0], vertices[2][1],
1124  vertices[3][0], vertices[3][1]);
1125  }
1126  }
1127  }
1128  }
1129  }
1130  }
1131 
1132  return results;
1133 }
1134 
1144 
1146  // This routine will return a sample *fiducials* at *point*.
1147 
1148  // Get the (*x*, *y*) coordinates of *point*:
1149  int x = CV__round(CV_Point2D32F__x_get(point));
1150  int y = CV__round(CV_Point2D32F__y_get(point));
1151  CV_Image image = fiducials->gray_image;
1152 
1153  static int weights0[9] = {
1154  0, 0, 0,
1155  0, 100, 0,
1156  0, 0, 0};
1157 
1158  static int weights1[9] = {
1159  0, 15, 0,
1160  15, 40, 15,
1161  0, 15, 0};
1162 
1163  static int weights2[9] = {
1164  5, 10, 5,
1165  10, 40, 10,
1166  5, 10, 5};
1167 
1168  // Sample *image*:
1169  static int x_offsets[9] = {
1170  -1, 0, 1,
1171  -1, 0, 1,
1172  -1, 0, 1};
1173  static int y_offsets[9] = {
1174  -1, -1, -1,
1175  0, 0, 0,
1176  1, 1, 1};
1177 
1178  // Select sample *weights*:
1179  int *weights = (int *)0;
1180  switch (fiducials->weights_index) {
1181  case 1:
1182  weights = weights1;
1183  break;
1184  case 2:
1185  weights = weights2;
1186  break;
1187  default:
1188  weights = weights0;
1189  break;
1190  }
1191 
1192  // Interate across sample point;
1193  int numerator = 0;
1194  int denominator = 0;
1195  for (int index = 0; index < 9; index++) {
1196  int sample = CV_Image__gray_fetch(image,
1197  x + x_offsets[index], y + y_offsets[index]);
1198  if (sample >= 0) {
1199  int weight = weights[index];
1200  numerator += sample * weight;
1201  denominator += weight;
1202  }
1203  }
1204 
1205  // Compute *result* checking for divide by zero:
1206  int result = 0;
1207  if (denominator > 0) {
1208  result = numerator / denominator;
1209  }
1210  return result;
1211 }
1212 
1219 
1220 //FIXME: Does this routine belong in CV.c???!!!
1221 //FIXME: Should this be merged with *CV_Point2D32F_Vector__is_clockwise*???!!!
1222 
1224  // This routine will ensure that {corners} are ordered
1225  // in the counter-clockwise direction.
1226 
1227  if (CV_Point2D32F_Vector__is_clockwise(corners)) {
1228  // Extract two corners to be swapped:
1229  CV_Point2D32F corner1 = CV_Point2D32F_Vector__fetch1(corners, 1);
1230  CV_Point2D32F corner3 = CV_Point2D32F_Vector__fetch1(corners, 3);
1231 
1232  // Extract X and Y for both corners:
1233  double x1 = CV_Point2D32F__x_get(corner1);
1234  double y1 = CV_Point2D32F__y_get(corner1);
1235  double x3 = CV_Point2D32F__x_get(corner3);
1236  double y3 = CV_Point2D32F__y_get(corner3);
1237 
1238  // Swap contents of {corner1} and {corner3}:
1239  CV_Point2D32F__x_set(corner1, x3);
1240  CV_Point2D32F__y_set(corner1, y3);
1241  CV_Point2D32F__x_set(corner3, x1);
1242  CV_Point2D32F__y_set(corner3, y1);
1243  }
1244 }
1245 
1252 
1254 
1255  // Extract the three corners:
1256  CV_Point2D32F corner0 = CV_Point2D32F_Vector__fetch1(corners, 0);
1257  CV_Point2D32F corner1 = CV_Point2D32F_Vector__fetch1(corners, 1);
1258  CV_Point2D32F corner2 = CV_Point2D32F_Vector__fetch1(corners, 2);
1259 
1260  // Extract X and Y for all four corners:
1261  double x0 = CV_Point2D32F__x_get(corner0);
1262  double y0 = CV_Point2D32F__y_get(corner0);
1263  double x1 = CV_Point2D32F__x_get(corner1);
1264  double y1 = CV_Point2D32F__y_get(corner1);
1265  double x2 = CV_Point2D32F__x_get(corner2);
1266  double y2 = CV_Point2D32F__y_get(corner2);
1267 
1268  // Create two vectors from the first two lines of the polygon:
1269  double v1x = x1 - x0;
1270  double v1y = y1 - y0;
1271  double v2x = x2 - x1;
1272  double v2y = y2 - y1;
1273 
1274  // Determine the sign of the Z coordinate of the cross product:
1275  double z = v1x * v2y - v2x * v1y;
1276 
1277  // If the Z coordinate is negative, to reverse the sequence of the corners:
1278  return z < 0.0;
1279  }
1280 
1294 
1296  Fiducials fiducials, CV_Point2D32F_Vector corners) {
1297 
1298  // Extract the 8 references from {references}:
1299  CV_Point2D32F_Vector references = fiducials->references;
1300  CV_Point2D32F reference0 = CV_Point2D32F_Vector__fetch1(references, 0);
1301  CV_Point2D32F reference1 = CV_Point2D32F_Vector__fetch1(references, 1);
1302  CV_Point2D32F reference2 = CV_Point2D32F_Vector__fetch1(references, 2);
1303  CV_Point2D32F reference3 = CV_Point2D32F_Vector__fetch1(references, 3);
1304  CV_Point2D32F reference4 = CV_Point2D32F_Vector__fetch1(references, 4);
1305  CV_Point2D32F reference5 = CV_Point2D32F_Vector__fetch1(references, 5);
1306  CV_Point2D32F reference6 = CV_Point2D32F_Vector__fetch1(references, 6);
1307  CV_Point2D32F reference7 = CV_Point2D32F_Vector__fetch1(references, 7);
1308 
1309  // Extract the 4 corners from {corners}:
1310  CV_Point2D32F corner0 = CV_Point2D32F_Vector__fetch1(corners, 0);
1311  CV_Point2D32F corner1 = CV_Point2D32F_Vector__fetch1(corners, 1);
1312  CV_Point2D32F corner2 = CV_Point2D32F_Vector__fetch1(corners, 2);
1313  CV_Point2D32F corner3 = CV_Point2D32F_Vector__fetch1(corners, 3);
1314 
1315  // Extract the x and y references from {corner0} through {corner3}:
1316  double x0 = CV_Point2D32F__x_get(corner0);
1317  double y0 = CV_Point2D32F__y_get(corner0);
1318  double x1 = CV_Point2D32F__x_get(corner1);
1319  double y1 = CV_Point2D32F__y_get(corner1);
1320  double x2 = CV_Point2D32F__x_get(corner2);
1321  double y2 = CV_Point2D32F__y_get(corner2);
1322  double x3 = CV_Point2D32F__x_get(corner3);
1323  double y3 = CV_Point2D32F__y_get(corner3);
1324 
1325  double dx21 = x2 - x1;
1326  double dy21 = y2 - y1;
1327  double dx30 = x3 - x0;
1328  double dy30 = y3 - y0;
1329 
1330  // Determine the points ({xx0, yy0}) and ({xx1, yy1}) that determine
1331  // a line parrallel to one side of the quadralatal:
1332  double xx0 = x1 + dx21 * 5.0 / 20.0;
1333  double yy0 = y1 + dy21 * 5.0 / 20.0;
1334  double xx1 = x0 + dx30 * 5.0 / 20.0;
1335  double yy1 = y0 + dy30 * 5.0 / 20.0;
1336 
1337  // Set the outside and inside reference points along the line
1338  // through points ({xx0, yy0}) and ({xx1, yy1}):
1339  double dxx10 = xx1 - xx0;
1340  double dyy10 = yy1 - yy0;
1341  CV_Point2D32F__x_set(reference0, xx0 + dxx10 * -1.0 / 20.0);
1342  CV_Point2D32F__y_set(reference0, yy0 + dyy10 * -1.0 / 20.0);
1343  CV_Point2D32F__x_set(reference4, xx0 + dxx10 * 1.0 / 20.0);
1344  CV_Point2D32F__y_set(reference4, yy0 + dyy10 * 1.0 / 20.0);
1345  CV_Point2D32F__x_set(reference1, xx0 + dxx10 * 21.0 / 20.0);
1346  CV_Point2D32F__y_set(reference1, yy0 + dyy10 * 21.0 / 20.0);
1347  CV_Point2D32F__x_set(reference5, xx0 + dxx10 * 19.0 / 20.0);
1348  CV_Point2D32F__y_set(reference5, yy0 + dyy10 * 19.0 / 20.0);
1349 
1350  // Determine the points ({xx2, yy2}) and ({xx3, yy3}) that determine
1351  // a line parrallel to the other side of the quadralatal:
1352  double xx2 = x1 + dx21 * 15.0 / 20.0;
1353  double yy2 = y1 + dy21 * 15.0 / 20.0;
1354  double xx3 = x0 + dx30 * 15.0 / 20.0;
1355  double yy3 = y0 + dy30 * 15.0 / 20.0;
1356 
1357  // Set the outside and inside reference points along the line
1358  // through points ({xx2, yy2}) and ({xx3, yy3}):
1359  double dxx32 = xx3 - xx2;
1360  double dyy32 = yy3 - yy2;
1361  CV_Point2D32F__x_set(reference2, xx2 + dxx32 * -1.0 / 20.0);
1362  CV_Point2D32F__y_set(reference2, yy2 + dyy32 * -1.0 / 20.0);
1363  CV_Point2D32F__x_set(reference6, xx2 + dxx32 * 1.0 / 20.0);
1364  CV_Point2D32F__y_set(reference6, yy2 + dyy32 * 1.0 / 20.0);
1365  CV_Point2D32F__x_set(reference3, xx2 + dxx32 * 21.0 / 20.0);
1366  CV_Point2D32F__y_set(reference3, yy2 + dyy32 * 21.0 / 20.0);
1367  CV_Point2D32F__x_set(reference7, xx2 + dxx32 * 19.0 / 20.0);
1368  CV_Point2D32F__y_set(reference7, yy2 + dyy32 * 19.0 / 20.0);
1369 
1370  return references;
1371 }
1372 
1385 
1387  CV_Point2D32F_Vector points, unsigned int start_index, unsigned int end_index) {
1388 
1389  // Start with a big value move it down:
1390  int result = 0;
1391 
1392  // Iterate across the {points} from {start_index} to {end_index}:
1393  for (unsigned int index = start_index; index <= end_index; index++) {
1395  int value = Fiducials__point_sample(fiducials, point);
1396  //call d@(form@("max[%f%:%f%]:%d%\n\") %
1397  // f@(point.x) % f@(point.y) / f@(value))
1398  if (value > result) {
1399  // New maximum value:
1400  result = value;
1401  }
1402  }
1403  return result;
1404 }
1405 
1417 
1419  CV_Point2D32F_Vector points, unsigned int start_index, unsigned int end_index) {
1420 
1421  // Start with a big value move it down:
1422  int result = 0x7fffffff;
1423 
1424  // Iterate across the {points} from {start_index} to {end_index}:
1425  for (unsigned int index = start_index; index <= end_index; index++) {
1427  int value = Fiducials__point_sample(fiducials, point);
1428  if (value < result) {
1429  // New minimum value:
1430  result = value;
1431  }
1432  }
1433  return result;
1434 }
1435 
1448 
1449 //FIXME: sample points comes from *fiducials*, so shouldn't have
1450 // have *fiducials* as a argument instead of *sample_points*???!!!
1451 
1453  CV_Point2D32F_Vector corners, CV_Point2D32F_Vector sample_points) {
1454 
1455  CV_Point2D32F corner0 = CV_Point2D32F_Vector__fetch1(corners, 0);
1456  CV_Point2D32F corner1 = CV_Point2D32F_Vector__fetch1(corners, 1);
1457  CV_Point2D32F corner2 = CV_Point2D32F_Vector__fetch1(corners, 2);
1458  CV_Point2D32F corner3 = CV_Point2D32F_Vector__fetch1(corners, 3);
1459 
1460  // Extract the x and y references from {corner0} through {corner3}:
1461  double x0 = CV_Point2D32F__x_get(corner0);
1462  double y0 = CV_Point2D32F__y_get(corner0);
1463  double x1 = CV_Point2D32F__x_get(corner1);
1464  double y1 = CV_Point2D32F__y_get(corner1);
1465  double x2 = CV_Point2D32F__x_get(corner2);
1466  double y2 = CV_Point2D32F__y_get(corner2);
1467  double x3 = CV_Point2D32F__x_get(corner3);
1468  double y3 = CV_Point2D32F__y_get(corner3);
1469 
1470  // Figure out the vector directions {corner1} to {corner2}, as well as,
1471  // the vector from {corner3} to {corner0}. If {corners} specify a
1472  // quadralateral, these vectors should be approximately parallel:
1473  double dx21 = x2 - x1;
1474  double dy21 = y2 - y1;
1475  double dx30 = x3 - x0;
1476  double dy30 = y3 - y0;
1477 
1478  // {index} will cycle through the 64 sample points in {sample_points}:
1479  unsigned int index = 0;
1480 
1481  // There are ten rows (or columns) enclosed by the quadralateral.
1482  // (The outermost "white" rows and columns are not enclosed by the
1483  // quadralateral.) Since we want to sample the middle 8 rows (or
1484  // columns), We want a fraction that goes from 3/20, 5/20, ..., 17/20.
1485  // The fractions 1/20 and 19/20 would correspond to a black border,
1486  // which we do not care about:
1487  double i_fraction = 3.0 / 20.0;
1488  double i_increment = 2.0 / 20.0;
1489 
1490  // Loop over the first axis of the grid:
1491  unsigned int i = 0;
1492  while (i < 8) {
1493 
1494  // Compute ({xx1},{yy1}) which is a point that is {i_fraction} between
1495  // ({x1},{y1}) and ({x2},{y2}), as well as, ({xx2},{yy2}) which is a
1496  // point that is {i_fraction} between ({x0},{y0}) and ({x3},{y3}).
1497  double xx1 = x1 + dx21 * i_fraction;
1498  double yy1 = y1 + dy21 * i_fraction;
1499  double xx2 = x0 + dx30 * i_fraction;
1500  double yy2 = y0 + dy30 * i_fraction;
1501 
1502  // Compute the vector from ({xx1},{yy1}) to ({xx2},{yy2}):
1503  double dxx21 = xx2 - xx1;
1504  double dyy21 = yy2 - yy1;
1505 
1506  // As with {i_fraction}, {j_fraction} needs to sample the
1507  // the data stripes through the quadralateral with values
1508  // that range from 3/20 through 17/20:
1509  double j_fraction = 3.0 / 20.0;
1510  double j_increment = 2.0 / 20.0;
1511 
1512  // Loop over the second axis of the grid:
1513  unsigned int j = 0;
1514  while (j < 8) {
1515  // Fetch next {sample_point}:
1516  CV_Point2D32F sample_point =
1517  CV_Point2D32F_Vector__fetch1(sample_points, index);
1518  index = index + 1;
1519 
1520  // Write the rvGrid position into the rvGrid array:
1521  CV_Point2D32F__x_set(sample_point, xx1 + dxx21 * j_fraction);
1522  CV_Point2D32F__y_set(sample_point, yy1 + dyy21 * j_fraction);
1523 
1524  // Increment {j_faction} to the sample point:
1525  j_fraction = j_fraction + j_increment;
1526  j = j + 1;
1527  }
1528 
1529  // Increment {i_fraction} to the next sample striple:
1530  i_fraction = i_fraction + i_increment;
1531  i = i + 1;
1532  }
1533 
1534  // clockwise direction. Bit 0 will be closest to corners[1], bit 7
1535  // will be closest to corners[0], bit 56 closest to corners[2] and
1536  // bit 63 closest to corners[3].
1537 
1538  //Fiducials__sample_points_helper("0:7", corner0, sample_point7);
1539  //Fiducials__sample_points_helper("1:0", corner0, sample_point0);
1540  //Fiducials__sample_points_helper("2:56", corner0, sample_point56);
1541  //Fiducials__sample_points_helper("3:63", corner0, sample_point63);
1542 }
1543 
1544 // Used in *Fiducials__sample_points*() for debugging:
1545 //
1546 //void Fiducials__sample_points_helper(
1547 // String_Const label, CV_Point2D32F corner, CV_Point2D32F sample_point) {
1548 // double corner_x = CV_Point2D32F__x_get(corner);
1549 // double corner_y = CV_Point2D32F__y_get(corner);
1550 // double sample_point_x = CV_Point2D32F__x_get(sample_point);
1551 // double sample_point_y = CV_Point2D32F__y_get(sample_point);
1552 // File__format(stderr, "Label: %s corner: %f:%f sample_point %f:%f\n",
1553 // label, (int)corner_x, (int)corner_y,
1554 // (int)sample_point_x, (int)sample_point_y);
1555 //}
1556 
1558 {
1559  (String_Const)0, // fiducials_path
1560  (void *)0, // announce_object
1561  (Fiducials_Fiducial_Announce_Routine)0, // fiducial_announce_routine
1562  (String_Const)0, // log_file_name
1563 };
1564 
1571 
1573 {
1574  return &fiducials_create_struct;
1575 }
void CV_Point2D32F__x_set(CV_Point2D32F point, double x)
Definition: CV.cpp:818
CV_Point2D32F_Vector sample_points
Definition: Fiducials.hpp:60
CvScalar * CV_Scalar
Definition: CV.hpp:24
CV_Point2D32F_Vector corners
Definition: Fiducials.hpp:37
int CV__gaussian
Definition: CV.cpp:165
int CV__rgb_to_gray
Definition: CV.cpp:51
CV_Memory_Storage CV_Memory_Storage__create(int block_size)
Definition: CV.cpp:769
void CV_Image__copy(CV_Image source_image, CV_Image destination_image, CV_Image mask)
Definition: CV.cpp:390
static struct Fiducials_Create__Struct fiducials_create_struct
Definition: Fiducials.cpp:1557
int CV_Sequence__total_get(CV_Sequence sequence)
Definition: CV.cpp:916
CV_Image temporary_gray_image
Definition: Fiducials.hpp:66
void Memory__free(Memory memory)
Releases the storage associated with memory.
Definition: Memory.cpp:60
CV_Image debug_image
Definition: Fiducials.hpp:39
void String__free(String_Const string)
will free memory assciated with string.
Definition: String.cpp:65
Fiducials_Fiducial_Announce_Routine fiducial_announce_routine
Definition: Fiducials.hpp:75
void CV_Memory_Storage__clear(CV_Memory_Storage storage)
Definition: CV.cpp:765
CvSize * CV_Size
Definition: CV.hpp:26
double CV_Point2D32F__y_get(CV_Point2D32F point)
Definition: CV.cpp:822
void CV_Image__smooth(CV_Image source_image, CV_Image destination_image, int smooth_type, int parameter1, int parameter2, double parameter3, double parameter4)
Definition: CV.cpp:539
unsigned int debug_index
Definition: Fiducials.hpp:40
void Fiducials__image_show(Fiducials fiducials, bool show)
Is a HighGUI interface to show the current image.
Definition: Fiducials.cpp:451
int CV_Point__y_get(CV_Point point)
Definition: CV.cpp:793
String_Const fiducials_path
Definition: Fiducials.hpp:73
int CV__depth_8u
Definition: CV.cpp:22
Definition: FEC.hpp:44
int CV_Point__x_get(CV_Point point)
Definition: CV.cpp:785
void CV_Point2D32F__point_set(CV_Point2D32F point2d32f, CV_Point point)
Definition: CV.cpp:830
int Fiducials__points_minimum(Fiducials fiducials, CV_Point2D32F_Vector points, unsigned int start_index, unsigned int end_index)
Return the minimum value of the points in points.
Definition: Fiducials.cpp:1418
CV_Term_Criteria term_criteria
Definition: Fiducials.hpp:67
CvPoint2D32f * CV_Point2D32F
Definition: CV.hpp:22
FILE * File
FILE is a file I/O object.
Definition: File.hpp:12
void * announce_object
Definition: Fiducials.hpp:33
CV_Sequence CV_Sequence__approximate_polygon(CV_Sequence contour, int header_size, CV_Memory_Storage storage, int method, int parameter1, double parameter2)
Definition: CV.cpp:885
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)
Definition: CV.cpp:484
int CV__poly_approx_dp
Definition: CV.cpp:883
CV_Sequence CV_Image__find_contours(CV_Image image, CV_Memory_Storage storage, int header_size, int mode, int method, CV_Point point)
Definition: CV.cpp:454
CV_Term_Criteria CV_Term_Criteria__create(int type, int maximum_iterations, double epsilon)
Definition: CV.cpp:948
String_Const path
Definition: Fiducials.hpp:55
void CV_Scalar__free(CV_Scalar cv_scalar)
Definition: CV.cpp:870
CV_Image gray_image
Definition: Fiducials.hpp:43
CvPoint2D32f * CV_Point2D32F_Vector
Definition: CV.hpp:23
CV_Memory_Storage storage
Definition: Fiducials.hpp:64
int CV__term_criteria_iterations
Definition: CV.cpp:945
Fiducials_Fiducial_Announce_Routine fiducial_announce_routine
Definition: Fiducials.hpp:48
bool CV_Point2D32F_Vector__is_clockwise(CV_Point2D32F_Vector corners)
Return true if corners is in a clockwise direction.
Definition: Fiducials.cpp:1253
int CV_Image__width_get(CV_Image image)
Definition: CV.cpp:741
Fiducials_Results results
Definition: Fiducials.hpp:59
CvMemStorage * CV_Memory_Storage
Definition: CV.hpp:20
bool tag_bits[64]
Definition: Fiducials.hpp:65
int CV__gray_to_rgb
Definition: CV.cpp:53
IplImage * CV_Image
Definition: CV.hpp:18
#define Memory__new(Type, from)
Allocate a Type object from the heap.
Definition: Memory.hpp:23
CV_Scalar blue
Definition: Fiducials.hpp:35
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...
Definition: File.cpp:107
CV_Image CV_Image__create(CV_Size size, unsigned int depth, unsigned int channels)
Definition: CV.cpp:377
int CV__thresh_binary
Definition: CV.cpp:113
char * String
Copyright (c) 2013-2014 by Wayne C. Gramlich. All rights reserved.
Definition: String.hpp:8
void(* Fiducials_Fiducial_Announce_Routine)(void *announce_object, int id, int direction, double world_diagonal, double x1, double y1, double x2, double y2, double x3, double y3, double x4, double y4)
Definition: Fiducials.hpp:13
CV_Point2D32F CV_Point2D32F_Vector__fetch1(CV_Point2D32F_Vector vector, unsigned int index)
Definition: CV.cpp:853
Fiducials Fiducials__create(CV_Image original_image, Fiducials_Create fiducials_create)
Create and return a Fiducials object.
Definition: Fiducials.cpp:556
CV_Point CV_Sequence__point_fetch1(CV_Sequence sequence, unsigned int index)
Definition: CV.cpp:912
int Fiducials__points_maximum(Fiducials fiducials, CV_Point2D32F_Vector points, unsigned int start_index, unsigned int end_index)
Return the maximum value of the points in points.
Definition: Fiducials.cpp:1386
CV_Scalar CV_Scalar__rgb(double red, double green, double blue)
Definition: CV.cpp:877
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)
Definition: CV.cpp:347
CV_Image original_image
Definition: Fiducials.hpp:51
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)
Definition: CV.cpp:533
int CV_Image__gray_fetch(CV_Image image, int x, int y)
Definition: CV.cpp:475
int CV_Image__height_get(CV_Image image)
Definition: CV.cpp:498
void CV_Image__convert_color(CV_Image source_image, CV_Image destination_image, int conversion_code)
Definition: CV.cpp:385
bool CV_Sequence__check_contour_convexity(CV_Sequence contour)
Definition: CV.cpp:899
void Fiducials__fiducial_announce(void *announce_object, int id, int direction, double world_diagonal, double x1, double y1, double x2, double y2, double x3, double y3, double x4, double y4)
Callback routine tthat prints out the fidicial information.
Definition: Fiducials.cpp:410
Fiducials_Create Fiducials_Create__one_and_only(void)
Returns the one and only Fiducials_Create object.
Definition: Fiducials.cpp:1572
CV_Scalar purple
Definition: Fiducials.hpp:56
CV_Point2D32F_Vector Fiducials__references_compute(Fiducials fiducials, CV_Point2D32F_Vector corners)
Return 8 sample locations to determine if a quadralateral is worth testing for quadralateral&#39;ness.
Definition: Fiducials.cpp:1295
unsigned int sequence_number
Definition: Fiducials.hpp:61
int CV__round(double value)
Definition: CV.cpp:290
int CV__term_criteria_eps
Definition: CV.cpp:946
FEC FEC__create(unsigned int symbol_size, unsigned int data_size, unsigned int parity_size)
Definition: FEC.cpp:653
CV_Point CV_Point__create(int x, int y)
Definition: CV.cpp:775
CV_Size size_m1xm1
Definition: Fiducials.hpp:63
unsigned int CRC__compute(unsigned int *buffer, unsigned int size)
Returns a 16-bit CRC of the size bytes in buffer.
Definition: CRC.cpp:58
Fiducials_Results Fiducials__process(Fiducials fiducials)
Process the current image associated with fiducials.
Definition: Fiducials.cpp:748
void * Memory
Memory is a pointer to memory.
Definition: Memory.hpp:27
CV_Slice CV__whole_seq
Definition: CV.cpp:13
unsigned int weights_index
Definition: Fiducials.hpp:68
CV_Sequence CV_Sequence__next_get(CV_Sequence sequence)
Definition: CV.cpp:908
int CV__chain_approx_simple
Definition: CV.cpp:445
CvPoint * CV_Point
Definition: CV.hpp:21
File File__open(String_Const file_name, String_Const flags)
will open file_name using flags to specify read/write options.
Definition: File.cpp:243
CV_Size image_size
Definition: Fiducials.hpp:45
void Fiducials__map_save(Fiducials fiducials)
Force the map associated with fiducials to be saved.
Definition: Fiducials.cpp:737
void CV_Point2D32F__y_set(CV_Point2D32F point, double y)
Definition: CV.cpp:826
int CV__adaptive_thresh_gaussian_c
Definition: CV.cpp:112
CV_Image edge_image
Definition: Fiducials.hpp:41
CvSeq * CV_Sequence
Definition: CV.hpp:25
CV_Scalar black
Definition: Fiducials.hpp:34
CV_Point2D32F_Vector CV_Point2D32F_Vector__create(unsigned int size)
Definition: CV.cpp:839
double CV_Sequence__arc_length(CV_Sequence contour, CV_Slice slice, int is_closed)
Definition: CV.cpp:894
CV_Size CV_Size__create(int width, int height)
Definition: CV.cpp:922
void CV_Size__free(CV_Size cv_size)
Definition: CV.cpp:929
CV_Scalar cyan
Definition: Fiducials.hpp:38
const char * String_Const
Definition: String.hpp:9
CV_Point2D32F_Vector references
Definition: Fiducials.hpp:58
double CV_Sequence__contour_area(CV_Sequence contour, CV_Slice slice, int oriented)
Definition: CV.cpp:903
int CV__window_auto_size
Definition: CV.cpp:35
void CV_Image__cross_draw(CV_Image image, int x, int y, CV_Scalar color)
Definition: CV.cpp:395
int CV__retr_list
Definition: CV.cpp:438
String_Const log_file_name
Definition: Fiducials.hpp:76
void Fiducials__sample_points_compute(CV_Point2D32F_Vector corners, CV_Point2D32F_Vector sample_points)
Compute the fiducial locations to sample using corners
Definition: Fiducials.cpp:1452
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)
Definition: CV.cpp:429
double CV_Point2D32F__x_get(CV_Point2D32F point)
Definition: CV.cpp:814
void CV_Point2D32F_Vector__corners_normalize(CV_Point2D32F_Vector corners)
Force corners to be counter-clockwise.
Definition: Fiducials.cpp:1223
CvSlice * CV_Slice
Definition: CV.hpp:27
static CvSlice whole_sequence
Definition: CV.cpp:12
int Fiducials__point_sample(Fiducials fiducials, CV_Point2D32F point)
Helper routine to sample a point from the image in fiducials.
Definition: Fiducials.cpp:1145
bool FEC__correct(FEC fec, unsigned int *data, unsigned int size)
Definition: FEC.cpp:604
void Fiducials__image_set(Fiducials fiducials, CV_Image image)
Sets the original image for *fiducials.
Definition: Fiducials.cpp:427
void Fiducials__free(Fiducials fiducials)
will release the storage associated with fiducials.
Definition: Fiducials.cpp:713
CV_Scalar green
Definition: Fiducials.hpp:44
int CV_Image__channels_get(CV_Image image)
Definition: CV.cpp:381
String String__format(String_Const format,...)
Return a formatted version of format.
Definition: String.cpp:43
void CV__release_image(CV_Image image)
Definition: CV.cpp:265


fiducial_lib
Author(s): Wayne Gramlich
autogenerated on Thu Dec 28 2017 04:06:53