Now you can download a copy of these docs so you can use them offline! Download now
VisionAPI.cpp
1 /********************************************************************************
2 * Project : FIRST Motor Controller
3 * File Name : VisionAPI.cpp
4 * Contributors : ELF, EMF
5 * Creation Date : June 26, 2008
6 * Revision History : Source code & revision history maintained at sourceforge.WPI.edu
7 * File Description : C Routines for FIRST Vision API. Open source API developed
8 * by BAE Systems to interface with the National Instruments vision C library
9 * in the nivision.out module. The published interface to nivision.out is in
10 * the header file nivision.h and documented in the NIVisionCVI.chm help file.
11 */
12 /*----------------------------------------------------------------------------*/
13 /* Copyright (c) FIRST 2008. All Rights Reserved. */
14 /* Open Source Software - may be modified and shared by FRC teams. The code */
15 /* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
16 /*----------------------------------------------------------------------------*/
17 
18 #include "stdioLib.h"
19 #include "vxWorks.h"
20 
21 #include "BaeUtilities.h"
22 #include "FrcError.h"
23 #include "VisionAPI.h"
24 
25 int VisionAPI_debugFlag = 1;
26 #define DPRINTF if(VisionAPI_debugFlag)dprintf
27 
28 /* Image Management functions */
29 
40 Image* frcCreateImage(ImageType type) { return imaqCreateImage(type, DEFAULT_BORDER_SIZE); }
41 
48 int frcDispose(void* object) { return imaqDispose(object); }
58 int frcDispose( const char* functionName, ... ) /* Variable argument list */
59 {
60  va_list disposalPtrList; /* Input argument list */
61  void* disposalPtr; /* For iteration */
62  int success, returnValue = 1;
63 
64  va_start( disposalPtrList, functionName ); /* start of variable list */
65  disposalPtr = va_arg( disposalPtrList, void* );
66  while( disposalPtr != NULL ) {
67  success = imaqDispose(disposalPtr);
68  if (!success) {returnValue = 0;}
69  disposalPtr = va_arg( disposalPtrList, void* );
70  }
71  return returnValue;
72 }
73 
84 int frcCopyImage(Image* dest, const Image* source) { return imaqDuplicate(dest, source); }
85 
96 int frcCrop(Image* dest, const Image* source, Rect rect)
97 {
98  return imaqScale(dest, source, 1, 1, IMAQ_SCALE_LARGER, rect);
99 }
100 
101 
114 int frcScale(Image* dest, const Image* source, int xScale, int yScale, ScalingMode scaleMode)
115 {
116  Rect rect = IMAQ_NO_RECT;
117  return imaqScale(dest, source, xScale, yScale, scaleMode, rect);
118 }
119 
130  int frcReadImage(Image* image, const char* fileName)
131  {
132  return imaqReadFile(image, fileName, NULL, NULL);
133  }
134 
135 
163 int frcWriteImage(const Image* image, const char* fileName)
164 {
165  RGBValue* colorTable = NULL;
166  return imaqWriteFile(image, fileName, colorTable);
167 }
168 
169 
170 /* Measure Intensity functions */
171 
200 HistogramReport* frcHistogram(const Image* image, int numClasses, float min, float max)
201 {
202  Rect rect = IMAQ_NO_RECT;
203  return frcHistogram(image, numClasses, min, max, rect);
204 }
205 HistogramReport* frcHistogram(const Image* image, int numClasses, float min, float max, Rect rect)
206 {
207  int success;
208  int fillValue = 1;
209 
210  /* create the region of interest */
211  ROI* pRoi = imaqCreateROI();
212  success = imaqAddRectContour(pRoi, rect);
213  if ( !success ) { GetLastVisionError(); return NULL; }
214 
215  /* make a mask from the ROI */
216  Image* pMask = frcCreateImage(IMAQ_IMAGE_U8);
217  success = imaqROIToMask(pMask, pRoi, fillValue, NULL, NULL);
218  if ( !success ) {
219  GetLastVisionError();
220  frcDispose(__FUNCTION__, pRoi, NULL);
221  return NULL;
222  }
223 
224  /* get a histogram report */
225  HistogramReport* pHr = NULL;
226  pHr = imaqHistogram(image, numClasses, min, max, pMask);
227 
228  /* clean up */
229  frcDispose(__FUNCTION__, pRoi, pMask, NULL);
230 
231  return pHr;
232 }
233 
253 ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode)
254 {
255  return frcColorHistogram(image, numClasses, mode, NULL);
256 }
257 
258 ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode, Image* mask)
259 {
260  return imaqColorHistogram2((Image*)image, numClasses, mode, NULL, mask);
261 }
262 
263 
275 int frcGetPixelValue(const Image* image, Point pixel, PixelValue* value)
276 {
277  return imaqGetPixel(image, pixel, value);
278 }
279 
280 
281 /* Particle Analysis functions */
282 
297 int frcParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria2* criteria,
298  int criteriaCount, const ParticleFilterOptions* options, int* numParticles)
299 {
300  Rect rect = IMAQ_NO_RECT;
301  return frcParticleFilter(dest, source, criteria, criteriaCount, options, rect, numParticles);
302 }
303 
304 int frcParticleFilter(Image* dest, Image* source, const ParticleFilterCriteria2* criteria,
305  int criteriaCount, const ParticleFilterOptions* options, Rect rect, int* numParticles)
306 {
307  ROI* roi = imaqCreateROI();
308  imaqAddRectContour(roi, rect);
309  return imaqParticleFilter3(dest, source, criteria, criteriaCount, options, roi, numParticles);
310 }
311 
312 
327 int frcMorphology(Image* dest, Image* source, MorphologyMethod method)
328 {
329  return imaqMorphology(dest, source, method, NULL);
330 }
331 
332 int frcMorphology(Image* dest, Image* source, MorphologyMethod method, const StructuringElement* structuringElement)
333 {
334  return imaqMorphology(dest, source, method, structuringElement);
335 }
336 
350 int frcRejectBorder(Image* dest, Image* source)
351 { return imaqRejectBorder(dest, source, TRUE); }
352 
353 int frcRejectBorder(Image* dest, Image* source, int connectivity8)
354 {
355  return imaqRejectBorder(dest, source, connectivity8);
356 }
357 
358 
366 int frcCountParticles(Image* image, int* numParticles)
367 {
368  return imaqCountParticles(image, 1, numParticles);
369 }
370 
371 
382 int frcParticleAnalysis(Image* image, int particleNumber, ParticleAnalysisReport* par)
383 {
384  int success = 0;
385 
386  /* image information */
387  int height, width;
388  if ( ! imaqGetImageSize(image, &width, &height) ) { return success; }
389  par->imageWidth = width;
390  par->imageHeight = height;
391  par->particleIndex = particleNumber;
392 
393  /* center of mass point of the largest particle */
394  double returnDouble;
395  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_CENTER_OF_MASS_X, &returnDouble);
396  if ( !success ) { return success; }
397  par->center_mass_x = (int)returnDouble; // pixel
398 
399  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_CENTER_OF_MASS_Y, &returnDouble);
400  if ( !success ) { return success; }
401  par->center_mass_y = (int)returnDouble; // pixel
402 
403  /* particle size statistics */
404  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA, &returnDouble);
405  if ( !success ) { return success; }
406  par->particleArea = returnDouble;
407 
408  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_TOP, &returnDouble);
409  if ( !success ) { return success; }
410  par->boundingRect.top = (int)returnDouble;
411 
412  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_LEFT, &returnDouble);
413  if ( !success ) { return success; }
414  par->boundingRect.left = (int)returnDouble;
415 
416  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_HEIGHT, &returnDouble);
417  if ( !success ) { return success; }
418  par->boundingRect.height = (int)returnDouble;
419 
420  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_BOUNDING_RECT_WIDTH, &returnDouble);
421  if ( !success ) { return success; }
422  par->boundingRect.width = (int)returnDouble;
423 
424  /* particle quality statistics */
425  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA_BY_IMAGE_AREA, &returnDouble);
426  if ( !success ) { return success; }
427  par->particleToImagePercent = returnDouble;
428 
429  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA, &returnDouble);
430  if ( !success ) { return success; }
431  par->particleQuality = returnDouble;
432 
433  /* normalized position (-1 to 1) */
434  par->center_mass_x_normalized = RangeToNormalized(par->center_mass_x, width);
435  par->center_mass_y_normalized = RangeToNormalized(par->center_mass_y, height);
436 
437  return success;
438 }
439 
440 
441 /* Image Enhancement functions */
442 
457 int frcEqualize(Image* dest, const Image* source, float min, float max)
458 { return frcEqualize(dest, source, min, max, NULL); }
459 
460 int frcEqualize(Image* dest, const Image* source, float min, float max, const Image* mask)
461 {
462  return imaqEqualize(dest, source, min, max, mask);
463 }
464 
475 int frcColorEqualize(Image* dest, const Image* source)
476 {
477  return imaqColorEqualize(dest, source, TRUE);
478 }
479 
480 int frcColorEqualize(Image* dest, const Image* source, int colorEqualization)
481 {
482  return imaqColorEqualize(dest, source, TRUE);
483 }
484 
485 /* Image Conversion functions */
486 
510 int frcSmartThreshold(Image* dest, const Image* source,
511  unsigned int windowWidth, unsigned int windowHeight, LocalThresholdMethod method,
512  double deviationWeight, ObjectType type)
513 {
514  float replaceValue = 1.0;
515  return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method,
516  deviationWeight, type, replaceValue);
517 }
518 
519 int frcSmartThreshold(Image* dest, const Image* source,
520  unsigned int windowWidth, unsigned int windowHeight, LocalThresholdMethod method,
521  double deviationWeight, ObjectType type, float replaceValue)
522 {
523  return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method,
524  deviationWeight, type, replaceValue);
525 }
526 
541 int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax)
542 {
543  int newValue = 255;
544  return frcSimpleThreshold(dest, source, rangeMin, rangeMax, newValue);
545 }
546 
561 int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin, float rangeMax, float newValue)
562 {
563  int useNewValue = TRUE;
564  return imaqThreshold(dest, source, rangeMin, rangeMax, useNewValue, newValue);
565 }
566 
582 int frcColorThreshold(Image* dest, const Image* source, ColorMode mode,
583  const Range* plane1Range, const Range* plane2Range, const Range* plane3Range)
584 {
585  int replaceValue = 1;
586  return imaqColorThreshold(dest, source, replaceValue, mode, plane1Range, plane2Range, plane3Range);
587 }
588 
605 int frcColorThreshold(Image* dest, const Image* source, int replaceValue, ColorMode mode,
606  const Range* plane1Range, const Range* plane2Range, const Range* plane3Range)
607 { return imaqColorThreshold(dest, source, replaceValue, mode, plane1Range, plane2Range, plane3Range);}
608 
609 
619 int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange)
620 { return frcHueThreshold(dest, source, hueRange, DEFAULT_SATURATION_THRESHOLD); }
621 
622 int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange, int minSaturation)
623 {
624  // assume HSL mode
625  ColorMode mode = IMAQ_HSL;
626  // Set saturation 100 - 255
627  Range satRange; satRange.minValue = minSaturation; satRange.maxValue = 255;
628  // Set luminance 100 - 255
629  Range lumRange; lumRange.minValue = 100; lumRange.maxValue = 255;
630  // Replace pixels with 1 if pass threshold filter
631  int replaceValue = 1;
632  return imaqColorThreshold(dest, source, replaceValue, mode, hueRange, &satRange, &lumRange);
633 }
634 
647 int frcExtractColorPlanes(const Image* image, ColorMode mode,
648  Image* plane1, Image* plane2, Image* plane3)
649 { return imaqExtractColorPlanes(image, mode, plane1, plane2, plane3); }
650 
660 int frcExtractHuePlane(const Image* image, Image* huePlane)
661 {
662  return frcExtractHuePlane(image, huePlane, DEFAULT_SATURATION_THRESHOLD);
663 }
664 
665 int frcExtractHuePlane(const Image* image, Image* huePlane, int minSaturation)
666 {
667  return frcExtractColorPlanes(image, IMAQ_HSL, huePlane, NULL, NULL);
668 }
669 
670 
671 
672 
673 
674 
675 
676 

Generated on Sat Apr 26 2014 12:26:45 for WPILibC++ by doxygen 1.8.6