Squashed 'third_party/allwpilib_2016/' content from commit 7f61816

Change-Id: If9d9245880859cdf580f5d7f77045135d0521ce7
git-subtree-dir: third_party/allwpilib_2016
git-subtree-split: 7f618166ed253a24629934fcf89c3decb0528a3b
diff --git a/wpilibc/Athena/include/Vision/AxisCamera.h b/wpilibc/Athena/include/Vision/AxisCamera.h
new file mode 100644
index 0000000..b315938
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/AxisCamera.h
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <thread>
+#include <string>
+#include "HAL/cpp/priority_mutex.h"
+
+#include "ErrorBase.h"
+#include "Vision/ColorImage.h"
+#include "Vision/HSLImage.h"
+#include "nivision.h"
+
+/**
+ * Axis M1011 network camera
+ */
+class AxisCamera : public ErrorBase {
+ public:
+  enum WhiteBalance {
+    kWhiteBalance_Automatic,
+    kWhiteBalance_Hold,
+    kWhiteBalance_FixedOutdoor1,
+    kWhiteBalance_FixedOutdoor2,
+    kWhiteBalance_FixedIndoor,
+    kWhiteBalance_FixedFluorescent1,
+    kWhiteBalance_FixedFluorescent2
+  };
+
+  enum ExposureControl {
+    kExposureControl_Automatic,
+    kExposureControl_Hold,
+    kExposureControl_FlickerFree50Hz,
+    kExposureControl_FlickerFree60Hz
+  };
+
+  enum Resolution {
+    kResolution_640x480,
+    kResolution_480x360,
+    kResolution_320x240,
+    kResolution_240x180,
+    kResolution_176x144,
+    kResolution_160x120,
+  };
+
+  enum Rotation { kRotation_0, kRotation_180 };
+
+  explicit AxisCamera(std::string const &cameraHost);
+  virtual ~AxisCamera();
+
+  AxisCamera(const AxisCamera&) = delete;
+  AxisCamera& operator=(const AxisCamera&) = delete;
+
+  bool IsFreshImage() const;
+
+  int GetImage(Image *image);
+  int GetImage(ColorImage *image);
+  HSLImage *GetImage();
+  int CopyJPEG(char **destImage, unsigned int &destImageSize,
+               unsigned int &destImageBufferSize);
+
+  void WriteBrightness(int brightness);
+  int GetBrightness();
+
+  void WriteWhiteBalance(WhiteBalance whiteBalance);
+  WhiteBalance GetWhiteBalance();
+
+  void WriteColorLevel(int colorLevel);
+  int GetColorLevel();
+
+  void WriteExposureControl(ExposureControl exposureControl);
+  ExposureControl GetExposureControl();
+
+  void WriteExposurePriority(int exposurePriority);
+  int GetExposurePriority();
+
+  void WriteMaxFPS(int maxFPS);
+  int GetMaxFPS();
+
+  void WriteResolution(Resolution resolution);
+  Resolution GetResolution();
+
+  void WriteCompression(int compression);
+  int GetCompression();
+
+  void WriteRotation(Rotation rotation);
+  Rotation GetRotation();
+
+ private:
+  std::thread m_captureThread;
+  std::string m_cameraHost;
+  int m_cameraSocket = -1;
+  priority_mutex m_captureMutex;
+
+  priority_mutex m_imageDataMutex;
+  std::vector<uint8_t> m_imageData;
+  bool m_freshImage = false;
+
+  int m_brightness = 50;
+  WhiteBalance m_whiteBalance = kWhiteBalance_Automatic;
+  int m_colorLevel = 50;
+  ExposureControl m_exposureControl = kExposureControl_Automatic;
+  int m_exposurePriority = 50;
+  int m_maxFPS = 0;
+  Resolution m_resolution = kResolution_640x480;
+  int m_compression = 50;
+  Rotation m_rotation = kRotation_0;
+  bool m_parametersDirty = true;
+  bool m_streamDirty = true;
+  priority_mutex m_parametersMutex;
+
+  bool m_done = false;
+
+  void Capture();
+  void ReadImagesFromCamera();
+  bool WriteParameters();
+
+  int CreateCameraSocket(std::string const &requestString, bool setError);
+};
diff --git a/wpilibc/Athena/include/Vision/BaeUtilities.h b/wpilibc/Athena/include/Vision/BaeUtilities.h
new file mode 100644
index 0000000..8983ef4
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/BaeUtilities.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/*  Constants */
+#define LOG_DEBUG __FILE__, __FUNCTION__, __LINE__, DEBUG_TYPE
+#define LOG_INFO __FILE__, __FUNCTION__, __LINE__, INFO_TYPE
+#define LOG_ERROR __FILE__, __FUNCTION__, __LINE__, ERROR_TYPE
+#define LOG_CRITICAL __FILE__, __FUNCTION__, __LINE__, CRITICAL_TYPE
+#define LOG_FATAL __FILE__, __FUNCTION__, __LINE__, FATAL_TYPE
+#define LOG_DEBUG __FILE__, __FUNCTION__, __LINE__, DEBUG_TYPE
+
+/*   Enumerated Types */
+
+/** debug levels */
+enum dprint_type {
+  DEBUG_TYPE,
+  INFO_TYPE,
+  ERROR_TYPE,
+  CRITICAL_TYPE,
+  FATAL_TYPE
+};
+
+/** debug output setting */
+typedef enum DebugOutputType_enum {
+  DEBUG_OFF,
+  DEBUG_MOSTLY_OFF,
+  DEBUG_SCREEN_ONLY,
+  DEBUG_FILE_ONLY,
+  DEBUG_SCREEN_AND_FILE
+} DebugOutputType;
+
+/*  Enumerated Types */
+
+/* Utility functions */
+
+/* debug */
+void SetDebugFlag(DebugOutputType flag);
+void dprintf(const char *tempString, ...); /* Variable argument list */
+
+/* set FRC ranges for drive */
+double RangeToNormalized(double pixel, int range);
+/* change normalized value to any range - used for servo */
+float NormalizeToRange(float normalizedValue, float minRange, float maxRange);
+float NormalizeToRange(float normalizedValue);
+
+/* system utilities */
+void ShowActivity(char *fmt, ...);
+double ElapsedTime(double startTime);
+
+/* servo panning utilities */
+class Servo;
+double SinPosition(double *period, double sinStart);
+void panInit();
+void panInit(double period);
+void panForTarget(Servo *panServo);
+void panForTarget(Servo *panServo, double sinStart);
+
+/* config file read utilities */
+int processFile(char *inputFile, char *outputString, int lineNumber);
+int emptyString(char *string);
+void stripString(char *string);
diff --git a/wpilibc/Athena/include/Vision/BinaryImage.h b/wpilibc/Athena/include/Vision/BinaryImage.h
new file mode 100644
index 0000000..8b7b25c
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/BinaryImage.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "MonoImage.h"
+/**
+ * Included for ParticleAnalysisReport definition
+ * TODO: Eliminate this dependency!
+ */
+#include "Vision/VisionAPI.h"
+
+#include <vector>
+#include <algorithm>
+
+class BinaryImage : public MonoImage {
+ public:
+  virtual ~BinaryImage() = default;
+  int GetNumberParticles();
+  ParticleAnalysisReport GetParticleAnalysisReport(int particleNumber);
+  void GetParticleAnalysisReport(int particleNumber,
+                                 ParticleAnalysisReport *par);
+  std::vector<ParticleAnalysisReport> *GetOrderedParticleAnalysisReports();
+  BinaryImage *RemoveSmallObjects(bool connectivity8, int erosions);
+  BinaryImage *RemoveLargeObjects(bool connectivity8, int erosions);
+  BinaryImage *ConvexHull(bool connectivity8);
+  BinaryImage *ParticleFilter(ParticleFilterCriteria2 *criteria,
+                              int criteriaCount);
+  virtual void Write(const char *fileName);
+
+ private:
+  bool ParticleMeasurement(int particleNumber, MeasurementType whatToMeasure,
+                           int *result);
+  bool ParticleMeasurement(int particleNumber, MeasurementType whatToMeasure,
+                           double *result);
+  static double NormalizeFromRange(double position, int range);
+  static bool CompareParticleSizes(ParticleAnalysisReport particle1,
+                                   ParticleAnalysisReport particle2);
+};
diff --git a/wpilibc/Athena/include/Vision/ColorImage.h b/wpilibc/Athena/include/Vision/ColorImage.h
new file mode 100644
index 0000000..0304ad8
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/ColorImage.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ImageBase.h"
+#include "BinaryImage.h"
+#include "Threshold.h"
+
+class ColorImage : public ImageBase {
+ public:
+  ColorImage(ImageType type);
+  virtual ~ColorImage() = default;
+  BinaryImage *ThresholdRGB(int redLow, int redHigh, int greenLow,
+                            int greenHigh, int blueLow, int blueHigh);
+  BinaryImage *ThresholdHSL(int hueLow, int hueHigh, int saturationLow,
+                            int saturationHigh, int luminenceLow,
+                            int luminenceHigh);
+  BinaryImage *ThresholdHSV(int hueLow, int hueHigh, int saturationLow,
+                            int saturationHigh, int valueHigh, int valueLow);
+  BinaryImage *ThresholdHSI(int hueLow, int hueHigh, int saturationLow,
+                            int saturationHigh, int intensityLow,
+                            int intensityHigh);
+  BinaryImage *ThresholdRGB(Threshold &threshold);
+  BinaryImage *ThresholdHSL(Threshold &threshold);
+  BinaryImage *ThresholdHSV(Threshold &threshold);
+  BinaryImage *ThresholdHSI(Threshold &threshold);
+  MonoImage *GetRedPlane();
+  MonoImage *GetGreenPlane();
+  MonoImage *GetBluePlane();
+  MonoImage *GetHSLHuePlane();
+  MonoImage *GetHSVHuePlane();
+  MonoImage *GetHSIHuePlane();
+  MonoImage *GetHSLSaturationPlane();
+  MonoImage *GetHSVSaturationPlane();
+  MonoImage *GetHSISaturationPlane();
+  MonoImage *GetLuminancePlane();
+  MonoImage *GetValuePlane();
+  MonoImage *GetIntensityPlane();
+  void ReplaceRedPlane(MonoImage *plane);
+  void ReplaceGreenPlane(MonoImage *plane);
+  void ReplaceBluePlane(MonoImage *plane);
+  void ReplaceHSLHuePlane(MonoImage *plane);
+  void ReplaceHSVHuePlane(MonoImage *plane);
+  void ReplaceHSIHuePlane(MonoImage *plane);
+  void ReplaceHSLSaturationPlane(MonoImage *plane);
+  void ReplaceHSVSaturationPlane(MonoImage *plane);
+  void ReplaceHSISaturationPlane(MonoImage *plane);
+  void ReplaceLuminancePlane(MonoImage *plane);
+  void ReplaceValuePlane(MonoImage *plane);
+  void ReplaceIntensityPlane(MonoImage *plane);
+  void ColorEqualize();
+  void LuminanceEqualize();
+
+ private:
+  BinaryImage *ComputeThreshold(ColorMode colorMode, int low1, int high1,
+                                int low2, int high2, int low3, int high3);
+  void Equalize(bool allPlanes);
+  MonoImage *ExtractColorPlane(ColorMode mode, int planeNumber);
+  MonoImage *ExtractFirstColorPlane(ColorMode mode);
+  MonoImage *ExtractSecondColorPlane(ColorMode mode);
+  MonoImage *ExtractThirdColorPlane(ColorMode mode);
+  void ReplacePlane(ColorMode mode, MonoImage *plane, int planeNumber);
+  void ReplaceFirstColorPlane(ColorMode mode, MonoImage *plane);
+  void ReplaceSecondColorPlane(ColorMode mode, MonoImage *plane);
+  void ReplaceThirdColorPlane(ColorMode mode, MonoImage *plane);
+};
diff --git a/wpilibc/Athena/include/Vision/FrcError.h b/wpilibc/Athena/include/Vision/FrcError.h
new file mode 100644
index 0000000..0897c84
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/FrcError.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/* Error Codes */
+#define ERR_VISION_GENERAL_ERROR 166000  //
+#define ERR_COLOR_NOT_FOUND 166100       // TrackAPI.cpp
+#define ERR_PARTICLE_TOO_SMALL 166101    // TrackAPI.cpp
+
+#define ERR_CAMERA_FAILURE 166200                  // AxisCamera.cpp
+#define ERR_CAMERA_SOCKET_CREATE_FAILED 166201     // AxisCamera.cpp
+#define ERR_CAMERA_CONNECT_FAILED 166202           // AxisCamera.cpp
+#define ERR_CAMERA_STALE_IMAGE 166203              // AxisCamera.cpp
+#define ERR_CAMERA_NOT_INITIALIZED 166204          // AxisCamera.cpp
+#define ERR_CAMERA_NO_BUFFER_AVAILABLE 166205      // AxisCamera.cpp
+#define ERR_CAMERA_HEADER_ERROR 166206             // AxisCamera.cpp
+#define ERR_CAMERA_BLOCKING_TIMEOUT 166207         // AxisCamera.cpp
+#define ERR_CAMERA_AUTHORIZATION_FAILED 166208     // AxisCamera.cpp
+#define ERR_CAMERA_TASK_SPAWN_FAILED 166209        // AxisCamera.cpp
+#define ERR_CAMERA_TASK_INPUT_OUT_OF_RANGE 166210  // AxisCamera.cpp
+#define ERR_CAMERA_COMMAND_FAILURE 166211          // AxisCamera.cpp
+
+/* error handling functions */
+int GetLastVisionError();
+const char* GetVisionErrorText(int errorCode);
diff --git a/wpilibc/Athena/include/Vision/HSLImage.h b/wpilibc/Athena/include/Vision/HSLImage.h
new file mode 100644
index 0000000..0407748
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/HSLImage.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ColorImage.h"
+
+/**
+ * A color image represented in HSL color space at 3 bytes per pixel.
+ */
+class HSLImage : public ColorImage {
+ public:
+  HSLImage();
+  HSLImage(const char *fileName);
+  virtual ~HSLImage() = default;
+};
diff --git a/wpilibc/Athena/include/Vision/ImageBase.h b/wpilibc/Athena/include/Vision/ImageBase.h
new file mode 100644
index 0000000..c20ecfe
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/ImageBase.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdio.h>
+#include "nivision.h"
+#include "ErrorBase.h"
+
+#define DEFAULT_BORDER_SIZE 3
+
+class ImageBase : public ErrorBase {
+ public:
+  ImageBase(ImageType type);
+  virtual ~ImageBase();
+  virtual void Write(const char *fileName);
+  int GetHeight();
+  int GetWidth();
+  Image *GetImaqImage();
+
+ protected:
+  Image *m_imaqImage;
+};
diff --git a/wpilibc/Athena/include/Vision/MonoImage.h b/wpilibc/Athena/include/Vision/MonoImage.h
new file mode 100644
index 0000000..d31f0a4
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/MonoImage.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ImageBase.h"
+
+#include <vector>
+
+class MonoImage : public ImageBase {
+ public:
+  MonoImage();
+  virtual ~MonoImage() = default;
+
+  std::vector<EllipseMatch> *DetectEllipses(
+      EllipseDescriptor *ellipseDescriptor, CurveOptions *curveOptions,
+      ShapeDetectionOptions *shapeDetectionOptions, ROI *roi);
+  std::vector<EllipseMatch> *DetectEllipses(
+      EllipseDescriptor *ellipseDescriptor);
+};
diff --git a/wpilibc/Athena/include/Vision/RGBImage.h b/wpilibc/Athena/include/Vision/RGBImage.h
new file mode 100644
index 0000000..cb3b3e5
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/RGBImage.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ColorImage.h"
+
+/**
+ * A color image represented in RGB color space at 3 bytes per pixel.
+ */
+class RGBImage : public ColorImage {
+ public:
+  RGBImage();
+  RGBImage(const char *fileName);
+  virtual ~RGBImage() = default;
+};
diff --git a/wpilibc/Athena/include/Vision/Threshold.h b/wpilibc/Athena/include/Vision/Threshold.h
new file mode 100644
index 0000000..83493e8
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/Threshold.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * Color threshold values.
+ * This object represnts the threshold values for any type of color object
+ * that is used in a threshhold operation. It simplifies passing values
+ * around in a program for color detection.
+ */
+class Threshold {
+ public:
+  int plane1Low;
+  int plane1High;
+  int plane2Low;
+  int plane2High;
+  int plane3Low;
+  int plane3High;
+  Threshold(int plane1Low, int plane1High, int plane2Low, int plane2High,
+            int plane3Low, int plane3High);
+};
diff --git a/wpilibc/Athena/include/Vision/VisionAPI.h b/wpilibc/Athena/include/Vision/VisionAPI.h
new file mode 100644
index 0000000..3153f1b
--- /dev/null
+++ b/wpilibc/Athena/include/Vision/VisionAPI.h
@@ -0,0 +1,172 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "nivision.h"
+
+/*   Constants */
+
+#define DEFAULT_BORDER_SIZE 3  // VisionAPI.frcCreateImage
+#define DEFAULT_SATURATION_THRESHOLD 40  // TrackAPI.FindColor
+
+/*   Forward Declare Data Structures */
+typedef struct FindEdgeOptions_struct FindEdgeOptions;
+typedef struct CircularEdgeReport_struct CircularEdgeReport;
+
+/*   Data Structures */
+
+/**  frcParticleAnalysis returns this structure */
+typedef struct ParticleAnalysisReport_struct {
+  int imageHeight;
+  int imageWidth;
+  double imageTimestamp;
+  int particleIndex;  // the particle index analyzed
+  /* X-coordinate of the point representing the average position of the
+   * total particle mass, assuming every point in the particle has a constant
+   * density */
+  int center_mass_x;  // MeasurementType: IMAQ_MT_CENTER_OF_MASS_X
+  /* Y-coordinate of the point representing the average position of the
+   * total particle mass, assuming every point in the particle has a constant
+   * density */
+  int center_mass_y;  // MeasurementType: IMAQ_MT_CENTER_OF_MASS_Y
+  double center_mass_x_normalized;  // Center of mass x value normalized to -1.0
+                                    // to +1.0 range
+  double center_mass_y_normalized;  // Center of mass y value normalized to -1.0
+                                    // to +1.0 range
+  /* Area of the particle */
+  double particleArea;  // MeasurementType: IMAQ_MT_AREA
+  /* Bounding Rectangle */
+  Rect boundingRect;  // left/top/width/height
+  /* Percentage of the particle Area covering the Image Area. */
+  double particleToImagePercent;  // MeasurementType: IMAQ_MT_AREA_BY_IMAGE_AREA
+  /* Percentage of the particle Area in relation to its Particle and Holes Area
+   */
+  double particleQuality;  // MeasurementType:
+                           // IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA
+} ParticleAnalysisReport;
+
+/** Tracking functions return this structure */
+typedef struct ColorReport_struct {
+  int numberParticlesFound;   // Number of particles found for this color
+  int largestParticleNumber;  // The particle index of the largest particle
+  /* Color information */
+  float particleHueMax;   // HistogramReport: hue max
+  float particleHueMin;   // HistogramReport: hue max
+  float particleHueMean;  // HistogramReport: hue mean
+  float particleSatMax;   // HistogramReport: saturation max
+  float particleSatMin;   // HistogramReport: saturation max
+  float particleSatMean;  // HistogramReport: saturation mean
+  float particleLumMax;   // HistogramReport: luminance max
+  float particleLumMin;   // HistogramReport: luminance  max
+  float particleLumMean;  // HistogramReport: luminance mean
+} ColorReport;
+
+/*   Image Management functions */
+
+/* Create: calls imaqCreateImage. Border size is set to some default value */
+Image* frcCreateImage(ImageType type);
+
+/* Dispose: calls imaqDispose */
+int frcDispose(void* object);
+int frcDispose(const char* filename, ...);
+
+/* Copy: calls imaqDuplicateImage */
+int frcCopyImage(Image* dest, const Image* source);
+
+/* Image Extraction: Crop: calls imaqScale */
+int frcCrop(Image* dest, const Image* source, Rect rect);
+
+/* Image Extraction: Scale: calls imaqScale.  Scales entire image */
+int frcScale(Image* dest, const Image* source, int xScale, int yScale,
+             ScalingMode scaleMode);
+
+/* Read Image : calls imaqReadFile */
+int frcReadImage(Image* image, const char* fileName);
+/* Write Image : calls imaqWriteFile */
+int frcWriteImage(const Image* image, const char* fileName);
+
+/*   Measure Intensity functions */
+
+/* Histogram: calls imaqHistogram */
+HistogramReport* frcHistogram(const Image* image, int numClasses, float min,
+                              float max, Rect rect);
+/* Color Histogram: calls imaqColorHistogram2 */
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses,
+                                        ColorMode mode, Image* mask);
+
+/* Get Pixel Value: calls imaqGetPixel */
+int frcGetPixelValue(const Image* image, Point pixel, PixelValue* value);
+
+/*   Particle Analysis functions */
+
+/* Particle Filter: calls imaqParticleFilter3 */
+int frcParticleFilter(Image* dest, Image* source,
+                      const ParticleFilterCriteria2* criteria,
+                      int criteriaCount, const ParticleFilterOptions* options,
+                      Rect rect, int* numParticles);
+int frcParticleFilter(Image* dest, Image* source,
+                      const ParticleFilterCriteria2* criteria,
+                      int criteriaCount, const ParticleFilterOptions* options,
+                      int* numParticles);
+/* Morphology: calls imaqMorphology */
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method);
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method,
+                  const StructuringElement* structuringElement);
+/* Reject Border: calls imaqRejectBorder */
+int frcRejectBorder(Image* dest, Image* source);
+int frcRejectBorder(Image* dest, Image* source, int connectivity8);
+/* Count Particles: calls imaqCountParticles */
+int frcCountParticles(Image* image, int* numParticles);
+/* Particle Analysis Report: calls imaqMeasureParticle */
+int frcParticleAnalysis(Image* image, int particleNumber,
+                        ParticleAnalysisReport* par);
+
+/*   Image Enhancement functions */
+
+/* Equalize: calls imaqEqualize */
+int frcEqualize(Image* dest, const Image* source, float min, float max);
+int frcEqualize(Image* dest, const Image* source, float min, float max,
+                const Image* mask);
+
+/* Color Equalize: calls imaqColorEqualize */
+int frcColorEqualize(Image* dest, const Image* source);
+int frcColorEqualize(Image* dest, const Image* source, int colorEqualization);
+
+/*   Image Thresholding & Conversion functions */
+
+/* Smart Threshold: calls imaqLocalThreshold */
+int frcSmartThreshold(Image* dest, const Image* source,
+                      unsigned int windowWidth, unsigned int windowHeight,
+                      LocalThresholdMethod method, double deviationWeight,
+                      ObjectType type);
+int frcSmartThreshold(Image* dest, const Image* source,
+                      unsigned int windowWidth, unsigned int windowHeight,
+                      LocalThresholdMethod method, double deviationWeight,
+                      ObjectType type, float replaceValue);
+
+/* Simple Threshold: calls imaqThreshold */
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin,
+                       float rangeMax, float newValue);
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin,
+                       float rangeMax);
+
+/* Color/Hue Threshold: calls imaqColorThreshold */
+int frcColorThreshold(Image* dest, const Image* source, ColorMode mode,
+                      const Range* plane1Range, const Range* plane2Range,
+                      const Range* plane3Range);
+int frcColorThreshold(Image* dest, const Image* source, int replaceValue,
+                      ColorMode mode, const Range* plane1Range,
+                      const Range* plane2Range, const Range* plane3Range);
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange);
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange,
+                    int minSaturation);
+
+/* Extract ColorHue Plane: calls imaqExtractColorPlanes */
+int frcExtractColorPlanes(const Image* image, ColorMode mode, Image* plane1,
+                          Image* plane2, Image* plane3);
+int frcExtractHuePlane(const Image* image, Image* huePlane);
+int frcExtractHuePlane(const Image* image, Image* huePlane, int minSaturation);