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/ADXL345_I2C.h b/wpilibc/Athena/include/ADXL345_I2C.h
new file mode 100644
index 0000000..e55e007
--- /dev/null
+++ b/wpilibc/Athena/include/ADXL345_I2C.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "interfaces/Accelerometer.h"
+#include "I2C.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include <memory>
+
+/**
+ * ADXL345 Accelerometer on I2C.
+ *
+ * This class allows access to a Analog Devices ADXL345 3-axis accelerometer on
+ * an I2C bus.
+ * This class assumes the default (not alternate) sensor address of 0x1D (7-bit
+ * address).
+ */
+class ADXL345_I2C : public Accelerometer,
+                    public I2C,
+                    public LiveWindowSendable {
+ protected:
+  static const uint8_t kAddress = 0x1D;
+  static const uint8_t kPowerCtlRegister = 0x2D;
+  static const uint8_t kDataFormatRegister = 0x31;
+  static const uint8_t kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  explicit ADXL345_I2C(Port port, Range range = kRange_2G);
+  virtual ~ADXL345_I2C() = default;
+
+  ADXL345_I2C(const ADXL345_I2C&) = delete;
+  ADXL345_I2C& operator=(const ADXL345_I2C&) = delete;
+
+  // Accelerometer interface
+  virtual void SetRange(Range range) override;
+  virtual double GetX() override;
+  virtual double GetY() override;
+  virtual double GetZ() override;
+
+  virtual double GetAcceleration(Axes axis);
+  virtual AllAxes GetAccelerations();
+
+  virtual std::string GetSmartDashboardType() const override;
+  virtual void InitTable(std::shared_ptr<ITable> subtable) override;
+  virtual void UpdateTable() override;
+  virtual std::shared_ptr<ITable> GetTable() const override;
+  virtual void StartLiveWindowMode() override {}
+  virtual void StopLiveWindowMode() override {}
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/ADXL345_SPI.h b/wpilibc/Athena/include/ADXL345_SPI.h
new file mode 100644
index 0000000..1310133
--- /dev/null
+++ b/wpilibc/Athena/include/ADXL345_SPI.h
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "interfaces/Accelerometer.h"
+#include "SensorBase.h"
+#include "SPI.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * ADXL345 Accelerometer on SPI.
+ *
+ * This class allows access to an Analog Devices ADXL345 3-axis accelerometer
+ * via SPI.
+ * This class assumes the sensor is wired in 4-wire SPI mode.
+ */
+class ADXL345_SPI : public Accelerometer,
+                    protected SPI,
+                    public LiveWindowSendable {
+ protected:
+  static const uint8_t kPowerCtlRegister = 0x2D;
+  static const uint8_t kDataFormatRegister = 0x31;
+  static const uint8_t kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+  enum SPIAddressFields { kAddress_Read = 0x80, kAddress_MultiByte = 0x40 };
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  ADXL345_SPI(SPI::Port port, Range range = kRange_2G);
+  virtual ~ADXL345_SPI() = default;
+
+  ADXL345_SPI(const ADXL345_SPI&) = delete;
+  ADXL345_SPI& operator=(const ADXL345_SPI&) = delete;
+
+  // Accelerometer interface
+  virtual void SetRange(Range range) override;
+  virtual double GetX() override;
+  virtual double GetY() override;
+  virtual double GetZ() override;
+
+  virtual double GetAcceleration(Axes axis);
+  virtual AllAxes GetAccelerations();
+
+  virtual std::string GetSmartDashboardType() const override;
+  virtual void InitTable(std::shared_ptr<ITable> subtable) override;
+  virtual void UpdateTable() override;
+  virtual std::shared_ptr<ITable> GetTable() const override;
+  virtual void StartLiveWindowMode() override {}
+  virtual void StopLiveWindowMode() override {}
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/ADXL362.h b/wpilibc/Athena/include/ADXL362.h
new file mode 100644
index 0000000..ea47686
--- /dev/null
+++ b/wpilibc/Athena/include/ADXL362.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "interfaces/Accelerometer.h"
+#include "SensorBase.h"
+#include "SPI.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * ADXL362 SPI Accelerometer.
+ *
+ * This class allows access to an Analog Devices ADXL362 3-axis accelerometer.
+ */
+class ADXL362 : public Accelerometer, public LiveWindowSendable {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  ADXL362(Range range = kRange_2G);
+  ADXL362(SPI::Port port, Range range = kRange_2G);
+  virtual ~ADXL362() = default;
+
+  ADXL362(const ADXL362&) = delete;
+  ADXL362& operator=(const ADXL362&) = delete;
+
+  // Accelerometer interface
+  virtual void SetRange(Range range) override;
+  virtual double GetX() override;
+  virtual double GetY() override;
+  virtual double GetZ() override;
+
+  virtual double GetAcceleration(Axes axis);
+  virtual AllAxes GetAccelerations();
+
+  virtual std::string GetSmartDashboardType() const override;
+  virtual void InitTable(std::shared_ptr<ITable> subtable) override;
+  virtual void UpdateTable() override;
+  virtual std::shared_ptr<ITable> GetTable() const override;
+  virtual void StartLiveWindowMode() override {}
+  virtual void StopLiveWindowMode() override {}
+
+ private:
+  SPI m_spi;
+  double m_gsPerLSB = 0.001;
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/ADXRS450_Gyro.h b/wpilibc/Athena/include/ADXRS450_Gyro.h
new file mode 100644
index 0000000..42a7a59
--- /dev/null
+++ b/wpilibc/Athena/include/ADXRS450_Gyro.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. 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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "GyroBase.h"
+#include "Notifier.h"
+#include "SPI.h"
+#include "HAL/cpp/priority_mutex.h"
+
+#include <memory>
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading.
+ *
+ * This class is for the digital ADXRS450 gyro sensor that connects via SPI.
+ */
+class ADXRS450_Gyro : public GyroBase {
+ public:
+  ADXRS450_Gyro();
+  explicit ADXRS450_Gyro(SPI::Port port);
+  virtual ~ADXRS450_Gyro() = default;
+
+  float GetAngle() const override;
+  double GetRate() const override;
+  void Reset() override;
+  void Calibrate() override;
+
+  std::string GetSmartDashboardType() const override;
+
+ private:
+  SPI m_spi;
+
+  uint16_t ReadRegister(uint8_t reg);
+};
diff --git a/wpilibc/Athena/include/AnalogAccelerometer.h b/wpilibc/Athena/include/AnalogAccelerometer.h
new file mode 100644
index 0000000..ad6d6dd
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogAccelerometer.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "AnalogInput.h"
+#include "SensorBase.h"
+#include "PIDSource.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * Handle operation of an analog accelerometer.
+ * The accelerometer reads acceleration directly through the sensor. Many
+ * sensors have
+ * multiple axis and can be treated as multiple devices. Each is calibrated by
+ * finding
+ * the center value over a period of time.
+ */
+class AnalogAccelerometer : public SensorBase,
+                            public PIDSource,
+                            public LiveWindowSendable {
+ public:
+  explicit AnalogAccelerometer(int32_t channel);
+  explicit AnalogAccelerometer(AnalogInput *channel);
+  explicit AnalogAccelerometer(std::shared_ptr<AnalogInput> channel);
+  virtual ~AnalogAccelerometer() = default;
+
+  float GetAcceleration() const;
+  void SetSensitivity(float sensitivity);
+  void SetZero(float zero);
+  double PIDGet() override;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  void InitAccelerometer();
+
+  std::shared_ptr<AnalogInput> m_analogInput;
+  float m_voltsPerG = 1.0;
+  float m_zeroGVoltage = 2.5;
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/AnalogGyro.h b/wpilibc/Athena/include/AnalogGyro.h
new file mode 100644
index 0000000..4ce0ccb
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogGyro.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "GyroBase.h"
+
+class AnalogInput;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot
+ * rotates the new heading is computed by integrating the rate of rotation
+ * returned
+ * by the sensor. When the class is instantiated, it does a short calibration
+ * routine
+ * where it samples the gyro while at rest to determine the default offset. This
+ * is
+ * subtracted from each sample to determine the heading. This gyro class must be
+ * used
+ * with a channel that is assigned one of the Analog accumulators from the FPGA.
+ * See
+ * AnalogInput for the current accumulator assignments.
+ *
+ * This class is for gyro sensors that connect to an analog input.
+ */
+class AnalogGyro : public GyroBase {
+ public:
+  static const uint32_t kOversampleBits = 10;
+  static const uint32_t kAverageBits = 0;
+  static constexpr float kSamplesPerSecond = 50.0;
+  static constexpr float kCalibrationSampleTime = 5.0;
+  static constexpr float kDefaultVoltsPerDegreePerSecond = 0.007;
+
+  explicit AnalogGyro(int32_t channel);
+  explicit AnalogGyro(AnalogInput *channel);
+  explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
+  AnalogGyro(int32_t channel, uint32_t center, float offset);
+  AnalogGyro(std::shared_ptr<AnalogInput> channel, uint32_t center, float offset);
+  virtual ~AnalogGyro() = default;
+
+  float GetAngle() const override;
+  double GetRate() const override;
+  virtual uint32_t GetCenter() const;
+  virtual float GetOffset() const;
+  void SetSensitivity(float voltsPerDegreePerSecond);
+  void SetDeadband(float volts);
+  void Reset() override;
+  virtual void InitGyro();
+  void Calibrate() override;
+
+  std::string GetSmartDashboardType() const override;
+
+ protected:
+  std::shared_ptr<AnalogInput> m_analog;
+
+ private:
+  float m_voltsPerDegreePerSecond;
+  float m_offset;
+  uint32_t m_center;
+};
diff --git a/wpilibc/Athena/include/AnalogInput.h b/wpilibc/Athena/include/AnalogInput.h
new file mode 100644
index 0000000..d47d1f2
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogInput.h
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "SensorBase.h"
+#include "PIDSource.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * Analog input class.
+ *
+ * Connected to each analog channel is an averaging and oversampling engine.
+ * This engine accumulates
+ * the specified ( by SetAverageBits() and SetOversampleBits() ) number of
+ * samples before returning a new
+ * value.  This is not a sliding window average.  The only difference between
+ * the oversampled samples and
+ * the averaged samples is that the oversampled samples are simply accumulated
+ * effectively increasing the
+ * resolution, while the averaged samples are divided by the number of samples
+ * to retain the resolution,
+ * but get more stable values.
+ */
+class AnalogInput : public SensorBase,
+                    public PIDSource,
+                    public LiveWindowSendable {
+ public:
+  static const uint8_t kAccumulatorModuleNumber = 1;
+  static const uint32_t kAccumulatorNumChannels = 2;
+  static const uint32_t kAccumulatorChannels[kAccumulatorNumChannels];
+
+  explicit AnalogInput(uint32_t channel);
+  virtual ~AnalogInput();
+
+  int16_t GetValue() const;
+  int32_t GetAverageValue() const;
+
+  float GetVoltage() const;
+  float GetAverageVoltage() const;
+
+  uint32_t GetChannel() const;
+
+  void SetAverageBits(uint32_t bits);
+  uint32_t GetAverageBits() const;
+  void SetOversampleBits(uint32_t bits);
+  uint32_t GetOversampleBits() const;
+
+  uint32_t GetLSBWeight() const;
+  int32_t GetOffset() const;
+
+  bool IsAccumulatorChannel() const;
+  void InitAccumulator();
+  void SetAccumulatorInitialValue(int64_t value);
+  void ResetAccumulator();
+  void SetAccumulatorCenter(int32_t center);
+  void SetAccumulatorDeadband(int32_t deadband);
+  int64_t GetAccumulatorValue() const;
+  uint32_t GetAccumulatorCount() const;
+  void GetAccumulatorOutput(int64_t &value, uint32_t &count) const;
+
+  static void SetSampleRate(float samplesPerSecond);
+  static float GetSampleRate();
+
+  double PIDGet() override;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  uint32_t m_channel;
+  //TODO: Adjust HAL to avoid use of raw pointers.
+  void *m_port;
+  int64_t m_accumulatorOffset;
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/AnalogOutput.h b/wpilibc/Athena/include/AnalogOutput.h
new file mode 100644
index 0000000..c30b5c7
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogOutput.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* 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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/HAL.hpp"
+#include "SensorBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include <memory>
+#include <cstdint>
+
+/**
+ * MXP analog output class.
+ */
+class AnalogOutput : public SensorBase, public LiveWindowSendable {
+ public:
+  explicit AnalogOutput(uint32_t channel);
+  virtual ~AnalogOutput();
+
+  void SetVoltage(float voltage);
+  float GetVoltage() const;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ protected:
+  uint32_t m_channel;
+  void *m_port;
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/AnalogPotentiometer.h b/wpilibc/Athena/include/AnalogPotentiometer.h
new file mode 100644
index 0000000..7b7b12a
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogPotentiometer.h
@@ -0,0 +1,85 @@
+#include "AnalogInput.h"
+#include "interfaces/Potentiometer.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * Class for reading analog potentiometers. Analog potentiometers read
+ * in an analog voltage that corresponds to a position. The position is
+ * in whichever units you choose, by way of the scaling and offset
+ * constants passed to the constructor.
+ *
+ * @author Alex Henning
+ * @author Colby Skeggs (rail voltage)
+ */
+class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable {
+ public:
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * Use the fullRange and offset values so that the output produces
+   * meaningful values. I.E: you have a 270 degree potentiometer and
+   * you want the output to be degrees with the halfway point as 0
+   * degrees. The fullRange value is 270.0(degrees) and the offset is
+   * -135.0 since the halfway point after scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the
+   * fraction of the supply voltage, plus the offset.
+   *
+   * @param channel The analog channel this potentiometer is plugged into.
+   * @param fullRange The scaling to multiply the voltage by to get a meaningful
+   * unit.
+   * @param offset The offset to add to the scaled value for controlling the
+   * zero value
+   */
+  explicit AnalogPotentiometer(int channel, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  explicit AnalogPotentiometer(AnalogInput *input, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  explicit AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                               double fullRange = 1.0, double offset = 0.0);
+
+  virtual ~AnalogPotentiometer() = default;
+
+  /**
+   * Get the current reading of the potentiomer.
+   *
+   * @return The current position of the potentiometer.
+   */
+  virtual double Get() const override;
+
+  /**
+   * Implement the PIDSource interface.
+   *
+   * @return The current reading.
+   */
+  virtual double PIDGet() override;
+
+  /*
+   * Live Window code, only does anything if live window is activated.
+   */
+  virtual std::string GetSmartDashboardType() const override;
+  virtual void InitTable(std::shared_ptr<ITable> subtable) override;
+  virtual void UpdateTable() override;
+  virtual std::shared_ptr<ITable> GetTable() const override;
+
+  /**
+   * AnalogPotentiometers don't have to do anything special when entering the
+   * LiveWindow.
+   */
+  virtual void StartLiveWindowMode() override {}
+
+  /**
+   * AnalogPotentiometers don't have to do anything special when exiting the
+   * LiveWindow.
+   */
+  virtual void StopLiveWindowMode() override {}
+
+ private:
+  std::shared_ptr<AnalogInput> m_analog_input;
+  double m_fullRange, m_offset;
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/AnalogTrigger.h b/wpilibc/Athena/include/AnalogTrigger.h
new file mode 100644
index 0000000..7fdd202
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogTrigger.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "AnalogTriggerOutput.h"
+#include "SensorBase.h"
+
+class AnalogInput;
+
+class AnalogTrigger : public SensorBase {
+  friend class AnalogTriggerOutput;
+
+ public:
+  explicit AnalogTrigger(int32_t channel);
+  explicit AnalogTrigger(AnalogInput *channel);
+  virtual ~AnalogTrigger();
+
+  void SetLimitsVoltage(float lower, float upper);
+  void SetLimitsRaw(int32_t lower, int32_t upper);
+  void SetAveraged(bool useAveragedValue);
+  void SetFiltered(bool useFilteredValue);
+  uint32_t GetIndex() const;
+  bool GetInWindow();
+  bool GetTriggerState();
+  std::shared_ptr<AnalogTriggerOutput> CreateOutput(AnalogTriggerType type) const;
+
+ private:
+  uint8_t m_index;
+  void *m_trigger;
+};
diff --git a/wpilibc/Athena/include/AnalogTriggerOutput.h b/wpilibc/Athena/include/AnalogTriggerOutput.h
new file mode 100644
index 0000000..27ad3b8
--- /dev/null
+++ b/wpilibc/Athena/include/AnalogTriggerOutput.h
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "DigitalSource.h"
+
+class AnalogTrigger;
+
+/**
+ * Class to represent a specific output from an analog trigger.
+ * This class is used to get the current output value and also as a
+ * DigitalSource
+ * to provide routing of an output to digital subsystems on the FPGA such as
+ * Counter, Encoder, and Interrupt.
+ *
+ * The TriggerState output indicates the primary output value of the trigger.
+ * If the analog
+ * signal is less than the lower limit, the output is false.  If the analog
+ * value is greater
+ * than the upper limit, then the output is true.  If the analog value is in
+ * between, then
+ * the trigger output state maintains its most recent value.
+ *
+ * The InWindow output indicates whether or not the analog signal is inside the
+ * range defined
+ * by the limits.
+ *
+ * The RisingPulse and FallingPulse outputs detect an instantaneous transition
+ * from above the
+ * upper limit to below the lower limit, and vise versa.  These pulses represent
+ * a rollover
+ * condition of a sensor and can be routed to an up / down couter or to
+ * interrupts.  Because
+ * the outputs generate a pulse, they cannot be read directly.  To help ensure
+ * that a rollover
+ * condition is not missed, there is an average rejection filter available that
+ * operates on the
+ * upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples.
+ * This will reject
+ * a sample that is (due to averaging or sampling) errantly between the two
+ * limits.  This filter
+ * will fail if more than one sample in a row is errantly in between the two
+ * limits.  You may see
+ * this problem if attempting to use this feature with a mechanical rollover
+ * sensor, such as a
+ * 360 degree no-stop potentiometer without signal conditioning, because the
+ * rollover transition
+ * is not sharp / clean enough.  Using the averaging engine may help with this,
+ * but rotational speeds of
+ * the sensor will then be limited.
+ */
+class AnalogTriggerOutput : public DigitalSource {
+  friend class AnalogTrigger;
+
+ public:
+  virtual ~AnalogTriggerOutput();
+  bool Get() const;
+
+  // DigitalSource interface
+  virtual uint32_t GetChannelForRouting() const override;
+  virtual uint32_t GetModuleForRouting() const override;
+  virtual bool GetAnalogTriggerForRouting() const override;
+
+ protected:
+  AnalogTriggerOutput(const AnalogTrigger &trigger, AnalogTriggerType outputType);
+
+ private:
+  // Uses reference rather than smart pointer because a user can not construct
+  // an AnalogTriggerOutput themselves and because the AnalogTriggerOutput
+  // should always be in scope at the same time as an AnalogTrigger.
+  const AnalogTrigger &m_trigger;
+  AnalogTriggerType m_outputType;
+};
diff --git a/wpilibc/Athena/include/BuiltInAccelerometer.h b/wpilibc/Athena/include/BuiltInAccelerometer.h
new file mode 100644
index 0000000..b6b5f8e
--- /dev/null
+++ b/wpilibc/Athena/include/BuiltInAccelerometer.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "interfaces/Accelerometer.h"
+#include "SensorBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * Built-in accelerometer.
+ *
+ * This class allows access to the RoboRIO's internal accelerometer.
+ */
+class BuiltInAccelerometer : public Accelerometer,
+                             public SensorBase,
+                             public LiveWindowSendable {
+ public:
+  BuiltInAccelerometer(Range range = kRange_8G);
+  virtual ~BuiltInAccelerometer() = default;
+
+  // Accelerometer interface
+  virtual void SetRange(Range range) override;
+  virtual double GetX() override;
+  virtual double GetY() override;
+  virtual double GetZ() override;
+
+  virtual std::string GetSmartDashboardType() const override;
+  virtual void InitTable(std::shared_ptr<ITable> subtable) override;
+  virtual void UpdateTable() override;
+  virtual std::shared_ptr<ITable> GetTable() const override;
+  virtual void StartLiveWindowMode() override {}
+  virtual void StopLiveWindowMode() override {}
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/CAN/can_proto.h b/wpilibc/Athena/include/CAN/can_proto.h
new file mode 100644
index 0000000..c2737d7
--- /dev/null
+++ b/wpilibc/Athena/include/CAN/can_proto.h
@@ -0,0 +1,415 @@
+//*****************************************************************************
+//
+// can_proto.h - Definitions for the CAN protocol used to communicate with the
+//               BDC motor controller.
+//
+// Copyright (c) 2008 Texas Instruments Incorporated.  All rights reserved.
+// TI Information - Selective Disclosure
+//
+//*****************************************************************************
+
+#ifndef __CAN_PROTO_H__
+#define __CAN_PROTO_H__
+
+//*****************************************************************************
+//
+// The masks of the fields that are used in the message identifier.
+//
+//*****************************************************************************
+#define CAN_MSGID_FULL_M 0x1fffffff
+#define CAN_MSGID_DEVNO_M 0x0000003f
+#define CAN_MSGID_API_M 0x0000ffc0
+#define CAN_MSGID_MFR_M 0x00ff0000
+#define CAN_MSGID_DTYPE_M 0x1f000000
+#define CAN_MSGID_DEVNO_S 0
+#define CAN_MSGID_API_S 6
+#define CAN_MSGID_MFR_S 16
+#define CAN_MSGID_DTYPE_S 24
+
+//*****************************************************************************
+//
+// The Reserved device number values in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_DEVNO_BCAST 0x00000000
+
+//*****************************************************************************
+//
+// The Reserved system control API numbers in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_API_SYSHALT 0x00000000
+#define CAN_MSGID_API_SYSRST 0x00000040
+#define CAN_MSGID_API_DEVASSIGN 0x00000080
+#define CAN_MSGID_API_DEVQUERY 0x000000c0
+#define CAN_MSGID_API_HEARTBEAT 0x00000140
+#define CAN_MSGID_API_SYNC 0x00000180
+#define CAN_MSGID_API_UPDATE 0x000001c0
+#define CAN_MSGID_API_FIRMVER 0x00000200
+#define CAN_MSGID_API_ENUMERATE 0x00000240
+#define CAN_MSGID_API_SYSRESUME 0x00000280
+
+//*****************************************************************************
+//
+// The 32 bit values associated with the CAN_MSGID_API_STATUS request.
+//
+//*****************************************************************************
+#define CAN_STATUS_CODE_M 0x0000ffff
+#define CAN_STATUS_MFG_M 0x00ff0000
+#define CAN_STATUS_DTYPE_M 0x1f000000
+#define CAN_STATUS_CODE_S 0
+#define CAN_STATUS_MFG_S 16
+#define CAN_STATUS_DTYPE_S 24
+
+//*****************************************************************************
+//
+// The Reserved manufacturer identifiers in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_MFR_NI 0x00010000
+#define CAN_MSGID_MFR_LM 0x00020000
+#define CAN_MSGID_MFR_DEKA 0x00030000
+
+//*****************************************************************************
+//
+// The Reserved device type identifiers in the Message Id.
+//
+//*****************************************************************************
+#define CAN_MSGID_DTYPE_BCAST 0x00000000
+#define CAN_MSGID_DTYPE_ROBOT 0x01000000
+#define CAN_MSGID_DTYPE_MOTOR 0x02000000
+#define CAN_MSGID_DTYPE_RELAY 0x03000000
+#define CAN_MSGID_DTYPE_GYRO 0x04000000
+#define CAN_MSGID_DTYPE_ACCEL 0x05000000
+#define CAN_MSGID_DTYPE_USONIC 0x06000000
+#define CAN_MSGID_DTYPE_GEART 0x07000000
+#define CAN_MSGID_DTYPE_UPDATE 0x1f000000
+
+//*****************************************************************************
+//
+// LM Motor Control API Classes API Class and ID masks.
+//
+//*****************************************************************************
+#define CAN_MSGID_API_CLASS_M 0x0000fc00
+#define CAN_MSGID_API_ID_M 0x000003c0
+
+//*****************************************************************************
+//
+// LM Motor Control API Classes in the Message Id for non-broadcast.
+// These are the upper 6 bits of the API field, the lower 4 bits determine
+// the APIId.
+//
+//*****************************************************************************
+#define CAN_API_MC_VOLTAGE 0x00000000
+#define CAN_API_MC_SPD 0x00000400
+#define CAN_API_MC_VCOMP 0x00000800
+#define CAN_API_MC_POS 0x00000c00
+#define CAN_API_MC_ICTRL 0x00001000
+#define CAN_API_MC_STATUS 0x00001400
+#define CAN_API_MC_PSTAT 0x00001800
+#define CAN_API_MC_CFG 0x00001c00
+#define CAN_API_MC_ACK 0x00002000
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Control Voltage API definitions.
+//
+//*****************************************************************************
+#define LM_API_VOLT \
+  (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_VOLTAGE)
+#define LM_API_VOLT_EN (LM_API_VOLT | (0 << CAN_MSGID_API_S))
+#define LM_API_VOLT_DIS (LM_API_VOLT | (1 << CAN_MSGID_API_S))
+#define LM_API_VOLT_SET (LM_API_VOLT | (2 << CAN_MSGID_API_S))
+#define LM_API_VOLT_SET_RAMP (LM_API_VOLT | (3 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_VOLT_T_EN (LM_API_VOLT | (4 << CAN_MSGID_API_S))
+#define LM_API_VOLT_T_SET (LM_API_VOLT | (5 << CAN_MSGID_API_S))
+#define LM_API_VOLT_T_SET_NO_ACK (LM_API_VOLT | (7 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_VOLT_SET_NO_ACK (LM_API_VOLT | (8 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Control API definitions for LM_API_VOLT_SET_RAMP.
+//
+//*****************************************************************************
+#define LM_API_VOLT_RAMP_DIS 0
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Control API definitions for CAN_MSGID_API_SYNC.
+//
+//*****************************************************************************
+#define LM_API_SYNC_PEND_NOW 0
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Speed Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_SPD (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_SPD)
+#define LM_API_SPD_EN (LM_API_SPD | (0 << CAN_MSGID_API_S))
+#define LM_API_SPD_DIS (LM_API_SPD | (1 << CAN_MSGID_API_S))
+#define LM_API_SPD_SET (LM_API_SPD | (2 << CAN_MSGID_API_S))
+#define LM_API_SPD_PC (LM_API_SPD | (3 << CAN_MSGID_API_S))
+#define LM_API_SPD_IC (LM_API_SPD | (4 << CAN_MSGID_API_S))
+#define LM_API_SPD_DC (LM_API_SPD | (5 << CAN_MSGID_API_S))
+#define LM_API_SPD_REF (LM_API_SPD | (6 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_SPD_T_EN (LM_API_SPD | (7 << CAN_MSGID_API_S))
+#define LM_API_SPD_T_SET (LM_API_SPD | (8 << CAN_MSGID_API_S))
+#define LM_API_SPD_T_SET_NO_ACK (LM_API_SPD | (10 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_SPD_SET_NO_ACK (LM_API_SPD | (11 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Control Voltage Compensation Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_VCOMP \
+  (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_VCOMP)
+#define LM_API_VCOMP_EN (LM_API_VCOMP | (0 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_DIS (LM_API_VCOMP | (1 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_SET (LM_API_VCOMP | (2 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_IN_RAMP (LM_API_VCOMP | (3 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_COMP_RAMP (LM_API_VCOMP | (4 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_VCOMP_T_EN (LM_API_VCOMP | (5 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_T_SET (LM_API_VCOMP | (6 << CAN_MSGID_API_S))
+#define LM_API_VCOMP_T_SET_NO_ACK (LM_API_VCOMP | (8 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_VCOMP_SET_NO_ACK (LM_API_VCOMP | (9 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Position Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_POS (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_POS)
+#define LM_API_POS_EN (LM_API_POS | (0 << CAN_MSGID_API_S))
+#define LM_API_POS_DIS (LM_API_POS | (1 << CAN_MSGID_API_S))
+#define LM_API_POS_SET (LM_API_POS | (2 << CAN_MSGID_API_S))
+#define LM_API_POS_PC (LM_API_POS | (3 << CAN_MSGID_API_S))
+#define LM_API_POS_IC (LM_API_POS | (4 << CAN_MSGID_API_S))
+#define LM_API_POS_DC (LM_API_POS | (5 << CAN_MSGID_API_S))
+#define LM_API_POS_REF (LM_API_POS | (6 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_POS_T_EN (LM_API_POS | (7 << CAN_MSGID_API_S))
+#define LM_API_POS_T_SET (LM_API_POS | (8 << CAN_MSGID_API_S))
+#define LM_API_POS_T_SET_NO_ACK (LM_API_POS | (10 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_POS_SET_NO_ACK (LM_API_POS | (11 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Current Control API definitions.
+//
+//*****************************************************************************
+#define LM_API_ICTRL \
+  (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_ICTRL)
+#define LM_API_ICTRL_EN (LM_API_ICTRL | (0 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_DIS (LM_API_ICTRL | (1 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_SET (LM_API_ICTRL | (2 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_PC (LM_API_ICTRL | (3 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_IC (LM_API_ICTRL | (4 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_DC (LM_API_ICTRL | (5 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_ICTRL_T_EN (LM_API_ICTRL | (6 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_T_SET (LM_API_ICTRL | (7 << CAN_MSGID_API_S))
+#define LM_API_ICTRL_T_SET_NO_ACK (LM_API_ICTRL | (9 << CAN_MSGID_API_S))
+//##### FIRST END #####
+#define LM_API_ICTRL_SET_NO_ACK (LM_API_ICTRL | (10 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Firmware Update API definitions.
+//
+//*****************************************************************************
+#define LM_API_UPD (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_UPDATE)
+#define LM_API_UPD_PING (LM_API_UPD | (0 << CAN_MSGID_API_S))
+#define LM_API_UPD_DOWNLOAD (LM_API_UPD | (1 << CAN_MSGID_API_S))
+#define LM_API_UPD_SEND_DATA (LM_API_UPD | (2 << CAN_MSGID_API_S))
+#define LM_API_UPD_RESET (LM_API_UPD | (3 << CAN_MSGID_API_S))
+#define LM_API_UPD_ACK (LM_API_UPD | (4 << CAN_MSGID_API_S))
+#define LM_API_HWVER (LM_API_UPD | (5 << CAN_MSGID_API_S))
+#define LM_API_UPD_REQUEST (LM_API_UPD | (6 << CAN_MSGID_API_S))
+//##### FIRST BEGIN #####
+#define LM_API_UNTRUST_EN (LM_API_UPD | (11 << CAN_MSGID_API_S))
+#define LM_API_TRUST_EN (LM_API_UPD | (12 << CAN_MSGID_API_S))
+#define LM_API_TRUST_HEARTBEAT (LM_API_UPD | (13 << CAN_MSGID_API_S))
+//##### FIRST END #####
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Status API definitions.
+//
+//*****************************************************************************
+#define LM_API_STATUS \
+  (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_STATUS)
+#define LM_API_STATUS_VOLTOUT (LM_API_STATUS | (0 << CAN_MSGID_API_S))
+#define LM_API_STATUS_VOLTBUS (LM_API_STATUS | (1 << CAN_MSGID_API_S))
+#define LM_API_STATUS_CURRENT (LM_API_STATUS | (2 << CAN_MSGID_API_S))
+#define LM_API_STATUS_TEMP (LM_API_STATUS | (3 << CAN_MSGID_API_S))
+#define LM_API_STATUS_POS (LM_API_STATUS | (4 << CAN_MSGID_API_S))
+#define LM_API_STATUS_SPD (LM_API_STATUS | (5 << CAN_MSGID_API_S))
+#define LM_API_STATUS_LIMIT (LM_API_STATUS | (6 << CAN_MSGID_API_S))
+#define LM_API_STATUS_FAULT (LM_API_STATUS | (7 << CAN_MSGID_API_S))
+#define LM_API_STATUS_POWER (LM_API_STATUS | (8 << CAN_MSGID_API_S))
+#define LM_API_STATUS_CMODE (LM_API_STATUS | (9 << CAN_MSGID_API_S))
+#define LM_API_STATUS_VOUT (LM_API_STATUS | (10 << CAN_MSGID_API_S))
+#define LM_API_STATUS_STKY_FLT (LM_API_STATUS | (11 << CAN_MSGID_API_S))
+#define LM_API_STATUS_FLT_COUNT (LM_API_STATUS | (12 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// These definitions are used with the byte that is returned from
+// the status request for LM_API_STATUS_LIMIT.
+//
+//*****************************************************************************
+#define LM_STATUS_LIMIT_FWD 0x01
+#define LM_STATUS_LIMIT_REV 0x02
+#define LM_STATUS_LIMIT_SFWD 0x04
+#define LM_STATUS_LIMIT_SREV 0x08
+#define LM_STATUS_LIMIT_STKY_FWD 0x10
+#define LM_STATUS_LIMIT_STKY_REV 0x20
+#define LM_STATUS_LIMIT_STKY_SFWD 0x40
+#define LM_STATUS_LIMIT_STKY_SREV 0x80
+
+//*****************************************************************************
+//
+// LM Motor Control status codes returned due to the CAN_STATUS_CODE_M field.
+//
+//*****************************************************************************
+#define LM_STATUS_FAULT_ILIMIT 0x01
+#define LM_STATUS_FAULT_TLIMIT 0x02
+#define LM_STATUS_FAULT_VLIMIT 0x04
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Configuration API definitions.
+//
+//*****************************************************************************
+#define LM_API_CFG (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_CFG)
+#define LM_API_CFG_NUM_BRUSHES (LM_API_CFG | (0 << CAN_MSGID_API_S))
+#define LM_API_CFG_ENC_LINES (LM_API_CFG | (1 << CAN_MSGID_API_S))
+#define LM_API_CFG_POT_TURNS (LM_API_CFG | (2 << CAN_MSGID_API_S))
+#define LM_API_CFG_BRAKE_COAST (LM_API_CFG | (3 << CAN_MSGID_API_S))
+#define LM_API_CFG_LIMIT_MODE (LM_API_CFG | (4 << CAN_MSGID_API_S))
+#define LM_API_CFG_LIMIT_FWD (LM_API_CFG | (5 << CAN_MSGID_API_S))
+#define LM_API_CFG_LIMIT_REV (LM_API_CFG | (6 << CAN_MSGID_API_S))
+#define LM_API_CFG_MAX_VOUT (LM_API_CFG | (7 << CAN_MSGID_API_S))
+#define LM_API_CFG_FAULT_TIME (LM_API_CFG | (8 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The Stellaris ACK API definition.
+//
+//*****************************************************************************
+#define LM_API_ACK (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_ACK)
+
+//*****************************************************************************
+//
+// The 8 bit values that can be returned by a call to LM_API_STATUS_HWVER.
+//
+//*****************************************************************************
+#define LM_HWVER_UNKNOWN 0x00
+#define LM_HWVER_JAG_1_0 0x01
+#define LM_HWVER_JAG_2_0 0x02
+
+//*****************************************************************************
+//
+// The 8 bit values that can be returned by a call to LM_API_STATUS_CMODE.
+//
+//*****************************************************************************
+#define LM_STATUS_CMODE_VOLT 0x00
+#define LM_STATUS_CMODE_CURRENT 0x01
+#define LM_STATUS_CMODE_SPEED 0x02
+#define LM_STATUS_CMODE_POS 0x03
+#define LM_STATUS_CMODE_VCOMP 0x04
+
+//*****************************************************************************
+//
+// The values that can specified as the position or speed reference.  Not all
+// values are valid for each reference; if an invalid reference is set, then
+// none will be selected.
+//
+//*****************************************************************************
+#define LM_REF_ENCODER 0x00
+#define LM_REF_POT 0x01
+#define LM_REF_INV_ENCODER 0x02
+#define LM_REF_QUAD_ENCODER 0x03
+#define LM_REF_NONE 0xff
+
+//*****************************************************************************
+//
+// The flags that are used to indicate the currently active fault sources.
+//
+//*****************************************************************************
+#define LM_FAULT_CURRENT 0x01
+#define LM_FAULT_TEMP 0x02
+#define LM_FAULT_VBUS 0x04
+#define LM_FAULT_GATE_DRIVE 0x08
+#define LM_FAULT_COMM 0x10
+
+//*****************************************************************************
+//
+// The Stellaris Motor Class Periodic Status API definitions.
+//
+//*****************************************************************************
+#define LM_API_PSTAT \
+  (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | CAN_API_MC_PSTAT)
+#define LM_API_PSTAT_PER_EN_S0 (LM_API_PSTAT | (0 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_PER_EN_S1 (LM_API_PSTAT | (1 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_PER_EN_S2 (LM_API_PSTAT | (2 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_PER_EN_S3 (LM_API_PSTAT | (3 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S0 (LM_API_PSTAT | (4 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S1 (LM_API_PSTAT | (5 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S2 (LM_API_PSTAT | (6 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_CFG_S3 (LM_API_PSTAT | (7 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S0 (LM_API_PSTAT | (8 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S1 (LM_API_PSTAT | (9 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S2 (LM_API_PSTAT | (10 << CAN_MSGID_API_S))
+#define LM_API_PSTAT_DATA_S3 (LM_API_PSTAT | (11 << CAN_MSGID_API_S))
+
+//*****************************************************************************
+//
+// The values that can be used to configure the data the Periodic Status
+// Message bytes.  Bytes of a multi-byte data values are encoded as
+// little-endian, therefore B0 is the least significant byte.
+//
+//*****************************************************************************
+#define LM_PSTAT_END 0
+#define LM_PSTAT_VOLTOUT_B0 1
+#define LM_PSTAT_VOLTOUT_B1 2
+#define LM_PSTAT_VOLTBUS_B0 3
+#define LM_PSTAT_VOLTBUS_B1 4
+#define LM_PSTAT_CURRENT_B0 5
+#define LM_PSTAT_CURRENT_B1 6
+#define LM_PSTAT_TEMP_B0 7
+#define LM_PSTAT_TEMP_B1 8
+#define LM_PSTAT_POS_B0 9
+#define LM_PSTAT_POS_B1 10
+#define LM_PSTAT_POS_B2 11
+#define LM_PSTAT_POS_B3 12
+#define LM_PSTAT_SPD_B0 13
+#define LM_PSTAT_SPD_B1 14
+#define LM_PSTAT_SPD_B2 15
+#define LM_PSTAT_SPD_B3 16
+#define LM_PSTAT_LIMIT_NCLR 17
+#define LM_PSTAT_LIMIT_CLR 18
+#define LM_PSTAT_FAULT 19
+#define LM_PSTAT_STKY_FLT_NCLR 20
+#define LM_PSTAT_STKY_FLT_CLR 21
+#define LM_PSTAT_VOUT_B0 22
+#define LM_PSTAT_VOUT_B1 23
+#define LM_PSTAT_FLT_COUNT_CURRENT 24
+#define LM_PSTAT_FLT_COUNT_TEMP 25
+#define LM_PSTAT_FLT_COUNT_VOLTBUS 26
+#define LM_PSTAT_FLT_COUNT_GATE 27
+#define LM_PSTAT_FLT_COUNT_COMM 28
+#define LM_PSTAT_CANSTS 29
+#define LM_PSTAT_CANERR_B0 30
+#define LM_PSTAT_CANERR_B1 31
+
+#endif  // __CAN_PROTO_H__
diff --git a/wpilibc/Athena/include/CANJaguar.h b/wpilibc/Athena/include/CANJaguar.h
new file mode 100644
index 0000000..5d05d47
--- /dev/null
+++ b/wpilibc/Athena/include/CANJaguar.h
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2009. 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 "ErrorBase.h"
+#include "MotorSafety.h"
+#include "Resource.h"
+#include "MotorSafetyHelper.h"
+#include "PIDOutput.h"
+#include "CANSpeedController.h"
+#include "HAL/cpp/Semaphore.hpp"
+#include "HAL/HAL.hpp"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITableListener.h"
+#include "NetworkCommunication/CANSessionMux.h"
+#include "CAN/can_proto.h"
+
+#include <atomic>
+#include "HAL/cpp/priority_mutex.h"
+#include <memory>
+#include <utility>
+#include <sstream>
+
+/**
+ * Luminary Micro / Vex Robotics Jaguar Speed Control
+ */
+class CANJaguar : public MotorSafety,
+                  public CANSpeedController,
+                  public ErrorBase,
+                  public LiveWindowSendable,
+                  public ITableListener {
+ public:
+  // The internal PID control loop in the Jaguar runs at 1kHz.
+  static const int32_t kControllerRate = 1000;
+  static constexpr double kApproxBusVoltage = 12.0;
+
+  // Control mode tags
+  /** Sets an encoder as the speed reference only. <br> Passed as the "tag" when
+   * setting the control mode.*/
+  static const struct EncoderStruct {
+  } Encoder;
+  /** Sets a quadrature encoder as the position and speed reference. <br> Passed
+   * as the "tag" when setting the control mode.*/
+  static const struct QuadEncoderStruct {
+  } QuadEncoder;
+  /** Sets a potentiometer as the position reference only. <br> Passed as the
+   * "tag" when setting the control mode. */
+  static const struct PotentiometerStruct {
+  } Potentiometer;
+
+  explicit CANJaguar(uint8_t deviceNumber);
+  virtual ~CANJaguar();
+
+  uint8_t getDeviceNumber() const;
+  uint8_t GetHardwareVersion() const;
+
+  // PIDOutput interface
+  virtual void PIDWrite(float output) override;
+
+  // Control mode methods
+  void EnableControl(double encoderInitialPosition = 0.0);
+  void DisableControl();
+
+  void SetPercentMode();
+  void SetPercentMode(EncoderStruct, uint16_t codesPerRev);
+  void SetPercentMode(QuadEncoderStruct, uint16_t codesPerRev);
+  void SetPercentMode(PotentiometerStruct);
+
+  void SetCurrentMode(double p, double i, double d);
+  void SetCurrentMode(EncoderStruct, uint16_t codesPerRev, double p, double i,
+                      double d);
+  void SetCurrentMode(QuadEncoderStruct, uint16_t codesPerRev, double p,
+                      double i, double d);
+  void SetCurrentMode(PotentiometerStruct, double p, double i, double d);
+
+  void SetSpeedMode(EncoderStruct, uint16_t codesPerRev, double p, double i,
+                    double d);
+  void SetSpeedMode(QuadEncoderStruct, uint16_t codesPerRev, double p, double i,
+                    double d);
+
+  void SetPositionMode(QuadEncoderStruct, uint16_t codesPerRev, double p,
+                       double i, double d);
+  void SetPositionMode(PotentiometerStruct, double p, double i, double d);
+
+  void SetVoltageMode();
+  void SetVoltageMode(EncoderStruct, uint16_t codesPerRev);
+  void SetVoltageMode(QuadEncoderStruct, uint16_t codesPerRev);
+  void SetVoltageMode(PotentiometerStruct);
+
+  // CANSpeedController interface
+  virtual float Get() const override;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual void Disable() override;
+  virtual void SetP(double p) override;
+  virtual void SetI(double i) override;
+  virtual void SetD(double d) override;
+  virtual void SetPID(double p, double i, double d) override;
+  virtual double GetP() const override;
+  virtual double GetI() const override;
+  virtual double GetD() const override;
+  virtual bool IsModePID(CANSpeedController::ControlMode mode) const override;
+  virtual float GetBusVoltage() const override;
+  virtual float GetOutputVoltage() const override;
+  virtual float GetOutputCurrent() const override;
+  virtual float GetTemperature() const override;
+  virtual double GetPosition() const override;
+  virtual double GetSpeed() const override;
+  virtual bool GetForwardLimitOK() const override;
+  virtual bool GetReverseLimitOK() const override;
+  virtual uint16_t GetFaults() const override;
+  virtual void SetVoltageRampRate(double rampRate) override;
+  virtual uint32_t GetFirmwareVersion() const override;
+  virtual void ConfigNeutralMode(NeutralMode mode) override;
+  virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override;
+  virtual void ConfigPotentiometerTurns(uint16_t turns) override;
+  virtual void ConfigSoftPositionLimits(double forwardLimitPosition,
+                                        double reverseLimitPosition) override;
+  virtual void DisableSoftPositionLimits() override;
+  virtual void ConfigLimitMode(LimitMode mode) override;
+  virtual void ConfigForwardLimit(double forwardLimitPosition) override;
+  virtual void ConfigReverseLimit(double reverseLimitPosition) override;
+  virtual void ConfigMaxOutputVoltage(double voltage) override;
+  virtual void ConfigFaultTime(float faultTime) override;
+  virtual void SetControlMode(ControlMode mode);
+  virtual ControlMode GetControlMode() const;
+
+  static void UpdateSyncGroup(uint8_t syncGroup);
+
+  void SetExpiration(float timeout) override;
+  float GetExpiration() const override;
+  bool IsAlive() const override;
+  void StopMotor() override;
+  bool IsSafetyEnabled() const override;
+  void SetSafetyEnabled(bool enabled) override;
+  void GetDescription(std::ostringstream& desc) const override;
+  uint8_t GetDeviceID() const;
+
+  // SpeedController overrides
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ protected:
+  // Control mode helpers
+  void SetSpeedReference(uint8_t reference);
+  uint8_t GetSpeedReference() const;
+
+  void SetPositionReference(uint8_t reference);
+  uint8_t GetPositionReference() const;
+
+  uint8_t packPercentage(uint8_t *buffer, double value);
+  uint8_t packFXP8_8(uint8_t *buffer, double value);
+  uint8_t packFXP16_16(uint8_t *buffer, double value);
+  uint8_t packint16_t(uint8_t *buffer, int16_t value);
+  uint8_t packint32_t(uint8_t *buffer, int32_t value);
+  double unpackPercentage(uint8_t *buffer) const;
+  double unpackFXP8_8(uint8_t *buffer) const;
+  double unpackFXP16_16(uint8_t *buffer) const;
+  int16_t unpackint16_t(uint8_t *buffer) const;
+  int32_t unpackint32_t(uint8_t *buffer) const;
+
+  void sendMessage(uint32_t messageID, const uint8_t *data, uint8_t dataSize,
+                   int32_t period = CAN_SEND_PERIOD_NO_REPEAT);
+  void requestMessage(uint32_t messageID,
+                      int32_t period = CAN_SEND_PERIOD_NO_REPEAT);
+  bool getMessage(uint32_t messageID, uint32_t mask, uint8_t *data,
+                  uint8_t *dataSize) const;
+
+  void setupPeriodicStatus();
+  void updatePeriodicStatus() const;
+
+  mutable priority_recursive_mutex m_mutex;
+
+  uint8_t m_deviceNumber;
+  float m_value = 0.0f;
+
+  // Parameters/configuration
+  ControlMode m_controlMode = kPercentVbus;
+  uint8_t m_speedReference = LM_REF_NONE;
+  uint8_t m_positionReference = LM_REF_NONE;
+  double m_p = 0.0;
+  double m_i = 0.0;
+  double m_d = 0.0;
+  NeutralMode m_neutralMode = kNeutralMode_Jumper;
+  uint16_t m_encoderCodesPerRev = 0;
+  uint16_t m_potentiometerTurns = 0;
+  LimitMode m_limitMode = kLimitMode_SwitchInputsOnly;
+  double m_forwardLimit = 0.0;
+  double m_reverseLimit = 0.0;
+  double m_maxOutputVoltage = 30.0;
+  double m_voltageRampRate = 0.0;
+  float m_faultTime = 0.0f;
+
+  // Which parameters have been verified since they were last set?
+  bool m_controlModeVerified = false; // Needs to be verified because it's set in the constructor
+  bool m_speedRefVerified = true;
+  bool m_posRefVerified = true;
+  bool m_pVerified = true;
+  bool m_iVerified = true;
+  bool m_dVerified = true;
+  bool m_neutralModeVerified = true;
+  bool m_encoderCodesPerRevVerified = true;
+  bool m_potentiometerTurnsVerified = true;
+  bool m_forwardLimitVerified = true;
+  bool m_reverseLimitVerified = true;
+  bool m_limitModeVerified = true;
+  bool m_maxOutputVoltageVerified = true;
+  bool m_voltageRampRateVerified = true;
+  bool m_faultTimeVerified = true;
+
+  // Status data
+  mutable float m_busVoltage = 0.0f;
+  mutable float m_outputVoltage = 0.0f;
+  mutable float m_outputCurrent = 0.0f;
+  mutable float m_temperature = 0.0f;
+  mutable double m_position = 0.0;
+  mutable double m_speed = 0.0;
+  mutable uint8_t m_limits = 0x00;
+  mutable uint16_t m_faults = 0x0000;
+  uint32_t m_firmwareVersion = 0;
+  uint8_t m_hardwareVersion = 0;
+
+  // Which periodic status messages have we received at least once?
+  mutable std::atomic<bool> m_receivedStatusMessage0{false};
+  mutable std::atomic<bool> m_receivedStatusMessage1{false};
+  mutable std::atomic<bool> m_receivedStatusMessage2{false};
+
+  bool m_controlEnabled = false;
+
+  void verify();
+
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  void InitCANJaguar();
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/CANSpeedController.h b/wpilibc/Athena/include/CANSpeedController.h
new file mode 100644
index 0000000..73ed379
--- /dev/null
+++ b/wpilibc/Athena/include/CANSpeedController.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SpeedController.h"
+
+/**
+ * Interface for "smart" CAN-based speed controllers.
+ * @see CANJaguar
+ * @see CANTalon
+ */
+class CANSpeedController : public SpeedController {
+ public:
+  enum ControlMode {
+    kPercentVbus = 0,
+    kCurrent = 1,
+    kSpeed = 2,
+    kPosition = 3,
+    kVoltage = 4,
+    kFollower = 5  // Not supported in Jaguar.
+  };
+
+  // Helper function for the ControlMode enum
+  std::string GetModeName(ControlMode mode) {
+    switch(mode) {
+      case kPercentVbus: return "PercentVbus";
+      case kCurrent: return "Current";
+      case kSpeed: return "Speed";
+      case kPosition: return "Position";
+      case kVoltage: return "Voltage";
+      case kFollower: return "Follower";
+      default: return "[unknown control mode]";
+    }
+  }
+
+  // Helper function for the ControlMode enum
+  virtual bool IsModePID(ControlMode mode) const = 0;
+
+  enum Faults {
+    kCurrentFault = 1,
+    kTemperatureFault = 2,
+    kBusVoltageFault = 4,
+    kGateDriverFault = 8,
+    /* SRX extensions */
+    kFwdLimitSwitch = 0x10,
+    kRevLimitSwitch = 0x20,
+    kFwdSoftLimit = 0x40,
+    kRevSoftLimit = 0x80,
+  };
+
+  enum Limits { kForwardLimit = 1, kReverseLimit = 2 };
+
+  enum NeutralMode {
+    /** Use the NeutralMode that is set by the jumper wire on the CAN device */
+    kNeutralMode_Jumper = 0,
+    /** Stop the motor's rotation by applying a force. */
+    kNeutralMode_Brake = 1,
+    /** Do not attempt to stop the motor. Instead allow it to coast to a stop
+       without applying resistance. */
+    kNeutralMode_Coast = 2
+  };
+
+  enum LimitMode {
+    /** Only use switches for limits */
+    kLimitMode_SwitchInputsOnly = 0,
+    /** Use both switches and soft limits */
+    kLimitMode_SoftPositionLimits = 1,
+    /* SRX extensions */
+    /** Disable switches and disable soft limits */
+    kLimitMode_SrxDisableSwitchInputs = 2,
+  };
+
+  virtual float Get() const = 0;
+  virtual void Set(float value, uint8_t syncGroup = 0) = 0;
+  virtual void Disable() = 0;
+  virtual void SetP(double p) = 0;
+  virtual void SetI(double i) = 0;
+  virtual void SetD(double d) = 0;
+  virtual void SetPID(double p, double i, double d) = 0;
+  virtual double GetP() const = 0;
+  virtual double GetI() const = 0;
+  virtual double GetD() const = 0;
+  virtual float GetBusVoltage() const = 0;
+  virtual float GetOutputVoltage() const = 0;
+  virtual float GetOutputCurrent() const = 0;
+  virtual float GetTemperature() const = 0;
+  virtual double GetPosition() const = 0;
+  virtual double GetSpeed() const = 0;
+  virtual bool GetForwardLimitOK() const = 0;
+  virtual bool GetReverseLimitOK() const = 0;
+  virtual uint16_t GetFaults() const = 0;
+  virtual void SetVoltageRampRate(double rampRate) = 0;
+  virtual uint32_t GetFirmwareVersion() const = 0;
+  virtual void ConfigNeutralMode(NeutralMode mode) = 0;
+  virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) = 0;
+  virtual void ConfigPotentiometerTurns(uint16_t turns) = 0;
+  virtual void ConfigSoftPositionLimits(double forwardLimitPosition,
+                                        double reverseLimitPosition) = 0;
+  virtual void DisableSoftPositionLimits() = 0;
+  virtual void ConfigLimitMode(LimitMode mode) = 0;
+  virtual void ConfigForwardLimit(double forwardLimitPosition) = 0;
+  virtual void ConfigReverseLimit(double reverseLimitPosition) = 0;
+  virtual void ConfigMaxOutputVoltage(double voltage) = 0;
+  virtual void ConfigFaultTime(float faultTime) = 0;
+  // Hold off on interface until we figure out ControlMode enums.
+  //	virtual void SetControlMode(ControlMode mode) = 0;
+  //	virtual ControlMode GetControlMode() const = 0;
+};
diff --git a/wpilibc/Athena/include/CANTalon.h b/wpilibc/Athena/include/CANTalon.h
new file mode 100644
index 0000000..15ebbe2
--- /dev/null
+++ b/wpilibc/Athena/include/CANTalon.h
@@ -0,0 +1,317 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SafePWM.h"
+#include "CANSpeedController.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+#include "PIDInterface.h"
+#include "HAL/CanTalonSRX.h"
+#include "MotorSafetyHelper.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITable.h"
+
+#include <memory>
+
+/**
+ * CTRE Talon SRX Speed Controller with CAN Control
+ */
+class CANTalon : public MotorSafety,
+                 public CANSpeedController,
+                 public ErrorBase,
+                 public LiveWindowSendable,
+                 public ITableListener,
+                 public PIDSource,
+                 public PIDInterface {
+ public:
+  enum FeedbackDevice {
+    QuadEncoder = 0,
+    AnalogPot = 2,
+    AnalogEncoder = 3,
+    EncRising = 4,
+    EncFalling = 5,
+    CtreMagEncoder_Relative = 6, //!< Cross The Road Electronics Magnetic Encoder in Absolute/PulseWidth Mode
+    CtreMagEncoder_Absolute = 7, //!< Cross The Road Electronics Magnetic Encoder in Relative/Quadrature Mode
+    PulseWidth = 8,
+  };
+  /**
+   * Depending on the sensor type, Talon can determine if sensor is plugged in ot not.
+   */
+  enum FeedbackDeviceStatus {
+	FeedbackStatusUnknown = 0, 		//!< Sensor status could not be determined.  Not all sensors can do this.
+	FeedbackStatusPresent = 1, 		//!< Sensor is present and working okay.
+	FeedbackStatusNotPresent = 2, 	//!< Sensor is not present, not plugged in, not powered, etc...
+  };
+  enum StatusFrameRate {
+    StatusFrameRateGeneral = 0,
+    StatusFrameRateFeedback = 1,
+    StatusFrameRateQuadEncoder = 2,
+    StatusFrameRateAnalogTempVbat = 3,
+    StatusFrameRatePulseWidthMeas = 4,
+  };
+  explicit CANTalon(int deviceNumber);
+  explicit CANTalon(int deviceNumber, int controlPeriodMs);
+  DEFAULT_MOVE_CONSTRUCTOR(CANTalon);
+  virtual ~CANTalon();
+
+  // PIDOutput interface
+  virtual void PIDWrite(float output) override;
+
+  // PIDSource interface
+  virtual double PIDGet() override;
+
+  // MotorSafety interface
+  virtual void SetExpiration(float timeout) override;
+  virtual float GetExpiration() const override;
+  virtual bool IsAlive() const override;
+  virtual void StopMotor() override;
+  virtual void SetSafetyEnabled(bool enabled) override;
+  virtual bool IsSafetyEnabled() const override;
+  virtual void GetDescription(std::ostringstream& desc) const override;
+
+  // CANSpeedController interface
+  virtual float Get() const override;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual void Reset() override;
+  virtual void SetSetpoint(float value) override;
+  virtual void Disable() override;
+  virtual void EnableControl();
+  virtual void Enable() override;
+  virtual void SetP(double p) override;
+  virtual void SetI(double i) override;
+  virtual void SetD(double d) override;
+  void SetF(double f);
+  void SetIzone(unsigned iz);
+  virtual void SetPID(double p, double i, double d) override;
+  virtual void SetPID(double p, double i, double d, double f);
+  virtual double GetP() const override;
+  virtual double GetI() const override;
+  virtual double GetD() const override;
+  virtual double GetF() const;
+  virtual bool IsModePID(CANSpeedController::ControlMode mode) const override;
+  virtual float GetBusVoltage() const override;
+  virtual float GetOutputVoltage() const override;
+  virtual float GetOutputCurrent() const override;
+  virtual float GetTemperature() const override;
+  void SetPosition(double pos);
+  virtual double GetPosition() const override;
+  virtual double GetSpeed() const override;
+  virtual int GetClosedLoopError() const;
+  virtual void SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError);
+  virtual int GetAnalogIn() const;
+  virtual void SetAnalogPosition(int newPosition);
+  virtual int GetAnalogInRaw() const;
+  virtual int GetAnalogInVel() const;
+  virtual int GetEncPosition() const;
+  virtual void SetEncPosition(int);
+  virtual int GetEncVel() const;
+  int GetPinStateQuadA() const;
+  int GetPinStateQuadB() const;
+  int GetPinStateQuadIdx() const;
+  int IsFwdLimitSwitchClosed() const;
+  int IsRevLimitSwitchClosed() const;
+  int GetNumberOfQuadIdxRises() const;
+  void SetNumberOfQuadIdxRises(int rises);
+  virtual int GetPulseWidthPosition() const;
+  virtual void SetPulseWidthPosition(int newpos);
+  virtual int GetPulseWidthVelocity() const;
+  virtual int GetPulseWidthRiseToFallUs() const;
+  virtual int GetPulseWidthRiseToRiseUs() const;
+  virtual FeedbackDeviceStatus IsSensorPresent(FeedbackDevice feedbackDevice)const;
+  virtual bool GetForwardLimitOK() const override;
+  virtual bool GetReverseLimitOK() const override;
+  virtual uint16_t GetFaults() const override;
+  uint16_t GetStickyFaults() const;
+  void ClearStickyFaults();
+  virtual void SetVoltageRampRate(double rampRate) override;
+  virtual void SetVoltageCompensationRampRate(double rampRate);
+  virtual uint32_t GetFirmwareVersion() const override;
+  virtual void ConfigNeutralMode(NeutralMode mode) override;
+  virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) override;
+  virtual void ConfigPotentiometerTurns(uint16_t turns) override;
+  virtual void ConfigSoftPositionLimits(double forwardLimitPosition,
+                                        double reverseLimitPosition) override;
+  virtual void DisableSoftPositionLimits() override;
+  virtual void ConfigLimitMode(LimitMode mode) override;
+  virtual void ConfigForwardLimit(double forwardLimitPosition) override;
+  virtual void ConfigReverseLimit(double reverseLimitPosition) override;
+  /**
+   * Change the fwd limit switch setting to normally open or closed.
+   * Talon will disable momentarilly if the Talon's current setting
+   * is dissimilar to the caller's requested setting.
+   *
+   * Since Talon saves setting to flash this should only affect
+   * a given Talon initially during robot install.
+   *
+   * @param normallyOpen true for normally open.  false for normally closed.
+   */
+  void ConfigFwdLimitSwitchNormallyOpen(bool normallyOpen);
+  /**
+   * Change the rev limit switch setting to normally open or closed.
+   * Talon will disable momentarilly if the Talon's current setting
+   * is dissimilar to the caller's requested setting.
+   *
+   * Since Talon saves setting to flash this should only affect
+   * a given Talon initially during robot install.
+   *
+   * @param normallyOpen true for normally open.  false for normally closed.
+   */
+  void ConfigRevLimitSwitchNormallyOpen(bool normallyOpen);
+  virtual void ConfigMaxOutputVoltage(double voltage) override;
+  void ConfigPeakOutputVoltage(double forwardVoltage,double reverseVoltage);
+  void ConfigNominalOutputVoltage(double forwardVoltage,double reverseVoltage);
+  /**
+   * Enables Talon SRX to automatically zero the Sensor Position whenever an
+   * edge is detected on the index signal.
+   * @param enable 		boolean input, pass true to enable feature or false to disable.
+   * @param risingEdge 	boolean input, pass true to clear the position on rising edge,
+   *					pass false to clear the position on falling edge.
+   */
+  void EnableZeroSensorPositionOnIndex(bool enable, bool risingEdge);
+  void ConfigSetParameter(uint32_t paramEnum, double value);
+  bool GetParameter(uint32_t paramEnum, double & dvalue) const;
+
+  virtual void ConfigFaultTime(float faultTime) override;
+  virtual void SetControlMode(ControlMode mode);
+  void SetFeedbackDevice(FeedbackDevice device);
+  void SetStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs);
+  virtual ControlMode GetControlMode() const;
+  void SetSensorDirection(bool reverseSensor);
+  void SetClosedLoopOutputDirection(bool reverseOutput);
+  void SetCloseLoopRampRate(double rampRate);
+  void SelectProfileSlot(int slotIdx);
+  int GetIzone() const;
+  int GetIaccum() const;
+  void ClearIaccum();
+  int GetBrakeEnableDuringNeutral() const;
+
+  bool IsControlEnabled() const;
+  bool IsEnabled() const override;
+  double GetSetpoint() const override;
+
+  // LiveWindow stuff.
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  // SpeedController overrides
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  // Values for various modes as is sent in the CAN packets for the Talon.
+  enum TalonControlMode {
+    kThrottle = 0,
+    kFollowerMode = 5,
+    kVoltageMode = 4,
+    kPositionMode = 1,
+    kSpeedMode = 2,
+    kCurrentMode = 3,
+    kDisabled = 15
+  };
+
+  int m_deviceNumber;
+  std::unique_ptr<CanTalonSRX> m_impl;
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+  int m_profile = 0;  // Profile from CANTalon to use. Set to zero until we can
+                  // actually test this.
+
+  bool m_controlEnabled = true;
+  ControlMode m_controlMode = kPercentVbus;
+  TalonControlMode m_sendMode;
+
+  double m_setPoint = 0;
+  /**
+   * Encoder CPR, counts per rotations, also called codes per revoluion.
+   * Default value of zero means the API behaves as it did during the 2015 season, each position
+   * unit is a single pulse and there are four pulses per count (4X).
+   * Caller can use ConfigEncoderCodesPerRev to set the quadrature encoder CPR.
+   */
+  uint32_t m_codesPerRev = 0;
+  /**
+   * Number of turns per rotation.  For example, a 10-turn pot spins ten full rotations from
+   * a wiper voltage of zero to 3.3 volts.  Therefore knowing the
+   * number of turns a full voltage sweep represents is necessary for calculating rotations
+   * and velocity.
+   * A default value of zero means the API behaves as it did during the 2015 season, there are 1024
+   * position units from zero to 3.3V.
+   */
+  uint32_t m_numPotTurns = 0;
+  /**
+   * Although the Talon handles feedback selection, caching the feedback selection is helpful at the API level
+   * for scaling into rotations and RPM.
+   */
+  FeedbackDevice m_feedbackDevice = QuadEncoder;
+
+  static const unsigned int kDelayForSolicitedSignalsUs = 4000;
+  /**
+   * @param devToLookup FeedbackDevice to lookup the scalar for.  Because Talon
+   * 				allows multiple sensors to be attached simultaneously, caller must
+   *				specify which sensor to lookup.
+   * @return 		The number of native Talon units per rotation of the selected sensor.
+   *				Zero if the necessary sensor information is not available.
+   * @see ConfigEncoderCodesPerRev
+   * @see ConfigPotentiometerTurns
+   */
+  double GetNativeUnitsPerRotationScalar(FeedbackDevice devToLookup)const;
+  /**
+   * Fixup the sendMode so Set() serializes the correct demand value.
+   * Also fills the modeSelecet in the control frame to disabled.
+   * @param mode Control mode to ultimately enter once user calls Set().
+   * @see Set()
+   */
+  void ApplyControlMode(CANSpeedController::ControlMode mode);
+  /**
+   * @param fullRotations 	double precision value representing number of rotations of selected feedback sensor.
+   *							If user has never called the config routine for the selected sensor, then the caller
+   *							is likely passing rotations in engineering units already, in which case it is returned
+   *							as is.
+   *							@see ConfigPotentiometerTurns
+   *							@see ConfigEncoderCodesPerRev
+   * @return fullRotations in native engineering units of the Talon SRX firmware.
+   */
+  int32_t ScaleRotationsToNativeUnits(FeedbackDevice devToLookup, double fullRotations) const;
+  /**
+   * @param rpm 	double precision value representing number of rotations per minute of selected feedback sensor.
+   *							If user has never called the config routine for the selected sensor, then the caller
+   *							is likely passing rotations in engineering units already, in which case it is returned
+   *							as is.
+   *							@see ConfigPotentiometerTurns
+   *							@see ConfigEncoderCodesPerRev
+   * @return sensor velocity in native engineering units of the Talon SRX firmware.
+   */
+  int32_t ScaleVelocityToNativeUnits(FeedbackDevice devToLookup, double rpm) const;
+  /**
+   * @param nativePos 	integral position of the feedback sensor in native Talon SRX units.
+   *							If user has never called the config routine for the selected sensor, then the return
+   *							will be in TALON SRX units as well to match the behavior in the 2015 season.
+   *							@see ConfigPotentiometerTurns
+   *							@see ConfigEncoderCodesPerRev
+   * @return double precision number of rotations, unless config was never performed.
+   */
+  double ScaleNativeUnitsToRotations(FeedbackDevice devToLookup, int32_t nativePos) const;
+  /**
+   * @param nativeVel 	integral velocity of the feedback sensor in native Talon SRX units.
+   *							If user has never called the config routine for the selected sensor, then the return
+   *							will be in TALON SRX units as well to match the behavior in the 2015 season.
+   *							@see ConfigPotentiometerTurns
+   *							@see ConfigEncoderCodesPerRev
+   * @return double precision of sensor velocity in RPM, unless config was never performed.
+   */
+  double ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, int32_t nativeVel) const;
+
+  // LiveWindow stuff.
+  std::shared_ptr<ITable> m_table;
+  bool m_isInverted;
+
+  HasBeenMoved m_hasBeenMoved;
+};
diff --git a/wpilibc/Athena/include/CameraServer.h b/wpilibc/Athena/include/CameraServer.h
new file mode 100644
index 0000000..17ece99
--- /dev/null
+++ b/wpilibc/Athena/include/CameraServer.h
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* 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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "USBCamera.h"
+#include "ErrorBase.h"
+#include "nivision.h"
+#include "NIIMAQdx.h"
+
+#include "HAL/cpp/priority_mutex.h"
+#include <thread>
+#include <memory>
+#include <condition_variable>
+#include <tuple>
+#include <vector>
+
+class CameraServer : public ErrorBase {
+ private:
+  static constexpr uint16_t kPort = 1180;
+  static constexpr uint8_t kMagicNumber[] = {0x01, 0x00, 0x00, 0x00};
+  static constexpr uint32_t kSize640x480 = 0;
+  static constexpr uint32_t kSize320x240 = 1;
+  static constexpr uint32_t kSize160x120 = 2;
+  static constexpr int32_t kHardwareCompression = -1;
+  static constexpr uint32_t kMaxImageSize = 200000;
+
+ protected:
+  CameraServer();
+
+  std::shared_ptr<USBCamera> m_camera;
+  std::thread m_serverThread;
+  std::thread m_captureThread;
+  priority_recursive_mutex m_imageMutex;
+  std::condition_variable_any m_newImageVariable;
+  std::vector<uint8_t*> m_dataPool;
+  unsigned int m_quality;
+  bool m_autoCaptureStarted;
+  bool m_hwClient;
+  std::tuple<uint8_t*, unsigned int, unsigned int, bool> m_imageData;
+
+  void Serve();
+  void AutoCapture();
+  void SetImageData(uint8_t* data, unsigned int size, unsigned int start = 0,
+                    bool imaqData = false);
+  void FreeImageData(
+      std::tuple<uint8_t*, unsigned int, unsigned int, bool> imageData);
+
+  struct Request {
+    uint32_t fps;
+    int32_t compression;
+    uint32_t size;
+  };
+
+ public:
+  static CameraServer* GetInstance();
+  void SetImage(Image const* image);
+
+  void StartAutomaticCapture(
+      char const* cameraName = USBCamera::kDefaultCameraName);
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * You should call this method to just see a camera feed on the
+   * dashboard without doing any vision processing on the roboRIO.
+   * {@link #SetImage} should not be called after this is called.
+   *
+   * @param camera The camera interface (eg. USBCamera)
+   */
+  void StartAutomaticCapture(std::shared_ptr<USBCamera> camera);
+
+  bool IsAutoCaptureStarted();
+
+  void SetQuality(unsigned int quality);
+  unsigned int GetQuality();
+
+  void SetSize(unsigned int size);
+};
diff --git a/wpilibc/Athena/include/Compressor.h b/wpilibc/Athena/include/Compressor.h
new file mode 100644
index 0000000..d5962c3
--- /dev/null
+++ b/wpilibc/Athena/include/Compressor.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#ifndef Compressor_H_
+#define Compressor_H_
+
+#include "HAL/HAL.hpp"
+#include "SensorBase.h"
+#include "tables/ITableListener.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * PCM compressor
+ */
+class Compressor : public SensorBase,
+                   public LiveWindowSendable,
+                   public ITableListener {
+ public:
+  // Default PCM ID is 0
+  explicit Compressor(uint8_t pcmID = GetDefaultSolenoidModule());
+  virtual ~Compressor() = default;
+
+  void Start();
+  void Stop();
+  bool Enabled() const;
+
+  bool GetPressureSwitchValue() const;
+
+  float GetCompressorCurrent() const;
+
+  void SetClosedLoopControl(bool on);
+  bool GetClosedLoopControl() const;
+
+  bool GetCompressorCurrentTooHighFault() const;
+  bool GetCompressorCurrentTooHighStickyFault() const;
+  bool GetCompressorShortedStickyFault() const;
+  bool GetCompressorShortedFault() const;
+  bool GetCompressorNotConnectedStickyFault() const;
+  bool GetCompressorNotConnectedFault() const;
+  void ClearAllPCMStickyFaults();
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+
+ protected:
+  void *m_pcm_pointer;
+
+ private:
+  void SetCompressor(bool on);
+
+  std::shared_ptr<ITable> m_table;
+};
+
+#endif /* Compressor_H_ */
diff --git a/wpilibc/Athena/include/ControllerPower.h b/wpilibc/Athena/include/ControllerPower.h
new file mode 100644
index 0000000..7384e60
--- /dev/null
+++ b/wpilibc/Athena/include/ControllerPower.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#ifndef __CONTROLLER_POWER_H__
+#define __CONTROLLER_POWER_H__
+
+class ControllerPower {
+ public:
+  static double GetInputVoltage();
+  static double GetInputCurrent();
+  static double GetVoltage3V3();
+  static double GetCurrent3V3();
+  static bool GetEnabled3V3();
+  static int GetFaultCount3V3();
+  static double GetVoltage5V();
+  static double GetCurrent5V();
+  static bool GetEnabled5V();
+  static int GetFaultCount5V();
+  static double GetVoltage6V();
+  static double GetCurrent6V();
+  static bool GetEnabled6V();
+  static int GetFaultCount6V();
+};
+#endif
\ No newline at end of file
diff --git a/wpilibc/Athena/include/Counter.h b/wpilibc/Athena/include/Counter.h
new file mode 100644
index 0000000..4066de8
--- /dev/null
+++ b/wpilibc/Athena/include/Counter.h
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "AnalogTriggerOutput.h"
+#include "CounterBase.h"
+#include "SensorBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+class DigitalGlitchFilter;
+
+/**
+ * Class for counting the number of ticks on a digital input channel.
+ * This is a general purpose class for counting repetitive events. It can return
+ * the number
+ * of counts, the period of the most recent cycle, and detect when the signal
+ * being counted
+ * has stopped by supplying a maximum cycle time.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Counter : public SensorBase,
+                public CounterBase,
+                public LiveWindowSendable {
+ public:
+  explicit Counter(Mode mode = kTwoPulse);
+  explicit Counter(int32_t channel);
+  explicit Counter(DigitalSource *source);
+  explicit Counter(std::shared_ptr<DigitalSource> source);
+  DEPRECATED("Use pass-by-reference instead.")
+  explicit Counter(AnalogTrigger *trigger);
+  explicit Counter(const AnalogTrigger &trigger);
+  Counter(EncodingType encodingType, DigitalSource *upSource,
+          DigitalSource *downSource, bool inverted);
+  Counter(EncodingType encodingType, std::shared_ptr<DigitalSource> upSource,
+          std::shared_ptr<DigitalSource> downSource, bool inverted);
+  virtual ~Counter();
+
+  void SetUpSource(int32_t channel);
+  void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType);
+  void SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                   AnalogTriggerType triggerType);
+  void SetUpSource(DigitalSource *source);
+  void SetUpSource(std::shared_ptr<DigitalSource> source);
+  void SetUpSource(DigitalSource &source);
+  void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+  void ClearUpSource();
+
+  void SetDownSource(int32_t channel);
+  void SetDownSource(AnalogTrigger *analogTrigger,
+                     AnalogTriggerType triggerType);
+  void SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                     AnalogTriggerType triggerType);
+  void SetDownSource(DigitalSource *source);
+  void SetDownSource(std::shared_ptr<DigitalSource> source);
+  void SetDownSource(DigitalSource &source);
+  void SetDownSourceEdge(bool risingEdge, bool fallingEdge);
+  void ClearDownSource();
+
+  void SetUpDownCounterMode();
+  void SetExternalDirectionMode();
+  void SetSemiPeriodMode(bool highSemiPeriod);
+  void SetPulseLengthMode(float threshold);
+
+  void SetReverseDirection(bool reverseDirection);
+
+  // CounterBase interface
+  int32_t Get() const override;
+  void Reset() override;
+  double GetPeriod() const override;
+  void SetMaxPeriod(double maxPeriod) override;
+  void SetUpdateWhenEmpty(bool enabled);
+  bool GetStopped() const override;
+  bool GetDirection() const override;
+
+  void SetSamplesToAverage(int samplesToAverage);
+  int GetSamplesToAverage() const;
+  uint32_t GetFPGAIndex() const { return m_index; }
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  virtual std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ protected:
+  // Makes the counter count up.
+  std::shared_ptr<DigitalSource> m_upSource;
+  // Makes the counter count down.
+  std::shared_ptr<DigitalSource> m_downSource;
+  // The FPGA counter object
+  void *m_counter = nullptr;              ///< The FPGA counter object.
+ private:
+  uint32_t m_index = 0;            ///< The index of this counter.
+
+  std::shared_ptr<ITable> m_table;
+  friend class DigitalGlitchFilter;
+};
diff --git a/wpilibc/Athena/include/CounterBase.h b/wpilibc/Athena/include/CounterBase.h
new file mode 100644
index 0000000..68896a8
--- /dev/null
+++ b/wpilibc/Athena/include/CounterBase.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 <stdint.h>
+
+/**
+ * Interface for counting the number of ticks on a digital input channel.
+ * Encoders, Gear tooth sensors, and counters should all subclass this so it can
+ * be used to build more advanced classes for control and driving.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class CounterBase {
+ public:
+  enum EncodingType { k1X, k2X, k4X };
+
+  virtual ~CounterBase() = default;
+  virtual int32_t Get() const = 0;
+  virtual void Reset() = 0;
+  virtual double GetPeriod() const = 0;
+  virtual void SetMaxPeriod(double maxPeriod) = 0;
+  virtual bool GetStopped() const = 0;
+  virtual bool GetDirection() const = 0;
+};
diff --git a/wpilibc/Athena/include/DigitalGlitchFilter.h b/wpilibc/Athena/include/DigitalGlitchFilter.h
new file mode 100644
index 0000000..a6f9f90
--- /dev/null
+++ b/wpilibc/Athena/include/DigitalGlitchFilter.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. 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 <array>
+
+#include "HAL/cpp/priority_mutex.h"
+#include "DigitalSource.h"
+
+class Encoder;
+class Counter;
+
+/**
+ * Class to enable glitch filtering on a set of digital inputs.
+ * This class will manage adding and removing digital inputs from a FPGA glitch
+ * filter. The filter lets the user configure the time that an input must remain
+ * high or low before it is classified as high or low.
+ */
+class DigitalGlitchFilter : public SensorBase {
+ public:
+  DigitalGlitchFilter();
+  ~DigitalGlitchFilter();
+
+  void Add(DigitalSource *input);
+  void Add(Encoder *input);
+  void Add(Counter *input);
+
+  void Remove(DigitalSource *input);
+  void Remove(Encoder *input);
+  void Remove(Counter *input);
+
+  void SetPeriodCycles(uint32_t fpga_cycles);
+  void SetPeriodNanoSeconds(uint64_t nanoseconds);
+
+  uint32_t GetPeriodCycles();
+  uint64_t GetPeriodNanoSeconds();
+
+ private:
+  // Sets the filter for the input to be the requested index.  A value of 0
+  // disables the filter, and the filter value must be between 1 and 3,
+  // inclusive.
+  void DoAdd(DigitalSource *input, int requested_index);
+
+  int m_channelIndex = -1;
+  static priority_mutex m_mutex;
+  static ::std::array<bool, 3> m_filterAllocated;
+};
diff --git a/wpilibc/Athena/include/DigitalInput.h b/wpilibc/Athena/include/DigitalInput.h
new file mode 100644
index 0000000..79cfcc5
--- /dev/null
+++ b/wpilibc/Athena/include/DigitalInput.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "DigitalSource.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+#include <cstdint>
+
+class DigitalGlitchFilter;
+
+/**
+ * Class to read a digital input.
+ * This class will read digital inputs and return the current value on the
+ * channel. Other devices
+ * such as encoders, gear tooth sensors, etc. that are implemented elsewhere
+ * will automatically
+ * allocate digital inputs and outputs as required. This class is only for
+ * devices like switches
+ * etc. that aren't implemented anywhere else.
+ */
+class DigitalInput : public DigitalSource, public LiveWindowSendable {
+ public:
+  explicit DigitalInput(uint32_t channel);
+  virtual ~DigitalInput();
+  bool Get() const;
+  uint32_t GetChannel() const;
+
+  // Digital Source Interface
+  virtual uint32_t GetChannelForRouting() const;
+  virtual uint32_t GetModuleForRouting() const;
+  virtual bool GetAnalogTriggerForRouting() const;
+
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  uint32_t m_channel;
+
+  std::shared_ptr<ITable> m_table;
+  friend class DigitalGlitchFilter;
+};
diff --git a/wpilibc/Athena/include/DigitalOutput.h b/wpilibc/Athena/include/DigitalOutput.h
new file mode 100644
index 0000000..367fb80
--- /dev/null
+++ b/wpilibc/Athena/include/DigitalOutput.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "DigitalSource.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITableListener.h"
+
+#include <memory>
+
+/**
+ * Class to write to digital outputs.
+ * Write values to the digital output channels. Other devices implemented
+ * elsewhere will allocate
+ * channels automatically so for those devices it shouldn't be done here.
+ */
+class DigitalOutput : public DigitalSource,
+                      public ITableListener,
+                      public LiveWindowSendable {
+ public:
+  explicit DigitalOutput(uint32_t channel);
+  virtual ~DigitalOutput();
+  void Set(uint32_t value);
+  uint32_t GetChannel() const;
+  void Pulse(float length);
+  bool IsPulsing() const;
+  void SetPWMRate(float rate);
+  void EnablePWM(float initialDutyCycle);
+  void DisablePWM();
+  void UpdateDutyCycle(float dutyCycle);
+
+  // Digital Source Interface
+  virtual uint32_t GetChannelForRouting() const;
+  virtual uint32_t GetModuleForRouting() const;
+  virtual bool GetAnalogTriggerForRouting() const;
+
+  virtual void ValueChanged(ITable* source, llvm::StringRef key,
+                            std::shared_ptr<nt::Value> value, bool isNew);
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  uint32_t m_channel;
+  void *m_pwmGenerator;
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/DigitalSource.h b/wpilibc/Athena/include/DigitalSource.h
new file mode 100644
index 0000000..c716715
--- /dev/null
+++ b/wpilibc/Athena/include/DigitalSource.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "InterruptableSensorBase.h"
+
+/**
+ * DigitalSource Interface.
+ * The DigitalSource represents all the possible inputs for a counter or a
+ * quadrature encoder. The source may be
+ * either a digital input or an analog input. If the caller just provides a
+ * channel, then a digital input will be
+ * constructed and freed when finished for the source. The source can either be
+ * a digital input or analog trigger
+ * but not both.
+ */
+class DigitalSource : public InterruptableSensorBase {
+ public:
+  virtual ~DigitalSource() = default;
+  virtual uint32_t GetChannelForRouting() const = 0;
+  virtual uint32_t GetModuleForRouting() const = 0;
+  virtual bool GetAnalogTriggerForRouting() const = 0;
+};
diff --git a/wpilibc/Athena/include/DoubleSolenoid.h b/wpilibc/Athena/include/DoubleSolenoid.h
new file mode 100644
index 0000000..fd20397
--- /dev/null
+++ b/wpilibc/Athena/include/DoubleSolenoid.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SolenoidBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITableListener.h"
+
+#include <memory>
+
+/**
+ * DoubleSolenoid class for running 2 channels of high voltage Digital Output
+ * (PCM).
+ *
+ * The DoubleSolenoid class is typically used for pneumatics solenoids that
+ * have two positions controlled by two separate channels.
+ */
+class DoubleSolenoid : public SolenoidBase,
+                       public LiveWindowSendable,
+                       public ITableListener {
+ public:
+  enum Value { kOff, kForward, kReverse };
+
+  explicit DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel);
+  DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel,
+                 uint32_t reverseChannel);
+  virtual ~DoubleSolenoid();
+  virtual void Set(Value value);
+  virtual Value Get() const;
+  bool IsFwdSolenoidBlackListed() const;
+  bool IsRevSolenoidBlackListed() const;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew);
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  uint32_t m_forwardChannel;  ///< The forward channel on the module to control.
+  uint32_t m_reverseChannel;  ///< The reverse channel on the module to control.
+  uint8_t m_forwardMask;      ///< The mask for the forward channel.
+  uint8_t m_reverseMask;      ///< The mask for the reverse channel.
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/DriverStation.h b/wpilibc/Athena/include/DriverStation.h
new file mode 100644
index 0000000..23ee095
--- /dev/null
+++ b/wpilibc/Athena/include/DriverStation.h
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SensorBase.h"
+#include "RobotState.h"
+#include "Task.h"
+#include "HAL/HAL.hpp"
+#include "HAL/cpp/Semaphore.hpp"
+#include "HAL/cpp/priority_mutex.h"
+#include "HAL/cpp/priority_condition_variable.h"
+#include <condition_variable>
+#include <atomic>
+
+struct HALControlWord;
+class AnalogInput;
+
+/**
+ * Provide access to the network communication data to / from the Driver
+ * Station.
+ */
+class DriverStation : public SensorBase, public RobotStateInterface {
+ public:
+  enum Alliance { kRed, kBlue, kInvalid };
+
+  virtual ~DriverStation();
+  static DriverStation &GetInstance();
+  static void ReportError(std::string error);
+
+  static const uint32_t kJoystickPorts = 6;
+
+  float GetStickAxis(uint32_t stick, uint32_t axis);
+  int GetStickPOV(uint32_t stick, uint32_t pov);
+  uint32_t GetStickButtons(uint32_t stick) const;
+  bool GetStickButton(uint32_t stick, uint8_t button);
+
+  int GetStickAxisCount(uint32_t stick) const;
+  int GetStickPOVCount(uint32_t stick) const;
+  int GetStickButtonCount(uint32_t stick) const;
+
+  bool GetJoystickIsXbox(uint32_t stick) const;
+  int GetJoystickType(uint32_t stick) const;
+  std::string GetJoystickName(uint32_t stick) const;
+  int GetJoystickAxisType(uint32_t stick, uint8_t axis) const;
+
+  bool IsEnabled() const override;
+  bool IsDisabled() const override;
+  bool IsAutonomous() const override;
+  bool IsOperatorControl() const override;
+  bool IsTest() const override;
+  bool IsDSAttached() const;
+  bool IsNewControlData() const;
+  bool IsFMSAttached() const;
+  bool IsSysActive() const;
+  bool IsSysBrownedOut() const;
+
+  Alliance GetAlliance() const;
+  uint32_t GetLocation() const;
+  void WaitForData();
+  double GetMatchTime() const;
+  float GetBatteryVoltage() const;
+
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing
+   *   for diagnostic purposes only
+   * @param entering If true, starting disabled code; if false, leaving disabled
+   * code */
+  void InDisabled(bool entering) { m_userInDisabled = entering; }
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing
+   *   for diagnostic purposes only
+   * @param entering If true, starting autonomous code; if false, leaving
+   * autonomous code */
+  void InAutonomous(bool entering) { m_userInAutonomous = entering; }
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing
+   *   for diagnostic purposes only
+   * @param entering If true, starting teleop code; if false, leaving teleop
+   * code */
+  void InOperatorControl(bool entering) { m_userInTeleop = entering; }
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing
+   *   for diagnostic purposes only
+   * @param entering If true, starting test code; if false, leaving test code */
+  void InTest(bool entering) { m_userInTest = entering; }
+
+ protected:
+  DriverStation();
+
+  void GetData();
+
+ private:
+  static DriverStation *m_instance;
+  void ReportJoystickUnpluggedError(std::string message);
+  void Run();
+
+  HALJoystickAxes m_joystickAxes[kJoystickPorts];
+  HALJoystickPOVs m_joystickPOVs[kJoystickPorts];
+  HALJoystickButtons m_joystickButtons[kJoystickPorts];
+  HALJoystickDescriptor m_joystickDescriptor[kJoystickPorts];
+  Task m_task;
+  std::atomic<bool> m_isRunning{false};
+  mutable Semaphore m_newControlData{Semaphore::kEmpty};
+  mutable priority_condition_variable m_packetDataAvailableCond;
+  priority_mutex m_packetDataAvailableMutex;
+  std::condition_variable_any m_waitForDataCond;
+  priority_mutex m_waitForDataMutex;
+  bool m_userInDisabled = false;
+  bool m_userInAutonomous = false;
+  bool m_userInTeleop = false;
+  bool m_userInTest = false;
+  double m_nextMessageTime = 0;
+};
diff --git a/wpilibc/Athena/include/Encoder.h b/wpilibc/Athena/include/Encoder.h
new file mode 100644
index 0000000..76bfaf9
--- /dev/null
+++ b/wpilibc/Athena/include/Encoder.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "CounterBase.h"
+#include "SensorBase.h"
+#include "Counter.h"
+#include "PIDSource.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+class DigitalSource;
+class DigitalGlitchFilter;
+
+/**
+ * Class to read quad encoders.
+ * Quadrature encoders are devices that count shaft rotation and can sense
+ * direction. The output of
+ * the QuadEncoder class is an integer that can count either up or down, and can
+ * go negative for
+ * reverse direction counting. When creating QuadEncoders, a direction is
+ * supplied that changes the
+ * sense of the output to make code more readable if the encoder is mounted such
+ * that forward movement
+ * generates negative values. Quadrature encoders have two digital outputs, an A
+ * Channel and a B Channel
+ * that are out of phase with each other to allow the FPGA to do direction
+ * sensing.
+ *
+ * All encoders will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Encoder : public SensorBase,
+                public CounterBase,
+                public PIDSource,
+                public LiveWindowSendable {
+ public:
+  enum IndexingType {
+    kResetWhileHigh,
+    kResetWhileLow,
+    kResetOnFallingEdge,
+    kResetOnRisingEdge
+  };
+
+  Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+  Encoder(std::shared_ptr<DigitalSource> aSource,
+          std::shared_ptr<DigitalSource> bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+  Encoder(DigitalSource *aSource, DigitalSource *bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+  Encoder(DigitalSource &aSource, DigitalSource &bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+  virtual ~Encoder();
+
+  // CounterBase interface
+  int32_t Get() const override;
+  int32_t GetRaw() const;
+  int32_t GetEncodingScale() const;
+  void Reset() override;
+  double GetPeriod() const override;
+  void SetMaxPeriod(double maxPeriod) override;
+  bool GetStopped() const override;
+  bool GetDirection() const override;
+
+  double GetDistance() const;
+  double GetRate() const;
+  void SetMinRate(double minRate);
+  void SetDistancePerPulse(double distancePerPulse);
+  void SetReverseDirection(bool reverseDirection);
+  void SetSamplesToAverage(int samplesToAverage);
+  int GetSamplesToAverage() const;
+  double PIDGet() override;
+
+  void SetIndexSource(uint32_t channel, IndexingType type = kResetOnRisingEdge);
+  DEPRECATED("Use pass-by-reference instead.")
+  void SetIndexSource(DigitalSource *source,
+                      IndexingType type = kResetOnRisingEdge);
+  void SetIndexSource(const DigitalSource &source,
+                      IndexingType type = kResetOnRisingEdge);
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  int32_t GetFPGAIndex() const { return m_index; }
+
+ private:
+  void InitEncoder(bool _reverseDirection, EncodingType encodingType);
+  double DecodingScaleFactor() const;
+
+  std::shared_ptr<DigitalSource> m_aSource; // the A phase of the quad encoder
+  std::shared_ptr<DigitalSource> m_bSource; // the B phase of the quad encoder
+  void *m_encoder = nullptr;
+  int32_t m_index = 0;             // The encoder's FPGA index.
+  double m_distancePerPulse = 1.0; // distance of travel for each encoder tick
+  std::unique_ptr<Counter> m_counter =
+      nullptr;                     // Counter object for 1x and 2x encoding
+  EncodingType m_encodingType;     // Encoding type
+  int32_t m_encodingScale;         // 1x, 2x, or 4x, per the encodingType
+
+  std::shared_ptr<ITable> m_table;
+  friend class DigitalGlitchFilter;
+};
diff --git a/wpilibc/Athena/include/GearTooth.h b/wpilibc/Athena/include/GearTooth.h
new file mode 100644
index 0000000..3889f9c
--- /dev/null
+++ b/wpilibc/Athena/include/GearTooth.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "Counter.h"
+#include <memory>
+
+/**
+ * Alias for counter class.
+ * Implement the gear tooth sensor supplied by FIRST. Currently there is no
+ * reverse sensing on
+ * the gear tooth sensor, but in future versions we might implement the
+ * necessary timing in the
+ * FPGA to sense direction.
+ */
+class GearTooth : public Counter {
+ public:
+  /// 55 uSec for threshold
+  static constexpr double kGearToothThreshold = 55e-6;
+  GearTooth(uint32_t channel, bool directionSensitive = false);
+  GearTooth(DigitalSource *source, bool directionSensitive = false);
+  GearTooth(std::shared_ptr<DigitalSource> source,
+            bool directionSensitive = false);
+  virtual ~GearTooth() = default;
+  void EnableDirectionSensing(bool directionSensitive);
+
+  virtual std::string GetSmartDashboardType() const override;
+};
diff --git a/wpilibc/Athena/include/GyroBase.h b/wpilibc/Athena/include/GyroBase.h
new file mode 100644
index 0000000..6ed44aa
--- /dev/null
+++ b/wpilibc/Athena/include/GyroBase.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SensorBase.h"
+#include "PIDSource.h"
+#include "interfaces/Gyro.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * GyroBase is the common base class for Gyro implementations such as
+ * AnalogGyro.
+ */
+class GyroBase : public Gyro, public SensorBase, public PIDSource, public LiveWindowSendable {
+ public:
+  virtual ~GyroBase() = default;
+
+  // PIDSource interface
+  double PIDGet() override;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/I2C.h b/wpilibc/Athena/include/I2C.h
new file mode 100644
index 0000000..89041e7
--- /dev/null
+++ b/wpilibc/Athena/include/I2C.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SensorBase.h"
+
+/**
+ * I2C bus interface class.
+ *
+ * This class is intended to be used by sensor (and other I2C device) drivers.
+ * It probably should not be used directly.
+ *
+ */
+class I2C : SensorBase {
+ public:
+  enum Port { kOnboard, kMXP };
+
+  I2C(Port port, uint8_t deviceAddress);
+  virtual ~I2C();
+
+  I2C(const I2C&) = delete;
+  I2C& operator=(const I2C&) = delete;
+
+  bool Transaction(uint8_t *dataToSend, uint8_t sendSize, uint8_t *dataReceived,
+                   uint8_t receiveSize);
+  bool AddressOnly();
+  bool Write(uint8_t registerAddress, uint8_t data);
+  bool WriteBulk(uint8_t *data, uint8_t count);
+  bool Read(uint8_t registerAddress, uint8_t count, uint8_t *data);
+  bool ReadOnly(uint8_t count, uint8_t *buffer);
+  void Broadcast(uint8_t registerAddress, uint8_t data);
+  bool VerifySensor(uint8_t registerAddress, uint8_t count,
+                    const uint8_t *expected);
+
+ private:
+  Port m_port;
+  uint8_t m_deviceAddress;
+};
diff --git a/wpilibc/Athena/include/Internal/HardwareHLReporting.h b/wpilibc/Athena/include/Internal/HardwareHLReporting.h
new file mode 100644
index 0000000..a91a20d
--- /dev/null
+++ b/wpilibc/Athena/include/Internal/HardwareHLReporting.h
@@ -0,0 +1,8 @@
+
+#include "HLUsageReporting.h"
+
+class HardwareHLReporting : public HLUsageReportingInterface {
+ public:
+  virtual void ReportScheduler();
+  virtual void ReportSmartDashboard();
+};
diff --git a/wpilibc/Athena/include/InterruptableSensorBase.h b/wpilibc/Athena/include/InterruptableSensorBase.h
new file mode 100644
index 0000000..d77ae2f
--- /dev/null
+++ b/wpilibc/Athena/include/InterruptableSensorBase.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "SensorBase.h"
+#include "Resource.h"
+
+#include <memory>
+
+class InterruptableSensorBase : public SensorBase {
+ public:
+  enum WaitResult {
+    kTimeout = 0x0,
+    kRisingEdge = 0x1,
+    kFallingEdge = 0x100,
+    kBoth = 0x101,
+  };
+
+  InterruptableSensorBase();
+  virtual ~InterruptableSensorBase() = default;
+  virtual uint32_t GetChannelForRouting() const = 0;
+  virtual uint32_t GetModuleForRouting() const = 0;
+  virtual bool GetAnalogTriggerForRouting() const = 0;
+  virtual void RequestInterrupts(
+      InterruptHandlerFunction handler,
+      void *param);                  ///< Asynchronus handler version.
+  virtual void RequestInterrupts();  ///< Synchronus Wait version.
+  virtual void
+  CancelInterrupts();  ///< Free up the underlying chipobject functions.
+  virtual WaitResult WaitForInterrupt(
+      float timeout, bool ignorePrevious = true);  ///< Synchronus version.
+  virtual void
+  EnableInterrupts();  ///< Enable interrupts - after finishing setup.
+  virtual void DisableInterrupts();       ///< Disable, but don't deallocate.
+  virtual double ReadRisingTimestamp();   ///< Return the timestamp for the
+                                          ///rising interrupt that occurred.
+  virtual double ReadFallingTimestamp();  ///< Return the timestamp for the
+                                          ///falling interrupt that occurred.
+  virtual void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+ protected:
+  void *m_interrupt = nullptr;
+  uint32_t m_interruptIndex = std::numeric_limits<uint32_t>::max();
+  void AllocateInterrupts(bool watcher);
+
+  static std::unique_ptr<Resource> m_interrupts;
+};
diff --git a/wpilibc/Athena/include/IterativeRobot.h b/wpilibc/Athena/include/IterativeRobot.h
new file mode 100644
index 0000000..ccea4f8
--- /dev/null
+++ b/wpilibc/Athena/include/IterativeRobot.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "Timer.h"
+#include "RobotBase.h"
+
+/**
+ * IterativeRobot implements a specific type of Robot Program framework,
+ * extending the RobotBase class.
+ *
+ * The IterativeRobot class is intended to be subclassed by a user creating a
+ * robot program.
+ *
+ * This class is intended to implement the "old style" default code, by
+ * providing
+ * the following functions which are called by the main loop,
+ * StartCompetition(), at the appropriate times:
+ *
+ * RobotInit() -- provide for initialization at robot power-on
+ *
+ * Init() functions -- each of the following functions is called once when the
+ *                     appropriate mode is entered:
+ *  - DisabledInit()   -- called only when first disabled
+ *  - AutonomousInit() -- called each and every time autonomous is entered from
+ * another mode
+ *  - TeleopInit()     -- called each and every time teleop is entered from
+ * another mode
+ *  - TestInit()       -- called each and every time test is entered from
+ * another mode
+ *
+ * Periodic() functions -- each of these functions is called iteratively at the
+ *                         appropriate periodic rate (aka the "slow loop").  The
+ * default period of
+ *                         the iterative robot is synced to the driver station
+ * control packets,
+ *                         giving a periodic frequency of about 50Hz (50 times
+ * per second).
+ *   - DisabledPeriodic()
+ *   - AutonomousPeriodic()
+ *   - TeleopPeriodic()
+ *   - TestPeriodic()
+ *
+ */
+
+class IterativeRobot : public RobotBase {
+ public:
+  /*
+   * The default period for the periodic function calls (seconds)
+   * Setting the period to 0.0 will cause the periodic functions to follow
+   * the Driver Station packet rate of about 50Hz.
+   */
+  static constexpr double kDefaultPeriod = 0.0;
+
+  virtual void StartCompetition();
+
+  virtual void RobotInit();
+  virtual void DisabledInit();
+  virtual void AutonomousInit();
+  virtual void TeleopInit();
+  virtual void TestInit();
+
+  virtual void DisabledPeriodic();
+  virtual void AutonomousPeriodic();
+  virtual void TeleopPeriodic();
+  virtual void TestPeriodic();
+
+ protected:
+  virtual ~IterativeRobot() = default;
+  IterativeRobot() = default;
+
+ private:
+  bool m_disabledInitialized = false;
+  bool m_autonomousInitialized = false;
+  bool m_teleopInitialized = false;
+  bool m_testInitialized = false;
+};
diff --git a/wpilibc/Athena/include/Jaguar.h b/wpilibc/Athena/include/Jaguar.h
new file mode 100644
index 0000000..feb00c7
--- /dev/null
+++ b/wpilibc/Athena/include/Jaguar.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Luminary Micro / Vex Robotics Jaguar Speed Controller with PWM control
+ */
+class Jaguar : public SafePWM, public SpeedController {
+ public:
+  explicit Jaguar(uint32_t channel);
+  virtual ~Jaguar() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+
+  virtual void PIDWrite(float output) override;
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/Joystick.h b/wpilibc/Athena/include/Joystick.h
new file mode 100644
index 0000000..b8ea292
--- /dev/null
+++ b/wpilibc/Athena/include/Joystick.h
@@ -0,0 +1,118 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#ifndef JOYSTICK_H_
+#define JOYSTICK_H_
+
+#include <cstdint>
+#include <memory>
+#include <vector>
+#include "GenericHID.h"
+#include "ErrorBase.h"
+
+class DriverStation;
+
+/**
+ * Handle input from standard Joysticks connected to the Driver Station.
+ * This class handles standard input that comes from the Driver Station. Each
+ * time a value is requested
+ * the most recent value is returned. There is a single class instance for each
+ * joystick and the mapping
+ * of ports to hardware buttons depends on the code in the driver station.
+ */
+class Joystick : public GenericHID, public ErrorBase {
+ public:
+  static const uint32_t kDefaultXAxis = 0;
+  static const uint32_t kDefaultYAxis = 1;
+  static const uint32_t kDefaultZAxis = 2;
+  static const uint32_t kDefaultTwistAxis = 2;
+  static const uint32_t kDefaultThrottleAxis = 3;
+  typedef enum {
+    kXAxis,
+    kYAxis,
+    kZAxis,
+    kTwistAxis,
+    kThrottleAxis,
+    kNumAxisTypes
+  } AxisType;
+  static const uint32_t kDefaultTriggerButton = 1;
+  static const uint32_t kDefaultTopButton = 2;
+  typedef enum { kTriggerButton, kTopButton, kNumButtonTypes } ButtonType;
+  typedef enum { kLeftRumble, kRightRumble } RumbleType;
+  typedef enum {
+    kUnknown = -1,
+    kXInputUnknown = 0,
+    kXInputGamepad = 1,
+    kXInputWheel = 2,
+    kXInputArcadeStick = 3,
+    kXInputFlightStick = 4,
+    kXInputDancePad = 5,
+    kXInputGuitar = 6,
+    kXInputGuitar2 = 7,
+    kXInputDrumKit = 8,
+    kXInputGuitar3 = 11,
+    kXInputArcadePad = 19,
+    kHIDJoystick = 20,
+    kHIDGamepad = 21,
+    kHIDDriving = 22,
+    kHIDFlight = 23,
+    kHID1stPerson = 24
+  } HIDType;
+  explicit Joystick(uint32_t port);
+  Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes);
+  virtual ~Joystick() = default;
+
+  Joystick(const Joystick&) = delete;
+  Joystick& operator=(const Joystick&) = delete;
+
+  uint32_t GetAxisChannel(AxisType axis) const;
+  void SetAxisChannel(AxisType axis, uint32_t channel);
+
+  virtual float GetX(JoystickHand hand = kRightHand) const override;
+  virtual float GetY(JoystickHand hand = kRightHand) const override;
+  virtual float GetZ() const override;
+  virtual float GetTwist() const override;
+  virtual float GetThrottle() const override;
+  virtual float GetAxis(AxisType axis) const;
+  float GetRawAxis(uint32_t axis) const override;
+
+  virtual bool GetTrigger(JoystickHand hand = kRightHand) const override;
+  virtual bool GetTop(JoystickHand hand = kRightHand) const override;
+  virtual bool GetBumper(JoystickHand hand = kRightHand) const override;
+  virtual bool GetRawButton(uint32_t button) const override;
+  virtual int GetPOV(uint32_t pov = 0) const override;
+  bool GetButton(ButtonType button) const;
+  static Joystick *GetStickForPort(uint32_t port);
+
+  virtual float GetMagnitude() const;
+  virtual float GetDirectionRadians() const;
+  virtual float GetDirectionDegrees() const;
+
+  bool GetIsXbox() const;
+  Joystick::HIDType GetType() const;
+  std::string GetName() const;
+  int GetAxisType(uint8_t axis) const;
+
+  int GetAxisCount() const;
+  int GetButtonCount() const;
+  int GetPOVCount() const;
+
+  void SetRumble(RumbleType type, float value);
+  void SetOutput(uint8_t outputNumber, bool value);
+  void SetOutputs(uint32_t value);
+
+ private:
+  DriverStation &m_ds;
+  uint32_t m_port;
+  std::vector<uint32_t> m_axes;
+  std::vector<uint32_t> m_buttons;
+  uint32_t m_outputs = 0;
+  uint16_t m_leftRumble = 0;
+  uint16_t m_rightRumble = 0;
+};
+
+#endif
diff --git a/wpilibc/Athena/include/MotorSafety.h b/wpilibc/Athena/include/MotorSafety.h
new file mode 100644
index 0000000..6963ae7
--- /dev/null
+++ b/wpilibc/Athena/include/MotorSafety.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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
+
+#define DEFAULT_SAFETY_EXPIRATION 0.1
+
+#include <sstream>
+
+class MotorSafety {
+ public:
+  virtual void SetExpiration(float timeout) = 0;
+  virtual float GetExpiration() const = 0;
+  virtual bool IsAlive() const = 0;
+  virtual void StopMotor() = 0;
+  virtual void SetSafetyEnabled(bool enabled) = 0;
+  virtual bool IsSafetyEnabled() const = 0;
+  virtual void GetDescription(std::ostringstream& desc) const = 0;
+};
diff --git a/wpilibc/Athena/include/MotorSafetyHelper.h b/wpilibc/Athena/include/MotorSafetyHelper.h
new file mode 100644
index 0000000..bbe7658
--- /dev/null
+++ b/wpilibc/Athena/include/MotorSafetyHelper.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "ErrorBase.h"
+#include "HAL/cpp/priority_mutex.h"
+
+#include <set>
+
+class MotorSafety;
+
+class MotorSafetyHelper : public ErrorBase {
+ public:
+  MotorSafetyHelper(MotorSafety *safeObject);
+  ~MotorSafetyHelper();
+  void Feed();
+  void SetExpiration(float expirationTime);
+  float GetExpiration() const;
+  bool IsAlive() const;
+  void Check();
+  void SetSafetyEnabled(bool enabled);
+  bool IsSafetyEnabled() const;
+  static void CheckMotors();
+
+ private:
+  double m_expiration;  // the expiration time for this object
+  bool m_enabled;       // true if motor safety is enabled for this motor
+  double m_stopTime;    // the FPGA clock value when this motor has expired
+  mutable priority_recursive_mutex
+      m_syncMutex;            // protect accesses to the state for this object
+  MotorSafety *m_safeObject;  // the object that is using the helper
+  // List of all existing MotorSafetyHelper objects.
+  static std::set<MotorSafetyHelper*> m_helperList;
+  static priority_recursive_mutex
+      m_listMutex;  // protect accesses to the list of helpers
+};
diff --git a/wpilibc/Athena/include/NIIMAQdx.h b/wpilibc/Athena/include/NIIMAQdx.h
new file mode 100644
index 0000000..87be7f6
--- /dev/null
+++ b/wpilibc/Athena/include/NIIMAQdx.h
@@ -0,0 +1,950 @@
+//==============================================================================
+//
+//  Title	  : NIIMAQdx.h
+//  Created	  : 1403685834 seconds after 1/1/1970 12:00:00 UTC
+//  Copyright : © Copyright 2006, National Instruments Corporation, All rights
+//  reserved
+// 	Purpose	  : Include file for NI-IMAQdx library support.
+//
+//==============================================================================
+#ifndef ___niimaqdx_h___
+#define ___niimaqdx_h___
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#if !defined(niimaqdx_types)
+#define niimaqdx_types
+
+#ifdef _CVI_
+#pragma EnableLibraryRuntimeChecking
+#endif
+
+//==============================================================================
+//  Typedefs
+//==============================================================================
+#ifndef _NI_uInt8_DEFINED_
+#define _NI_uInt8_DEFINED_
+typedef unsigned char uInt8;
+#endif
+
+#ifndef _NI_uInt16_DEFINED_
+#define _NI_uInt16_DEFINED_
+typedef unsigned short int uInt16;
+#endif
+
+#ifndef _NI_uInt32_DEFINED_
+#define _NI_uInt32_DEFINED_
+#if defined(_MSC_VER)
+typedef unsigned long uInt32;
+#elif __GNUC__
+#if __x86_64__
+typedef unsigned int uInt32;
+#else
+typedef unsigned long uInt32;
+#endif
+#endif
+#endif
+
+#ifndef _NI_uInt64_DEFINED_
+#define _NI_uInt64_DEFINED_
+#if defined(_MSC_VER) || _CVI_ >= 700
+typedef unsigned __int64 uInt64;
+#elif __GNUC__
+typedef unsigned long long uInt64;
+#endif
+#endif
+
+#ifndef _NI_Int8_DEFINED_
+#define _NI_Int8_DEFINED_
+typedef char Int8;
+#endif
+
+#ifndef _NI_Int16_DEFINED_
+#define _NI_Int16_DEFINED_
+typedef short int Int16;
+#endif
+
+#ifndef _NI_Int32_DEFINED_
+#define _NI_Int32_DEFINED_
+#if defined(_MSC_VER)
+typedef long Int32;
+#elif __GNUC__
+#if __x86_64__
+typedef int Int32;
+#else
+typedef long Int32;
+#endif
+#endif
+#endif
+
+#ifndef _NI_Int64_DEFINED_
+#define _NI_Int64_DEFINED_
+#if defined(_MSC_VER) || _CVI_ >= 700
+typedef __int64 Int64;
+#elif __GNUC__
+typedef long long int Int64;
+#endif
+#endif
+
+#ifndef _NI_float32_DEFINED_
+#define _NI_float32_DEFINED_
+typedef float float32;
+#endif
+
+#ifndef _NI_float64_DEFINED_
+#define _NI_float64_DEFINED_
+typedef double float64;
+#endif
+
+#ifndef TRUE
+#define TRUE (1L)
+#endif
+
+#ifndef FALSE
+#define FALSE (0L)
+#endif
+
+#ifndef _NI_GUIDHNDL_DEFINED
+typedef uInt32 GUIHNDL;
+#endif
+
+#if (defined(_MSC_VER) || defined(_CVI_))
+#ifndef _NI_FUNC_DEFINED
+#define NI_FUNC __stdcall
+#endif
+
+#ifndef _NI_FUNCC_DEFINED
+#define NI_FUNCC __cdecl
+#endif
+#elif defined(__GNUC__)
+#ifndef _NI_FUNC_DEFINED
+#define NI_FUNC
+#endif
+
+#ifndef _NI_FUNCC_DEFINED
+#define NI_FUNCC
+#endif
+#endif
+
+#ifndef _NI_bool32_DEFINED_
+#define _NI_bool32_DEFINED_
+typedef uInt32 bool32;
+#endif
+
+#ifndef _NI_IMAQdxSession_DEFINED_
+#define _NI_IMAQdxSession_DEFINED_
+typedef uInt32 IMAQdxSession;
+#endif
+
+#define IMAQDX_MAX_API_STRING_LENGTH 512
+
+//==============================================================================
+//  Forward Declare Data Structures
+//==============================================================================
+typedef struct Image_struct Image;
+
+//==============================================================================
+//  Error Codes Enumeration
+//==============================================================================
+typedef enum IMAQdxError_enum {
+  IMAQdxErrorSuccess = 0x0,                  // Success
+  IMAQdxErrorSystemMemoryFull = 0xBFF69000,  // Not enough memory
+  IMAQdxErrorInternal,                       // Internal error
+  IMAQdxErrorInvalidParameter,               // Invalid parameter
+  IMAQdxErrorInvalidPointer,                 // Invalid pointer
+  IMAQdxErrorInvalidInterface,               // Invalid camera session
+  IMAQdxErrorInvalidRegistryKey,             // Invalid registry key
+  IMAQdxErrorInvalidAddress,                 // Invalid address
+  IMAQdxErrorInvalidDeviceType,              // Invalid device type
+  IMAQdxErrorNotImplemented,                 // Not implemented
+  IMAQdxErrorCameraNotFound,                 // Camera not found
+  IMAQdxErrorCameraInUse,                    // Camera is already in use.
+  IMAQdxErrorCameraNotInitialized,           // Camera is not initialized.
+  IMAQdxErrorCameraRemoved,                  // Camera has been removed.
+  IMAQdxErrorCameraRunning,                  // Acquisition in progress.
+  IMAQdxErrorCameraNotRunning,               // No acquisition in progress.
+  IMAQdxErrorAttributeNotSupported,  // Attribute not supported by the camera.
+  IMAQdxErrorAttributeNotSettable,   // Unable to set attribute.
+  IMAQdxErrorAttributeNotReadable,   // Unable to get attribute.
+  IMAQdxErrorAttributeOutOfRange,    // Attribute value is out of range.
+  IMAQdxErrorBufferNotAvailable,     // Requested buffer is unavailable.
+  IMAQdxErrorBufferListEmpty,  // Buffer list is empty. Add one or more buffers.
+  IMAQdxErrorBufferListLocked,     // Buffer list is already locked. Reconfigure
+                                   // acquisition and try again.
+  IMAQdxErrorBufferListNotLocked,  // No buffer list. Reconfigure acquisition
+                                   // and try again.
+  IMAQdxErrorResourcesAllocated,   // Transfer engine resources already
+                                   // allocated. Reconfigure acquisition and try
+                                   // again.
+  IMAQdxErrorResourcesUnavailable,  // Insufficient transfer engine resources.
+  IMAQdxErrorAsyncWrite,  // Unable to perform asychronous register write.
+  IMAQdxErrorAsyncRead,   // Unable to perform asychronous register read.
+  IMAQdxErrorTimeout,     // Timeout.
+  IMAQdxErrorBusReset,    // Bus reset occurred during a transaction.
+  IMAQdxErrorInvalidXML,  // Unable to load camera's XML file.
+  IMAQdxErrorFileAccess,  // Unable to read/write to file.
+  IMAQdxErrorInvalidCameraURLString,  // Camera has malformed URL string.
+  IMAQdxErrorInvalidCameraFile,       // Invalid camera file.
+  IMAQdxErrorGenICamError,            // Unknown Genicam error.
+  IMAQdxErrorFormat7Parameters,       // For format 7: The combination of speed,
+                                 // image position, image size, and color coding
+                                 // is incorrect.
+  IMAQdxErrorInvalidAttributeType,  // The attribute type is not compatible with
+                                    // the passed variable type.
+  IMAQdxErrorDLLNotFound,           // The DLL could not be found.
+  IMAQdxErrorFunctionNotFound,      // The function could not be found.
+  IMAQdxErrorLicenseNotActivated,   // License not activated.
+  IMAQdxErrorCameraNotConfiguredForListener,  // The camera is not configured
+                                              // properly to support a listener.
+  IMAQdxErrorCameraMulticastNotAvailable,  // Unable to configure the system for
+                                           // multicast support.
+  IMAQdxErrorBufferHasLostPackets,  // The requested buffer has lost packets and
+                                    // the user requested an error to be
+                                    // generated.
+  IMAQdxErrorGiGEVisionError,       // Unknown GiGE Vision error.
+  IMAQdxErrorNetworkError,          // Unknown network error.
+  IMAQdxErrorCameraUnreachable,     // Unable to connect to the camera.
+  IMAQdxErrorHighPerformanceNotSupported,  // High performance acquisition is
+                                           // not supported on the specified
+                                           // network interface. Connect the
+                                           // camera to a network interface
+                                           // running the high performance
+                                           // driver.
+  IMAQdxErrorInterfaceNotRenamed,    // Unable to rename interface. Invalid or
+                                     // duplicate name specified.
+  IMAQdxErrorNoSupportedVideoModes,  // The camera does not have any video modes
+                                     // which are supported.
+  IMAQdxErrorSoftwareTriggerOverrun,  // Software trigger overrun.
+  IMAQdxErrorTestPacketNotReceived,  // The system did not receive a test packet
+                                     // from the camera. The packet size may be
+                                     // too large for the network configuration
+                                     // or a firewall may be enabled.
+  IMAQdxErrorCorruptedImageReceived,  // The camera returned a corrupted image.
+  IMAQdxErrorCameraConfigurationHasChanged,  // The camera did not return an
+                                             // image of the correct type it was
+                                             // configured for previously.
+  IMAQdxErrorCameraInvalidAuthentication,    // The camera is configured with
+                                           // password authentication and either
+                                           // the user name and password were
+                                           // not configured or they are
+                                           // incorrect.
+  IMAQdxErrorUnknownHTTPError,  // The camera returned an unknown HTTP error.
+  IMAQdxErrorKernelDriverUnavailable,  // Unable to attach to the kernel mode
+                                       // driver.
+  IMAQdxErrorPixelFormatDecoderUnavailable,  // No decoder available for
+                                             // selected pixel format.
+  IMAQdxErrorFirmwareUpdateNeeded,  // The acquisition hardware needs a firmware
+                                    // update before it can be used.
+  IMAQdxErrorFirmwareUpdateRebootNeeded,  // The firmware on the acquisition
+                                          // hardware has been updated and the
+                                          // system must be rebooted before use.
+  IMAQdxErrorLightingCurrentOutOfRange,  // The requested current level from the
+                                         // lighting controller is not possible.
+  IMAQdxErrorUSB3VisionError,            // Unknown USB3 Vision error.
+  IMAQdxErrorInvalidU3VUSBDescriptor,    // The camera has a USB descriptor that
+                                         // is incompatible with the USB3 Vision
+                                         // specification.
+  IMAQdxErrorU3VInvalidControlInterface,  // The USB3 Vision control interface
+                                          // is not implemented or is invalid on
+                                          // this camera.
+  IMAQdxErrorU3VControlInterfaceError,    // There was an error from the control
+                                        // interface of the USB3 Vision camera.
+  IMAQdxErrorU3VInvalidEventInterface,  // The USB3 Vision event interface is
+                                        // not implemented or is invalid on this
+                                        // camera.
+  IMAQdxErrorU3VEventInterfaceError,    // There was an error from the event
+                                        // interface of the USB3 Vision camera.
+  IMAQdxErrorU3VInvalidStreamInterface,  // The USB3 Vision stream interface is
+                                         // not implemented or is invalid on
+                                         // this camera.
+  IMAQdxErrorU3VStreamInterfaceError,    // There was an error from the stream
+                                         // interface of the USB3 Vision camera.
+  IMAQdxErrorU3VUnsupportedConnectionSpeed,  // The USB connection speed is not
+                                             // supported by the camera.  Check
+                                             // whether the camera is plugged
+                                             // into a USB 2.0 port instead of a
+                                             // USB 3.0 port.  If so, verify
+                                             // that the camera supports this
+                                             // use case.
+  IMAQdxErrorU3VInsufficientPower,  // The USB3 Vision camera requires more
+                                    // current than can be supplied by the USB
+                                    // port in use.
+  IMAQdxErrorU3VInvalidMaxCurrent,  // The U3V_MaximumCurrentUSB20_mA registry
+                                    // value is not valid for the connected USB3
+                                    // Vision camera.
+  IMAQdxErrorBufferIncompleteData,  // The requested buffer has incomplete data
+                                    // and the user requested an error to be
+                                    // generated.
+  IMAQdxErrorCameraAcquisitionConfigFailed,  // The camera returned an error
+                                             // starting the acquisition.
+  IMAQdxErrorCameraClosePending,  // The camera still has outstanding references
+                                  // and will be closed when these operations
+                                  // complete.
+  IMAQdxErrorSoftwareFault,       // An unexpected software error occurred.
+  IMAQdxErrorCameraPropertyInvalid,  // The value for an invalid camera property
+                                     // was requested.
+  IMAQdxErrorJumboFramesNotEnabled,  // Jumbo frames are not enabled on the
+                                     // host.  Maximum packet size is 1500
+                                     // bytes.
+  IMAQdxErrorBayerPixelFormatNotSelected,  // This operation requires that the
+                                           // camera has a Bayer pixel format
+                                           // selected.
+  IMAQdxErrorGuard = 0xFFFFFFFF,
+} IMAQdxError;
+
+//==============================================================================
+//  Bus Type Enumeration
+//==============================================================================
+typedef enum IMAQdxBusType_enum {
+  IMAQdxBusTypeFireWire = 0x31333934,
+  IMAQdxBusTypeEthernet = 0x69707634,
+  IMAQdxBusTypeSimulator = 0x2073696D,
+  IMAQdxBusTypeDirectShow = 0x64736877,
+  IMAQdxBusTypeIP = 0x4950636D,
+  IMAQdxBusTypeSmartCam2 = 0x53436132,
+  IMAQdxBusTypeUSB3Vision = 0x55534233,
+  IMAQdxBusTypeUVC = 0x55564320,
+  IMAQdxBusTypeGuard = 0xFFFFFFFF,
+} IMAQdxBusType;
+
+//==============================================================================
+//  Camera Control Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxCameraControlMode_enum {
+  IMAQdxCameraControlModeController,
+  IMAQdxCameraControlModeListener,
+  IMAQdxCameraControlModeGuard = 0xFFFFFFFF,
+} IMAQdxCameraControlMode;
+
+//==============================================================================
+//  Buffer Number Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxBufferNumberMode_enum {
+  IMAQdxBufferNumberModeNext,
+  IMAQdxBufferNumberModeLast,
+  IMAQdxBufferNumberModeBufferNumber,
+  IMAQdxBufferNumberModeGuard = 0xFFFFFFFF,
+} IMAQdxBufferNumberMode;
+
+//==============================================================================
+//  Plug n Play Event Enumeration
+//==============================================================================
+typedef enum IMAQdxPnpEvent_enum {
+  IMAQdxPnpEventCameraAttached,
+  IMAQdxPnpEventCameraDetached,
+  IMAQdxPnpEventBusReset,
+  IMAQdxPnpEventGuard = 0xFFFFFFFF,
+} IMAQdxPnpEvent;
+
+//==============================================================================
+//  Bayer Pattern Enumeration
+//==============================================================================
+typedef enum IMAQdxBayerPattern_enum {
+  IMAQdxBayerPatternNone,
+  IMAQdxBayerPatternGB,
+  IMAQdxBayerPatternGR,
+  IMAQdxBayerPatternBG,
+  IMAQdxBayerPatternRG,
+  IMAQdxBayerPatternHardware,
+  IMAQdxBayerPatternGuard = 0xFFFFFFFF,
+} IMAQdxBayerPattern;
+
+//==============================================================================
+//  Bayer Decode Algorithm Enumeration
+//==============================================================================
+typedef enum IMAQdxBayerAlgorithm_enum {
+  IMAQdxBayerAlgorithmBilinear,
+  IMAQdxBayerAlgorithmVNG,
+  IMAQdxBayerAlgorithmGuard = 0xFFFFFFFF,
+} IMAQdxBayerAlgorithm;
+
+//==============================================================================
+//  Output Image Types -- Values match Vision Development Module image types
+//==============================================================================
+typedef enum IMAQdxOutputImageType_enum {
+  IMAQdxOutputImageTypeU8 = 0,
+  IMAQdxOutputImageTypeI16 = 1,
+  IMAQdxOutputImageTypeU16 = 7,
+  IMAQdxOutputImageTypeRGB32 = 4,
+  IMAQdxOutputImageTypeRGB64 = 6,
+  IMAQdxOutputImageTypeAuto = 0x7FFFFFFF,
+  IMAQdxOutputImageTypeGuard = 0xFFFFFFFF,
+} IMAQdxOutputImageType;
+
+//==============================================================================
+//  Controller Destination Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxDestinationMode_enum {
+  IMAQdxDestinationModeUnicast,
+  IMAQdxDestinationModeBroadcast,
+  IMAQdxDestinationModeMulticast,
+  IMAQdxDestinationModeGuard = 0xFFFFFFFF,
+} IMAQdxDestinationMode;
+
+//==============================================================================
+//   Attribute Type Enumeration
+//==============================================================================
+typedef enum IMAQdxAttributeType_enum {
+  IMAQdxAttributeTypeU32,
+  IMAQdxAttributeTypeI64,
+  IMAQdxAttributeTypeF64,
+  IMAQdxAttributeTypeString,
+  IMAQdxAttributeTypeEnum,
+  IMAQdxAttributeTypeBool,
+  IMAQdxAttributeTypeCommand,
+  IMAQdxAttributeTypeBlob,
+  IMAQdxAttributeTypeGuard = 0xFFFFFFFF,
+} IMAQdxAttributeType;
+
+//==============================================================================
+//  Value Type Enumeration
+//==============================================================================
+typedef enum IMAQdxValueType_enum {
+  IMAQdxValueTypeU32,
+  IMAQdxValueTypeI64,
+  IMAQdxValueTypeF64,
+  IMAQdxValueTypeString,
+  IMAQdxValueTypeEnumItem,
+  IMAQdxValueTypeBool,
+  IMAQdxValueTypeDisposableString,
+  IMAQdxValueTypeGuard = 0xFFFFFFFF,
+} IMAQdxValueType;
+
+//==============================================================================
+//  Interface File Flags Enumeration
+//==============================================================================
+typedef enum IMAQdxInterfaceFileFlags_enum {
+  IMAQdxInterfaceFileFlagsConnected = 0x1,
+  IMAQdxInterfaceFileFlagsDirty = 0x2,
+  IMAQdxInterfaceFileFlagsGuard = 0xFFFFFFFF,
+} IMAQdxInterfaceFileFlags;
+
+//==============================================================================
+//  Overwrite Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxOverwriteMode_enum {
+  IMAQdxOverwriteModeGetOldest = 0x0,
+  IMAQdxOverwriteModeFail = 0x2,
+  IMAQdxOverwriteModeGetNewest = 0x3,
+  IMAQdxOverwriteModeGuard = 0xFFFFFFFF,
+} IMAQdxOverwriteMode;
+
+//==============================================================================
+//  Incomplete Buffer Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxIncompleteBufferMode_enum {
+  IMAQdxIncompleteBufferModeIgnore,
+  IMAQdxIncompleteBufferModeFail,
+  IMAQdxIncompleteBufferModeGuard = 0xFFFFFFFF,
+} IMAQdxIncompleteBufferMode;
+
+//==============================================================================
+//  Lost Packet Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxLostPacketMode_enum {
+  IMAQdxLostPacketModeIgnore,
+  IMAQdxLostPacketModeFail,
+  IMAQdxLostPacketModeGuard = 0xFFFFFFFF,
+} IMAQdxLostPacketMode;
+
+//==============================================================================
+//  Attribute Visibility Enumeration
+//==============================================================================
+typedef enum IMAQdxAttributeVisibility_enum {
+  IMAQdxAttributeVisibilitySimple = 0x00001000,
+  IMAQdxAttributeVisibilityIntermediate = 0x00002000,
+  IMAQdxAttributeVisibilityAdvanced = 0x00004000,
+  IMAQdxAttributeVisibilityGuard = 0xFFFFFFFF,
+} IMAQdxAttributeVisibility;
+
+//==============================================================================
+//  Stream Channel Mode Enumeration
+//==============================================================================
+typedef enum IMAQdxStreamChannelMode_enum {
+  IMAQdxStreamChannelModeAutomatic,
+  IMAQdxStreamChannelModeManual,
+  IMAQdxStreamChannelModeGuard = 0xFFFFFFFF,
+} IMAQdxStreamChannelMode;
+
+//==============================================================================
+//  Pixel Signedness Enumeration
+//==============================================================================
+typedef enum IMAQdxPixelSignedness_enum {
+  IMAQdxPixelSignednessUnsigned,
+  IMAQdxPixelSignednessSigned,
+  IMAQdxPixelSignednessHardware,
+  IMAQdxPixelSignednessGuard = 0xFFFFFFFF,
+} IMAQdxPixelSignedness;
+
+//==============================================================================
+//  USB Connection Speed Enumeration
+//==============================================================================
+typedef enum IMAQdxUSBConnectionSpeed_enum {
+  IMAQdxUSBConnectionSpeedLow = 1,
+  IMAQdxUSBConnectionSpeedFull = 2,
+  IMAQdxUSBConnectionSpeedHigh = 4,
+  IMAQdxUSBConnectionSpeedSuper = 8,
+  IMAQdxUSBConnectionSpeedGuard = 0xFFFFFFFF,
+} IMAQdxUSBConnectionSpeed;
+
+//==============================================================================
+//  CVI Structures
+//==============================================================================
+#pragma pack(push, 4)
+
+//==============================================================================
+//  Camera Information Structure
+//==============================================================================
+typedef struct IMAQdxCameraInformation_struct {
+  uInt32 Type;
+  uInt32 Version;
+  uInt32 Flags;
+  uInt32 SerialNumberHi;
+  uInt32 SerialNumberLo;
+  IMAQdxBusType BusType;
+  char InterfaceName[IMAQDX_MAX_API_STRING_LENGTH];
+  char VendorName[IMAQDX_MAX_API_STRING_LENGTH];
+  char ModelName[IMAQDX_MAX_API_STRING_LENGTH];
+  char CameraFileName[IMAQDX_MAX_API_STRING_LENGTH];
+  char CameraAttributeURL[IMAQDX_MAX_API_STRING_LENGTH];
+} IMAQdxCameraInformation;
+
+//==============================================================================
+//  Camera File Structure
+//==============================================================================
+typedef struct IMAQdxCameraFile_struct {
+  uInt32 Type;
+  uInt32 Version;
+  char FileName[IMAQDX_MAX_API_STRING_LENGTH];
+} IMAQdxCameraFile;
+
+//==============================================================================
+//  Attribute Information Structure
+//==============================================================================
+typedef struct IMAQdxAttributeInformation_struct {
+  IMAQdxAttributeType Type;
+  bool32 Readable;
+  bool32 Writable;
+  char Name[IMAQDX_MAX_API_STRING_LENGTH];
+} IMAQdxAttributeInformation;
+
+//==============================================================================
+//  Enumeration Item Structure
+//==============================================================================
+typedef struct IMAQdxEnumItem_struct {
+  uInt32 Value;
+  uInt32 Reserved;
+  char Name[IMAQDX_MAX_API_STRING_LENGTH];
+} IMAQdxEnumItem;
+
+//==============================================================================
+//  Camera Information Structure
+//==============================================================================
+typedef IMAQdxEnumItem IMAQdxVideoMode;
+
+#pragma pack(pop)
+
+//==============================================================================
+//  Callbacks
+//==============================================================================
+typedef uInt32(NI_FUNC* FrameDoneEventCallbackPtr)(IMAQdxSession id,
+                                                   uInt32 bufferNumber,
+                                                   void* callbackData);
+typedef uInt32(NI_FUNC* PnpEventCallbackPtr)(IMAQdxSession id,
+                                             IMAQdxPnpEvent pnpEvent,
+                                             void* callbackData);
+typedef void(NI_FUNC* AttributeUpdatedEventCallbackPtr)(IMAQdxSession id,
+                                                        const char* name,
+                                                        void* callbackData);
+
+#endif  // niimaqdx_types
+//==============================================================================
+//  Attributes
+//==============================================================================
+#define IMAQdxAttributeBaseAddress \
+  "CameraInformation::BaseAddress"  // Read only. Gets the base address of the
+                                    // camera registers.
+#define IMAQdxAttributeBusType \
+  "CameraInformation::BusType"  // Read only. Gets the bus type of the camera.
+#define IMAQdxAttributeModelName \
+  "CameraInformation::ModelName"  // Read only. Returns the model name.
+#define IMAQdxAttributeSerialNumberHigh \
+  "CameraInformation::SerialNumberHigh"  // Read only. Gets the upper 32-bits of
+                                         // the camera 64-bit serial number.
+#define IMAQdxAttributeSerialNumberLow \
+  "CameraInformation::SerialNumberLow"  // Read only. Gets the lower 32-bits of
+                                        // the camera 64-bit serial number.
+#define IMAQdxAttributeVendorName \
+  "CameraInformation::VendorName"  // Read only. Returns the vendor name.
+#define IMAQdxAttributeHostIPAddress \
+  "CameraInformation::HostIPAddress"  // Read only. Returns the host adapter IP
+                                      // address.
+#define IMAQdxAttributeIPAddress \
+  "CameraInformation::IPAddress"  // Read only. Returns the IP address.
+#define IMAQdxAttributePrimaryURLString \
+  "CameraInformation::PrimaryURLString"  // Read only. Gets the camera's primary
+                                         // URL string.
+#define IMAQdxAttributeSecondaryURLString \
+  "CameraInformation::SecondaryURLString"  // Read only. Gets the camera's
+                                           // secondary URL string.
+#define IMAQdxAttributeAcqInProgress \
+  "StatusInformation::AcqInProgress"  // Read only. Gets the current state of
+                                      // the acquisition. TRUE if acquiring;
+                                      // otherwise FALSE.
+#define IMAQdxAttributeLastBufferCount \
+  "StatusInformation::LastBufferCount"  // Read only. Gets the number of
+                                        // transferred buffers.
+#define IMAQdxAttributeLastBufferNumber \
+  "StatusInformation::LastBufferNumber"  // Read only. Gets the last cumulative
+                                         // buffer number transferred.
+#define IMAQdxAttributeLostBufferCount \
+  "StatusInformation::LostBufferCount"  // Read only. Gets the number of lost
+                                        // buffers during an acquisition
+                                        // session.
+#define IMAQdxAttributeLostPacketCount \
+  "StatusInformation::LostPacketCount"  // Read only. Gets the number of lost
+                                        // packets during an acquisition
+                                        // session.
+#define IMAQdxAttributeRequestedResendPackets \
+  "StatusInformation::RequestedResendPacketCount"  // Read only. Gets the number
+                                                   // of packets requested to be
+                                                   // resent during an
+                                                   // acquisition session.
+#define IMAQdxAttributeReceivedResendPackets \
+  "StatusInformation::ReceivedResendPackets"  // Read only. Gets the number of
+                                              // packets that were requested to
+                                              // be resent during an acquisition
+                                              // session and were completed.
+#define IMAQdxAttributeHandledEventCount \
+  "StatusInformation::HandledEventCount"  // Read only. Gets the number of
+                                          // handled events during an
+                                          // acquisition session.
+#define IMAQdxAttributeLostEventCount \
+  "StatusInformation::LostEventCount"  // Read only. Gets the number of lost
+                                       // events during an acquisition session.
+#define IMAQdxAttributeBayerGainB \
+  "AcquisitionAttributes::Bayer::GainB"  // Sets/gets the white balance gain for
+                                         // the blue component of the Bayer
+                                         // conversion.
+#define IMAQdxAttributeBayerGainG \
+  "AcquisitionAttributes::Bayer::GainG"  // Sets/gets the white balance gain for
+                                         // the green component of the Bayer
+                                         // conversion.
+#define IMAQdxAttributeBayerGainR \
+  "AcquisitionAttributes::Bayer::GainR"  // Sets/gets the white balance gain for
+                                         // the red component of the Bayer
+                                         // conversion.
+#define IMAQdxAttributeBayerPattern \
+  "AcquisitionAttributes::Bayer::Pattern"  // Sets/gets the Bayer pattern to
+                                           // use.
+#define IMAQdxAttributeStreamChannelMode \
+  "AcquisitionAttributes::Controller::StreamChannelMode"  // Gets/sets the mode
+                                                          // for allocating a
+                                                          // FireWire stream
+                                                          // channel.
+#define IMAQdxAttributeDesiredStreamChannel \
+  "AcquisitionAttributes::Controller::DesiredStreamChannel"  // Gets/sets the
+                                                             // stream channel
+                                                             // to manually
+                                                             // allocate.
+#define IMAQdxAttributeFrameInterval \
+  "AcquisitionAttributes::FrameInterval"  // Read only. Gets the duration in
+                                          // milliseconds between successive
+                                          // frames.
+#define IMAQdxAttributeIgnoreFirstFrame \
+  "AcquisitionAttributes::IgnoreFirstFrame"  // Gets/sets the video delay of one
+                                             // frame between starting the
+                                             // camera and receiving the video
+                                             // feed.
+#define IMAQdxAttributeOffsetX \
+  "OffsetX"  // Gets/sets the left offset of the image.
+#define IMAQdxAttributeOffsetY \
+  "OffsetY"                           // Gets/sets the top offset of the image.
+#define IMAQdxAttributeWidth "Width"  // Gets/sets the width of the image.
+#define IMAQdxAttributeHeight "Height"  // Gets/sets the height of the image.
+#define IMAQdxAttributePixelFormat \
+  "PixelFormat"  // Gets/sets the pixel format of the source sensor.
+#define IMAQdxAttributePacketSize \
+  "PacketSize"  // Gets/sets the packet size in bytes.
+#define IMAQdxAttributePayloadSize \
+  "PayloadSize"  // Gets/sets the frame size in bytes.
+#define IMAQdxAttributeSpeed \
+  "AcquisitionAttributes::Speed"  // Gets/sets the transfer speed in Mbps for a
+                                  // FireWire packet.
+#define IMAQdxAttributeShiftPixelBits \
+  "AcquisitionAttributes::ShiftPixelBits"  // Gets/sets the alignment of 16-bit
+                                           // cameras. Downshift the pixel bits
+                                           // if the camera returns most
+                                           // significant bit-aligned data.
+#define IMAQdxAttributeSwapPixelBytes \
+  "AcquisitionAttributes::SwapPixelBytes"  // Gets/sets the endianness of 16-bit
+                                           // cameras. Swap the pixel bytes if
+                                           // the camera returns little endian
+                                           // data.
+#define IMAQdxAttributeOverwriteMode \
+  "AcquisitionAttributes::OverwriteMode"  // Gets/sets the overwrite mode, used
+                                          // to determine acquisition when an
+                                          // image transfer cannot be completed
+                                          // due to an overwritten internal
+                                          // buffer.
+#define IMAQdxAttributeTimeout \
+  "AcquisitionAttributes::Timeout"  // Gets/sets the timeout value in
+                                    // milliseconds, used to abort an
+                                    // acquisition when the image transfer
+                                    // cannot be completed within the delay.
+#define IMAQdxAttributeVideoMode \
+  "AcquisitionAttributes::VideoMode"  // Gets/sets the video mode for a camera.
+#define IMAQdxAttributeBitsPerPixel \
+  "AcquisitionAttributes::BitsPerPixel"  // Gets/sets the actual bits per pixel.
+                                         // For 16-bit components, this
+                                         // represents the actual bit depth
+                                         // (10-, 12-, 14-, or 16-bit).
+#define IMAQdxAttributePixelSignedness \
+  "AcquisitionAttributes::PixelSignedness"  // Gets/sets the signedness of the
+                                            // pixel. For 16-bit components,
+                                            // this represents the actual pixel
+                                            // signedness (Signed, or Unsigned).
+#define IMAQdxAttributeReserveDualPackets \
+  "AcquisitionAttributes::ReserveDualPackets"  // Gets/sets if dual packets will
+                                               // be reserved for a very large
+                                               // FireWire packet.
+#define IMAQdxAttributeReceiveTimestampMode \
+  "AcquisitionAttributes::ReceiveTimestampMode"  // Gets/sets the mode for
+                                                 // timestamping images received
+                                                 // by the driver.
+#define IMAQdxAttributeActualPeakBandwidth                      \
+  "AcquisitionAttributes::AdvancedEthernet::BandwidthControl::" \
+  "ActualPeakBandwidth"  // Read only. Returns the actual maximum peak bandwidth
+                         // the camera will be configured to use.
+#define IMAQdxAttributeDesiredPeakBandwidth                     \
+  "AcquisitionAttributes::AdvancedEthernet::BandwidthControl::" \
+  "DesiredPeakBandwidth"  // Gets/sets the desired maximum peak bandwidth the
+                          // camera should use.
+#define IMAQdxAttributeDestinationMode \
+  "AcquisitionAttributes::AdvancedEthernet::Controller::DestinationMode"  // Gets/Sets
+                                                                          // where
+                                                                          // the
+                                                                          // camera
+                                                                          // is
+                                                                          // instructed
+                                                                          // to
+                                                                          // send
+                                                                          // the
+                                                                          // image
+                                                                          // stream.
+#define IMAQdxAttributeDestinationMulticastAddress        \
+  "AcquisitionAttributes::AdvancedEthernet::Controller::" \
+  "DestinationMulticastAddress"  // Gets/Sets the multicast address the camera
+                                 // should send data in multicast mode.
+#define IMAQdxAttributeEventsEnabled \
+  "AcquisitionAttributes::AdvancedEthernet::EventParameters::EventsEnabled"  // Gets/Sets if events will be handled.
+#define IMAQdxAttributeMaxOutstandingEvents                    \
+  "AcquisitionAttributes::AdvancedEthernet::EventParameters::" \
+  "MaxOutstandingEvents"  // Gets/Sets the maximum number of outstanding events
+                          // to queue.
+#define IMAQdxAttributeTestPacketEnabled                            \
+  "AcquisitionAttributes::AdvancedEthernet::TestPacketParameters::" \
+  "TestPacketEnabled"  // Gets/Sets whether the driver will validate the image
+                       // streaming settings using test packets prior to an
+                       // acquisition
+#define IMAQdxAttributeTestPacketTimeout                            \
+  "AcquisitionAttributes::AdvancedEthernet::TestPacketParameters::" \
+  "TestPacketTimeout"  // Gets/Sets the timeout for validating test packet
+                       // reception (if enabled)
+#define IMAQdxAttributeMaxTestPacketRetries                         \
+  "AcquisitionAttributes::AdvancedEthernet::TestPacketParameters::" \
+  "MaxTestPacketRetries"  // Gets/Sets the number of retries for validating test
+                          // packet reception (if enabled)
+#define IMAQdxAttributeChunkDataDecodingEnabled \
+  "AcquisitionAttributes::ChunkDataDecoding::ChunkDataDecodingEnabled"  // Gets/Sets
+                                                                        // whether
+                                                                        // the
+                                                                        // driver
+                                                                        // will
+                                                                        // decode
+                                                                        // any
+                                                                        // chunk
+                                                                        // data
+                                                                        // in
+                                                                        // the
+                                                                        // image
+                                                                        // stream
+#define IMAQdxAttributeChunkDataDecodingMaxElementSize \
+  "AcquisitionAttributes::ChunkDataDecoding::MaximumChunkCopySize"  // Gets/Sets
+                                                                    // the
+                                                                    // maximum
+                                                                    // size of
+                                                                    // any
+                                                                    // single
+                                                                    // chunk
+                                                                    // data
+                                                                    // element
+                                                                    // that will
+                                                                    // be made
+                                                                    // available
+#define IMAQdxAttributeLostPacketMode \
+  "AcquisitionAttributes::AdvancedEthernet::LostPacketMode"  // Gets/sets the
+                                                             // behavior when
+                                                             // the user
+                                                             // extracts a
+                                                             // buffer that has
+                                                             // missing packets.
+#define IMAQdxAttributeMemoryWindowSize                         \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "MemoryWindowSize"  // Gets/sets the size of the memory window of the camera
+                      // in kilobytes. Should match the camera's internal buffer
+                      // size.
+#define IMAQdxAttributeResendsEnabled \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::ResendsEnabled"  // Gets/sets if resends will be issued for missing packets.
+#define IMAQdxAttributeResendThresholdPercentage                \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "ResendThresholdPercentage"  // Gets/sets the threshold of the packet
+                               // processing window that will trigger packets to
+                               // be resent.
+#define IMAQdxAttributeResendBatchingPercentage                 \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "ResendBatchingPercentage"  // Gets/sets the percent of the packet resend
+                              // threshold that will be issued as one group past
+                              // the initial threshold sent in a single request.
+#define IMAQdxAttributeMaxResendsPerPacket                      \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "MaxResendsPerPacket"  // Gets/sets the maximum number of resend requests that
+                         // will be issued for a missing packet.
+#define IMAQdxAttributeResendResponseTimeout                    \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "ResendResponseTimeout"  // Gets/sets the time to wait for a resend request to
+                           // be satisfied before sending another.
+#define IMAQdxAttributeNewPacketTimeout                         \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "NewPacketTimeout"  // Gets/sets the time to wait for new packets to arrive in
+                      // a partially completed image before assuming the rest of
+                      // the image was lost.
+#define IMAQdxAttributeMissingPacketTimeout                     \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "MissingPacketTimeout"  // Gets/sets the time to wait for a missing packet
+                          // before issuing a resend.
+#define IMAQdxAttributeResendTimerResolution                    \
+  "AcquisitionAttributes::AdvancedEthernet::ResendParameters::" \
+  "ResendTimerResolution"  // Gets/sets the resolution of the packet processing
+                           // system that is used for all packet-related
+                           // timeouts.
+
+//==============================================================================
+//  Functions
+//==============================================================================
+IMAQdxError NI_FUNC IMAQdxSnap(IMAQdxSession id, Image* image);
+IMAQdxError NI_FUNC IMAQdxConfigureGrab(IMAQdxSession id);
+IMAQdxError NI_FUNC IMAQdxGrab(IMAQdxSession id, Image* image,
+                               bool32 waitForNextBuffer,
+                               uInt32* actualBufferNumber);
+IMAQdxError NI_FUNC
+IMAQdxSequence(IMAQdxSession id, Image* images[], uInt32 count);
+IMAQdxError NI_FUNC
+IMAQdxDiscoverEthernetCameras(const char* address, uInt32 timeout);
+IMAQdxError NI_FUNC
+IMAQdxEnumerateCameras(IMAQdxCameraInformation cameraInformationArray[],
+                       uInt32* count, bool32 connectedOnly);
+IMAQdxError NI_FUNC IMAQdxResetCamera(const char* name, bool32 resetAll);
+IMAQdxError NI_FUNC IMAQdxOpenCamera(const char* name,
+                                     IMAQdxCameraControlMode mode,
+                                     IMAQdxSession* id);
+IMAQdxError NI_FUNC IMAQdxCloseCamera(IMAQdxSession id);
+IMAQdxError NI_FUNC IMAQdxConfigureAcquisition(IMAQdxSession id,
+                                               bool32 continuous,
+                                               uInt32 bufferCount);
+IMAQdxError NI_FUNC IMAQdxStartAcquisition(IMAQdxSession id);
+IMAQdxError NI_FUNC
+IMAQdxGetImage(IMAQdxSession id, Image* image, IMAQdxBufferNumberMode mode,
+               uInt32 desiredBufferNumber, uInt32* actualBufferNumber);
+IMAQdxError NI_FUNC
+IMAQdxGetImageData(IMAQdxSession id, void* buffer, uInt32 bufferSize,
+                   IMAQdxBufferNumberMode mode, uInt32 desiredBufferNumber,
+                   uInt32* actualBufferNumber);
+IMAQdxError NI_FUNC IMAQdxStopAcquisition(IMAQdxSession id);
+IMAQdxError NI_FUNC IMAQdxUnconfigureAcquisition(IMAQdxSession id);
+IMAQdxError NI_FUNC
+IMAQdxEnumerateVideoModes(IMAQdxSession id, IMAQdxVideoMode videoModeArray[],
+                          uInt32* count, uInt32* currentMode);
+IMAQdxError NI_FUNC IMAQdxEnumerateAttributes(
+    IMAQdxSession id, IMAQdxAttributeInformation attributeInformationArray[],
+    uInt32* count, const char* root);
+IMAQdxError NI_FUNC IMAQdxGetAttribute(IMAQdxSession id, const char* name,
+                                       IMAQdxValueType type, void* value);
+IMAQdxError NI_FUNCC IMAQdxSetAttribute(IMAQdxSession id, const char* name,
+                                        IMAQdxValueType type, ...);
+IMAQdxError NI_FUNC
+IMAQdxGetAttributeMinimum(IMAQdxSession id, const char* name,
+                          IMAQdxValueType type, void* value);
+IMAQdxError NI_FUNC
+IMAQdxGetAttributeMaximum(IMAQdxSession id, const char* name,
+                          IMAQdxValueType type, void* value);
+IMAQdxError NI_FUNC
+IMAQdxGetAttributeIncrement(IMAQdxSession id, const char* name,
+                            IMAQdxValueType type, void* value);
+IMAQdxError NI_FUNC IMAQdxGetAttributeType(IMAQdxSession id, const char* name,
+                                           IMAQdxAttributeType* type);
+IMAQdxError NI_FUNC
+IMAQdxIsAttributeReadable(IMAQdxSession id, const char* name, bool32* readable);
+IMAQdxError NI_FUNC
+IMAQdxIsAttributeWritable(IMAQdxSession id, const char* name, bool32* writable);
+IMAQdxError NI_FUNC
+IMAQdxEnumerateAttributeValues(IMAQdxSession id, const char* name,
+                               IMAQdxEnumItem list[], uInt32* size);
+IMAQdxError NI_FUNC IMAQdxGetAttributeTooltip(IMAQdxSession id,
+                                              const char* name, char* tooltip,
+                                              uInt32 length);
+IMAQdxError NI_FUNC IMAQdxGetAttributeUnits(IMAQdxSession id, const char* name,
+                                            char* units, uInt32 length);
+IMAQdxError NI_FUNC
+IMAQdxRegisterFrameDoneEvent(IMAQdxSession id, uInt32 bufferInterval,
+                             FrameDoneEventCallbackPtr callbackFunction,
+                             void* callbackData);
+IMAQdxError NI_FUNC IMAQdxRegisterPnpEvent(IMAQdxSession id,
+                                           IMAQdxPnpEvent event,
+                                           PnpEventCallbackPtr callbackFunction,
+                                           void* callbackData);
+IMAQdxError NI_FUNC
+IMAQdxWriteRegister(IMAQdxSession id, uInt32 offset, uInt32 value);
+IMAQdxError NI_FUNC
+IMAQdxReadRegister(IMAQdxSession id, uInt32 offset, uInt32* value);
+IMAQdxError NI_FUNC IMAQdxWriteMemory(IMAQdxSession id, uInt32 offset,
+                                      const char* values, uInt32 count);
+IMAQdxError NI_FUNC
+IMAQdxReadMemory(IMAQdxSession id, uInt32 offset, char* values, uInt32 count);
+IMAQdxError NI_FUNC
+IMAQdxGetErrorString(IMAQdxError error, char* message, uInt32 messageLength);
+IMAQdxError NI_FUNC
+IMAQdxWriteAttributes(IMAQdxSession id, const char* filename);
+IMAQdxError NI_FUNC
+IMAQdxReadAttributes(IMAQdxSession id, const char* filename);
+IMAQdxError NI_FUNC
+IMAQdxResetEthernetCameraAddress(const char* name, const char* address,
+                                 const char* subnet, const char* gateway,
+                                 uInt32 timeout);
+IMAQdxError NI_FUNC IMAQdxEnumerateAttributes2(
+    IMAQdxSession id, IMAQdxAttributeInformation attributeInformationArray[],
+    uInt32* count, const char* root, IMAQdxAttributeVisibility visibility);
+IMAQdxError NI_FUNC
+IMAQdxGetAttributeVisibility(IMAQdxSession id, const char* name,
+                             IMAQdxAttributeVisibility* visibility);
+IMAQdxError NI_FUNC
+IMAQdxGetAttributeDescription(IMAQdxSession id, const char* name,
+                              char* description, uInt32 length);
+IMAQdxError NI_FUNC
+IMAQdxGetAttributeDisplayName(IMAQdxSession id, const char* name,
+                              char* displayName, uInt32 length);
+IMAQdxError NI_FUNC IMAQdxDispose(void* buffer);
+IMAQdxError NI_FUNC IMAQdxRegisterAttributeUpdatedEvent(
+    IMAQdxSession id, const char* name,
+    AttributeUpdatedEventCallbackPtr callbackFunction, void* callbackData);
+IMAQdxError NI_FUNC IMAQdxEnumerateAttributes3(
+    IMAQdxSession id, IMAQdxAttributeInformation attributeInformationArray[],
+    uInt32* count, const char* root, IMAQdxAttributeVisibility visibility);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif  // ___niimaqdx_h___
diff --git a/wpilibc/Athena/include/NetworkCommunication/AICalibration.h b/wpilibc/Athena/include/NetworkCommunication/AICalibration.h
new file mode 100644
index 0000000..c4a8f75
--- /dev/null
+++ b/wpilibc/Athena/include/NetworkCommunication/AICalibration.h
@@ -0,0 +1,20 @@
+
+#ifndef __AICalibration_h__
+#define __AICalibration_h__
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+uint32_t FRC_NetworkCommunication_nAICalibration_getLSBWeight(
+    const uint32_t aiSystemIndex, const uint32_t channel, int32_t *status);
+int32_t FRC_NetworkCommunication_nAICalibration_getOffset(
+    const uint32_t aiSystemIndex, const uint32_t channel, int32_t *status);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif  // __AICalibration_h__
diff --git a/wpilibc/Athena/include/NetworkCommunication/CANInterfacePlugin.h b/wpilibc/Athena/include/NetworkCommunication/CANInterfacePlugin.h
new file mode 100644
index 0000000..1875980
--- /dev/null
+++ b/wpilibc/Athena/include/NetworkCommunication/CANInterfacePlugin.h
@@ -0,0 +1,109 @@
+// CANInterfacePlugin.h
+//
+//  Defines the API for building a CAN Interface Plugin to support
+//    PWM-cable-free CAN motor control on FRC robots.  This allows you
+//    to connect any CAN interface to the secure Jaguar CAN driver.
+//
+
+#ifndef __CANInterfacePlugin_h__
+#define __CANInterfacePlugin_h__
+
+#include <stdint.h>
+
+#define CAN_IS_FRAME_REMOTE 0x80000000
+#define CAN_IS_FRAME_11BIT 0x40000000
+#define CAN_29BIT_MESSAGE_ID_MASK 0x1FFFFFFF
+#define CAN_11BIT_MESSAGE_ID_MASK 0x000007FF
+
+class CANInterfacePlugin {
+ public:
+  CANInterfacePlugin() {}
+  virtual ~CANInterfacePlugin() {}
+
+  /**
+   * This entry-point of the CANInterfacePlugin is passed a message that the
+   * driver needs to send to
+   * a device on the CAN bus.
+   *
+   * This function may be called from multiple contexts and must therefore be
+   * reentrant.
+   *
+   * @param messageID The 29-bit CAN message ID in the lsbs.  The msb can
+   * indicate a remote frame.
+   * @param data A pointer to a buffer containing between 0 and 8 bytes to send
+   * with the message.  May be nullptr if dataSize is 0.
+   * @param dataSize The number of bytes to send with the message.
+   * @return Return any error code.  On success return 0.
+   */
+  virtual int32_t sendMessage(uint32_t messageID, const uint8_t *data,
+                              uint8_t dataSize) = 0;
+
+  /**
+   * This entry-point of the CANInterfacePlugin is passed buffers which should
+   * be populated with
+   * any received messages from devices on the CAN bus.
+   *
+   * This function is always called by a single task in the Jaguar driver, so it
+   * need not be reentrant.
+   *
+   * This function is expected to block for some period of time waiting for a
+   * message from the CAN bus.
+   * It may timeout periodically (returning non-zero to indicate no message was
+   * populated) to allow for
+   * shutdown and unloading of the plugin.
+   *
+   * @param messageID A reference to be populated with a received 29-bit CAN
+   * message ID in the lsbs.
+   * @param data A pointer to a buffer of 8 bytes to be populated with data
+   * received with the message.
+   * @param dataSize A reference to be populated with the size of the data
+   * received (0 - 8 bytes).
+   * @return This should return 0 if a message was populated, non-0 if no
+   * message was not populated.
+   */
+  virtual int32_t receiveMessage(uint32_t &messageID, uint8_t *data,
+                                 uint8_t &dataSize) = 0;
+
+#if defined(__linux)
+  /**
+   * This entry-point of the CANInterfacePlugin returns status of the CAN bus.
+   *
+   * This function may be called from multiple contexts and must therefore be
+   * reentrant.
+   *
+   * This function will return detailed hardware status if available for
+   * diagnostics of the CAN interface.
+   *
+   * @param busOffCount The number of times that sendMessage failed with a
+   * busOff error indicating that messages
+   *  are not successfully transmitted on the bus.
+   * @param txFullCount The number of times that sendMessage failed with a
+   * txFifoFull error indicating that messages
+   *  are not successfully received by any CAN device.
+   * @param receiveErrorCount The count of receive errors as reported by the CAN
+   * driver.
+   * @param transmitErrorCount The count of transmit errors as reported by the
+   * CAN driver.
+   * @return This should return 0 if all status was retrieved successfully or an
+   * error code if not.
+   */
+  virtual int32_t getStatus(uint32_t &busOffCount, uint32_t &txFullCount,
+                            uint32_t &receiveErrorCount,
+                            uint32_t &transmitErrorCount) {
+    return 0;
+  }
+#endif
+};
+
+/**
+ * This function allows you to register a CANInterfacePlugin to provide access a
+ * CAN bus.
+ *
+ * @param interface A pointer to an object that inherits from CANInterfacePlugin
+ * and implements
+ * the pure virtual interface.  If nullptr, unregister the current plugin.
+ */
+void FRC_NetworkCommunication_CANSessionMux_registerInterface(
+    CANInterfacePlugin *interface);
+
+#endif  // __CANInterfacePlugin_h__
diff --git a/wpilibc/Athena/include/NetworkCommunication/CANSessionMux.h b/wpilibc/Athena/include/NetworkCommunication/CANSessionMux.h
new file mode 100644
index 0000000..9cd9a3f
--- /dev/null
+++ b/wpilibc/Athena/include/NetworkCommunication/CANSessionMux.h
@@ -0,0 +1,81 @@
+// CANSessionMux.h
+//
+//  Defines the API for building a CAN Interface Plugin to support
+//    PWM-cable-free CAN motor control on FRC robots.  This allows you
+//    to connect any CAN interface to the secure Jaguar CAN driver.
+//
+
+#ifndef __CANSessionMux_h__
+#define __CANSessionMux_h__
+
+#include <stdint.h>
+
+#define CAN_SEND_PERIOD_NO_REPEAT 0
+#define CAN_SEND_PERIOD_STOP_REPEATING -1
+
+/* Flags in the upper bits of the messageID */
+#define CAN_IS_FRAME_REMOTE 0x80000000
+#define CAN_IS_FRAME_11BIT 0x40000000
+
+#define ERR_CANSessionMux_InvalidBuffer -44086
+#define ERR_CANSessionMux_MessageNotFound -44087
+#define WARN_CANSessionMux_NoToken 44087
+#define ERR_CANSessionMux_NotAllowed -44088
+#define ERR_CANSessionMux_NotInitialized -44089
+#define ERR_CANSessionMux_SessionOverrun 44050
+
+struct tCANStreamMessage {
+  uint32_t messageID;
+  uint32_t timeStamp;
+  uint8_t data[8];
+  uint8_t dataSize;
+};
+
+namespace nCANSessionMux {
+void sendMessage_wrapper(uint32_t messageID, const uint8_t *data,
+                         uint8_t dataSize, int32_t periodMs, int32_t *status);
+void receiveMessage_wrapper(uint32_t *messageID, uint32_t messageIDMask,
+                            uint8_t *data, uint8_t *dataSize,
+                            uint32_t *timeStamp, int32_t *status);
+void openStreamSession(uint32_t *sessionHandle, uint32_t messageID,
+                       uint32_t messageIDMask, uint32_t maxMessages,
+                       int32_t *status);
+void closeStreamSession(uint32_t sessionHandle);
+void readStreamSession(uint32_t sessionHandle,
+                       struct tCANStreamMessage *messages,
+                       uint32_t messagesToRead, uint32_t *messagesRead,
+                       int32_t *status);
+void getCANStatus(float *percentBusUtilization, uint32_t *busOffCount,
+                  uint32_t *txFullCount, uint32_t *receiveErrorCount,
+                  uint32_t *transmitErrorCount, int32_t *status);
+}
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void FRC_NetworkCommunication_CANSessionMux_sendMessage(uint32_t messageID,
+                                                        const uint8_t *data,
+                                                        uint8_t dataSize,
+                                                        int32_t periodMs,
+                                                        int32_t *status);
+void FRC_NetworkCommunication_CANSessionMux_receiveMessage(
+    uint32_t *messageID, uint32_t messageIDMask, uint8_t *data,
+    uint8_t *dataSize, uint32_t *timeStamp, int32_t *status);
+void FRC_NetworkCommunication_CANSessionMux_openStreamSession(
+    uint32_t *sessionHandle, uint32_t messageID, uint32_t messageIDMask,
+    uint32_t maxMessages, int32_t *status);
+void FRC_NetworkCommunication_CANSessionMux_closeStreamSession(
+    uint32_t sessionHandle);
+void FRC_NetworkCommunication_CANSessionMux_readStreamSession(
+    uint32_t sessionHandle, struct tCANStreamMessage *messages,
+    uint32_t messagesToRead, uint32_t *messagesRead, int32_t *status);
+void FRC_NetworkCommunication_CANSessionMux_getCANStatus(
+    float *percentBusUtilization, uint32_t *busOffCount, uint32_t *txFullCount,
+    uint32_t *receiveErrorCount, uint32_t *transmitErrorCount, int32_t *status);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif  // __CANSessionMux_h__
diff --git a/wpilibc/Athena/include/NetworkCommunication/FRCComm.h b/wpilibc/Athena/include/NetworkCommunication/FRCComm.h
new file mode 100644
index 0000000..588c8ca
--- /dev/null
+++ b/wpilibc/Athena/include/NetworkCommunication/FRCComm.h
@@ -0,0 +1,130 @@
+/*************************************************************
+ * 					NOTICE
+ *
+ * 	These are the only externally exposed functions to the
+ *   NetworkCommunication library
+ *
+ * This is an implementation of FRC Spec for Comm Protocol
+ * Revision 4.5, June 30, 2008
+ *
+ * Copyright (c) National Instruments 2008.  All Rights Reserved.
+ *
+ *************************************************************/
+
+#ifndef __FRC_COMM_H__
+#define __FRC_COMM_H__
+
+#ifdef SIMULATION
+#include <vxWorks_compat.h>
+#ifdef USE_THRIFT
+#define EXPORT_FUNC
+#else
+#define EXPORT_FUNC __declspec(dllexport) __cdecl
+#endif
+#else
+#include <stdint.h>
+#include <pthread.h>
+#define EXPORT_FUNC
+#endif
+
+#define ERR_FRCSystem_NetCommNotResponding -44049
+#define ERR_FRCSystem_NoDSConnection -44018
+
+enum AllianceStationID_t {
+  kAllianceStationID_red1,
+  kAllianceStationID_red2,
+  kAllianceStationID_red3,
+  kAllianceStationID_blue1,
+  kAllianceStationID_blue2,
+  kAllianceStationID_blue3,
+};
+
+enum MatchType_t {
+  kMatchType_none,
+  kMatchType_practice,
+  kMatchType_qualification,
+  kMatchType_elimination,
+};
+
+struct ControlWord_t {
+  uint32_t enabled : 1;
+  uint32_t autonomous : 1;
+  uint32_t test : 1;
+  uint32_t eStop : 1;
+  uint32_t fmsAttached : 1;
+  uint32_t dsAttached : 1;
+  uint32_t control_reserved : 26;
+};
+
+struct JoystickAxes_t {
+  uint16_t count;
+  int16_t axes[1];
+};
+
+struct JoystickPOV_t {
+  uint16_t count;
+  int16_t povs[1];
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+int EXPORT_FUNC FRC_NetworkCommunication_Reserve(void *instance);
+#ifndef SIMULATION
+void EXPORT_FUNC
+getFPGAHardwareVersion(uint16_t *fpgaVersion, uint32_t *fpgaRevision);
+#endif
+int EXPORT_FUNC setStatusData(float battery, uint8_t dsDigitalOut,
+                              uint8_t updateNumber, const char *userDataHigh,
+                              int userDataHighLength, const char *userDataLow,
+                              int userDataLowLength, int wait_ms);
+int EXPORT_FUNC setErrorData(const char *errors, int errorsLength, int wait_ms);
+
+#ifdef SIMULATION
+void EXPORT_FUNC setNewDataSem(HANDLE);
+#else
+void EXPORT_FUNC setNewDataSem(pthread_cond_t *);
+#endif
+
+// this uint32_t is really a LVRefNum
+int EXPORT_FUNC setNewDataOccurRef(uint32_t refnum);
+
+int EXPORT_FUNC
+FRC_NetworkCommunication_getControlWord(struct ControlWord_t *controlWord);
+int EXPORT_FUNC FRC_NetworkCommunication_getAllianceStation(
+    enum AllianceStationID_t *allianceStation);
+int EXPORT_FUNC FRC_NetworkCommunication_getMatchTime(float *matchTime);
+int EXPORT_FUNC
+FRC_NetworkCommunication_getJoystickAxes(uint8_t joystickNum,
+                                         struct JoystickAxes_t *axes,
+                                         uint8_t maxAxes);
+int EXPORT_FUNC FRC_NetworkCommunication_getJoystickButtons(uint8_t joystickNum,
+                                                            uint32_t *buttons,
+                                                            uint8_t *count);
+int EXPORT_FUNC
+FRC_NetworkCommunication_getJoystickPOVs(uint8_t joystickNum,
+                                         struct JoystickPOV_t *povs,
+                                         uint8_t maxPOVs);
+int EXPORT_FUNC
+FRC_NetworkCommunication_setJoystickOutputs(uint8_t joystickNum,
+                                            uint32_t hidOutputs,
+                                            uint16_t leftRumble,
+                                            uint16_t rightRumble);
+int EXPORT_FUNC
+FRC_NetworkCommunication_getJoystickDesc(uint8_t joystickNum, uint8_t *isXBox,
+                                         uint8_t *type, char *name,
+                                         uint8_t *axisCount, uint8_t *axisTypes,
+                                         uint8_t *buttonCount,
+                                         uint8_t *povCount);
+
+void EXPORT_FUNC FRC_NetworkCommunication_getVersionString(char *version);
+int EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramStarting(void);
+void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramDisabled(void);
+void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramAutonomous(void);
+void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramTeleop(void);
+void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramTest(void);
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/wpilibc/Athena/include/NetworkCommunication/LoadOut.h b/wpilibc/Athena/include/NetworkCommunication/LoadOut.h
new file mode 100644
index 0000000..5a11749
--- /dev/null
+++ b/wpilibc/Athena/include/NetworkCommunication/LoadOut.h
@@ -0,0 +1,57 @@
+
+#ifndef __LoadOut_h__
+#define __LoadOut_h__
+
+#ifdef SIMULATION
+#include <vxWorks_compat.h>
+#define EXPORT_FUNC __declspec(dllexport) __cdecl
+#else
+#include <stdint.h>
+#define EXPORT_FUNC
+#endif
+
+#define kMaxModuleNumber 2
+namespace nLoadOut {
+#if defined(SIMULATION)
+typedef enum {
+  kModuleType_Unknown = 0x00,
+  kModuleType_Analog = 0x01,
+  kModuleType_Digital = 0x02,
+  kModuleType_Solenoid = 0x03,
+} tModuleType;
+bool EXPORT_FUNC
+getModulePresence(tModuleType moduleType, uint8_t moduleNumber);
+#endif
+typedef enum {
+  kTargetClass_Unknown = 0x00,
+  kTargetClass_FRC1 = 0x10,
+  kTargetClass_FRC2 = 0x20,
+  kTargetClass_FRC3 = 0x30,
+  kTargetClass_RoboRIO = 0x40,
+#if defined(SIMULATION)
+  kTargetClass_FRC2_Analog = kTargetClass_FRC2 | kModuleType_Analog,
+  kTargetClass_FRC2_Digital = kTargetClass_FRC2 | kModuleType_Digital,
+  kTargetClass_FRC2_Solenoid = kTargetClass_FRC2 | kModuleType_Solenoid,
+#endif
+  kTargetClass_FamilyMask = 0xF0,
+  kTargetClass_ModuleMask = 0x0F,
+} tTargetClass;
+tTargetClass EXPORT_FUNC getTargetClass();
+}
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#if defined(SIMULATION)
+uint32_t EXPORT_FUNC
+FRC_NetworkCommunication_nLoadOut_getModulePresence(uint32_t moduleType,
+                                                    uint8_t moduleNumber);
+#endif
+uint32_t EXPORT_FUNC FRC_NetworkCommunication_nLoadOut_getTargetClass();
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif  // __LoadOut_h__
diff --git a/wpilibc/Athena/include/NetworkCommunication/symModuleLink.h b/wpilibc/Athena/include/NetworkCommunication/symModuleLink.h
new file mode 100644
index 0000000..621cbb6
--- /dev/null
+++ b/wpilibc/Athena/include/NetworkCommunication/symModuleLink.h
@@ -0,0 +1,19 @@
+#ifndef __SYM_MODULE_LINK_H__
+#define __SYM_MODULE_LINK_H__
+
+#include "HAL/HAL.hpp"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+extern STATUS moduleNameFindBySymbolName(
+    const char* symbol, /* symbol name to look for */
+    char* module        /* where to return module name */
+    );
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/wpilibc/Athena/include/PWM.h b/wpilibc/Athena/include/PWM.h
new file mode 100644
index 0000000..b7120c0
--- /dev/null
+++ b/wpilibc/Athena/include/PWM.h
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SensorBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITableListener.h"
+
+#include <memory>
+
+/**
+ * Class implements the PWM generation in the FPGA.
+ *
+ * The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They
+ * are mapped
+ * to the hardware dependent values, in this case 0-2000 for the FPGA.
+ * Changes are immediately sent to the FPGA, and the update occurs at the next
+ * FPGA cycle. There is no delay.
+ *
+ * As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as
+ * follows:
+ *   - 2000 = maximum pulse width
+ *   - 1999 to 1001 = linear scaling from "full forward" to "center"
+ *   - 1000 = center value
+ *   - 999 to 2 = linear scaling from "center" to "full reverse"
+ *   - 1 = minimum pulse width (currently .5ms)
+ *   - 0 = disabled (i.e. PWM output is held low)
+ */
+class PWM : public SensorBase,
+            public ITableListener,
+            public LiveWindowSendable {
+ public:
+  enum PeriodMultiplier {
+    kPeriodMultiplier_1X = 1,
+    kPeriodMultiplier_2X = 2,
+    kPeriodMultiplier_4X = 4
+  };
+
+  explicit PWM(uint32_t channel);
+  virtual ~PWM();
+  virtual void SetRaw(unsigned short value);
+  virtual unsigned short GetRaw() const;
+  void SetPeriodMultiplier(PeriodMultiplier mult);
+  void SetZeroLatch();
+  void EnableDeadbandElimination(bool eliminateDeadband);
+  void SetBounds(int32_t max, int32_t deadbandMax, int32_t center,
+                 int32_t deadbandMin, int32_t min);
+  void SetBounds(double max, double deadbandMax, double center,
+                 double deadbandMin, double min);
+  uint32_t GetChannel() const { return m_channel; }
+
+ protected:
+  /**
+   * kDefaultPwmPeriod is in ms
+   *
+   * - 20ms periods (50 Hz) are the "safest" setting in that this works for all
+   * devices
+   * - 20ms periods seem to be desirable for Vex Motors
+   * - 20ms periods are the specified period for HS-322HD servos, but work
+   * reliably down
+   *      to 10.0 ms; starting at about 8.5ms, the servo sometimes hums and get
+   *hot;
+   *      by 5.0ms the hum is nearly continuous
+   * - 10ms periods work well for Victor 884
+   * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed
+   * controllers.
+   *      Due to the shipping firmware on the Jaguar, we can't run the update
+   * period less
+   *      than 5.05 ms.
+   *
+   * kDefaultPwmPeriod is the 1x period (5.05 ms).  In hardware, the period
+   * scaling is implemented as an
+   * output squelch to get longer periods for old devices.
+   */
+  static constexpr float kDefaultPwmPeriod = 5.05;
+  /**
+   * kDefaultPwmCenter is the PWM range center in ms
+   */
+  static constexpr float kDefaultPwmCenter = 1.5;
+  /**
+   * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
+   */
+  static const int32_t kDefaultPwmStepsDown = 1000;
+  static const int32_t kPwmDisabled = 0;
+
+  virtual void SetPosition(float pos);
+  virtual float GetPosition() const;
+  virtual void SetSpeed(float speed);
+  virtual float GetSpeed() const;
+
+  bool m_eliminateDeadband;
+  int32_t m_maxPwm;
+  int32_t m_deadbandMaxPwm;
+  int32_t m_centerPwm;
+  int32_t m_deadbandMinPwm;
+  int32_t m_minPwm;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  uint32_t m_channel;
+  int32_t GetMaxPositivePwm() const { return m_maxPwm; }
+  int32_t GetMinPositivePwm() const {
+    return m_eliminateDeadband ? m_deadbandMaxPwm : m_centerPwm + 1;
+  }
+  int32_t GetCenterPwm() const { return m_centerPwm; }
+  int32_t GetMaxNegativePwm() const {
+    return m_eliminateDeadband ? m_deadbandMinPwm : m_centerPwm - 1;
+  }
+  int32_t GetMinNegativePwm() const { return m_minPwm; }
+  int32_t GetPositiveScaleFactor() const {
+    return GetMaxPositivePwm() - GetMinPositivePwm();
+  }  ///< The scale for positive speeds.
+  int32_t GetNegativeScaleFactor() const {
+    return GetMaxNegativePwm() - GetMinNegativePwm();
+  }  ///< The scale for negative speeds.
+  int32_t GetFullRangeScaleFactor() const {
+    return GetMaxPositivePwm() - GetMinNegativePwm();
+  }  ///< The scale for positions.
+};
diff --git a/wpilibc/Athena/include/PowerDistributionPanel.h b/wpilibc/Athena/include/PowerDistributionPanel.h
new file mode 100644
index 0000000..9a1bd7c
--- /dev/null
+++ b/wpilibc/Athena/include/PowerDistributionPanel.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+#ifndef __WPILIB_POWER_DISTRIBUTION_PANEL_H__
+#define __WPILIB_POWER_DISTRIBUTION_PANEL_H__
+
+#include "SensorBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+
+#include <memory>
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the
+ * CAN PDP.
+ * @author Thomas Clark
+ */
+class PowerDistributionPanel : public SensorBase, public LiveWindowSendable {
+ public:
+  PowerDistributionPanel();
+  PowerDistributionPanel(uint8_t module);
+
+  double GetVoltage() const;
+  double GetTemperature() const;
+  double GetCurrent(uint8_t channel) const;
+  double GetTotalCurrent() const;
+  double GetTotalPower() const;
+  double GetTotalEnergy() const;
+  void ResetTotalEnergy();
+  void ClearStickyFaults();
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+  uint8_t m_module;
+};
+
+#endif /* __WPILIB_POWER_DISTRIBUTION_PANEL_H__ */
diff --git a/wpilibc/Athena/include/Preferences.h b/wpilibc/Athena/include/Preferences.h
new file mode 100644
index 0000000..a2c3bc4
--- /dev/null
+++ b/wpilibc/Athena/include/Preferences.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. 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 "ErrorBase.h"
+#include "Task.h"
+#include <map>
+#include <string>
+#include <vector>
+#include "HAL/cpp/Semaphore.hpp"
+#include "tables/ITableListener.h"
+#include "networktables/NetworkTable.h"
+
+/**
+ * The preferences class provides a relatively simple way to save important
+ * values to
+ * the RoboRIO to access the next time the RoboRIO is booted.
+ *
+ * <p>This class loads and saves from a file
+ * inside the RoboRIO.  The user can not access the file directly, but may
+ * modify values at specific
+ * fields which will then be automatically periodically saved to the file
+ * by the NetworkTable server.</p>
+ *
+ * <p>This class is thread safe.</p>
+ *
+ * <p>This will also interact with {@link NetworkTable} by creating a table
+ * called "Preferences" with all the key-value pairs.</p>
+ */
+class Preferences : public ErrorBase {
+ public:
+  static Preferences *GetInstance();
+
+  std::vector<std::string> GetKeys();
+  std::string GetString(llvm::StringRef key, llvm::StringRef defaultValue = "");
+  int GetInt(llvm::StringRef key, int defaultValue = 0);
+  double GetDouble(llvm::StringRef key, double defaultValue = 0.0);
+  float GetFloat(llvm::StringRef key, float defaultValue = 0.0);
+  bool GetBoolean(llvm::StringRef key, bool defaultValue = false);
+  int64_t GetLong(llvm::StringRef key, int64_t defaultValue = 0);
+  void PutString(llvm::StringRef key, llvm::StringRef value);
+  void PutInt(llvm::StringRef key, int value);
+  void PutDouble(llvm::StringRef key, double value);
+  void PutFloat(llvm::StringRef key, float value);
+  void PutBoolean(llvm::StringRef key, bool value);
+  void PutLong(llvm::StringRef key, int64_t value);
+  DEPRECATED(
+      "Saving is now automatically performed by the NetworkTables server.")
+  void Save();
+  bool ContainsKey(llvm::StringRef key);
+  void Remove(llvm::StringRef key);
+
+ protected:
+  Preferences();
+  virtual ~Preferences() = default;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+  class Listener : public ITableListener {
+   public:
+    void ValueChanged(ITable* source, llvm::StringRef key,
+                      std::shared_ptr<nt::Value> value, bool isNew) override;
+    void ValueChangedEx(ITable* source, llvm::StringRef key,
+                        std::shared_ptr<nt::Value> value,
+                        unsigned int flags) override;
+  };
+  Listener m_listener;
+};
diff --git a/wpilibc/Athena/include/Relay.h b/wpilibc/Athena/include/Relay.h
new file mode 100644
index 0000000..f582221
--- /dev/null
+++ b/wpilibc/Athena/include/Relay.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "MotorSafety.h"
+#include "SensorBase.h"
+#include "tables/ITableListener.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITable.h"
+
+#include <memory>
+
+class MotorSafetyHelper;
+
+/**
+ * Class for Spike style relay outputs.
+ * Relays are intended to be connected to spikes or similar relays. The relay
+ * channels controls
+ * a pair of pins that are either both off, one on, the other on, or both on.
+ * This translates into
+ * two spike outputs at 0v, one at 12v and one at 0v, one at 0v and the other at
+ * 12v, or two
+ * spike outputs at 12V. This allows off, full forward, or full reverse control
+ * of motors without
+ * variable speed.  It also allows the two channels (forward and reverse) to be
+ * used independently
+ * for something that does not care about voltage polatiry (like a solenoid).
+ */
+class Relay : public MotorSafety,
+              public SensorBase,
+              public ITableListener,
+              public LiveWindowSendable {
+ public:
+  enum Value { kOff, kOn, kForward, kReverse };
+  enum Direction { kBothDirections, kForwardOnly, kReverseOnly };
+
+  Relay(uint32_t channel, Direction direction = kBothDirections);
+  virtual ~Relay();
+
+  void Set(Value value);
+  Value Get() const;
+  uint32_t GetChannel() const;
+
+  void SetExpiration(float timeout) override;
+  float GetExpiration() const override;
+  bool IsAlive() const override;
+  void StopMotor() override;
+  bool IsSafetyEnabled() const override;
+  void SetSafetyEnabled(bool enabled) override;
+  void GetDescription(std::ostringstream& desc) const override;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  uint32_t m_channel;
+  Direction m_direction;
+
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+};
diff --git a/wpilibc/Athena/include/RobotBase.h b/wpilibc/Athena/include/RobotBase.h
new file mode 100644
index 0000000..2fcd146
--- /dev/null
+++ b/wpilibc/Athena/include/RobotBase.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "Base.h"
+#include "Task.h"
+
+class DriverStation;
+
+#define START_ROBOT_CLASS(_ClassName_)                                       \
+  int main() {                                                               \
+    if (!HALInitialize()) {                                                  \
+      std::cerr << "FATAL ERROR: HAL could not be initialized" << std::endl; \
+      return -1;                                                             \
+    }                                                                        \
+    HALReport(HALUsageReporting::kResourceType_Language,                     \
+              HALUsageReporting::kLanguage_CPlusPlus);                       \
+    _ClassName_ *robot = new _ClassName_();                                  \
+    RobotBase::robotSetup(robot);                                            \
+    return 0;                                                                \
+  }
+
+/**
+ * Implement a Robot Program framework.
+ * The RobotBase class is intended to be subclassed by a user creating a robot
+ * program.
+ * Overridden Autonomous() and OperatorControl() methods are called at the
+ * appropriate time
+ * as the match proceeds. In the current implementation, the Autonomous code
+ * will run to
+ * completion before the OperatorControl code could start. In the future the
+ * Autonomous code
+ * might be spawned as a task, then killed at the end of the Autonomous period.
+ */
+class RobotBase {
+  friend class RobotDeleter;
+
+ public:
+  static RobotBase &getInstance();
+  static void setInstance(RobotBase *robot);
+
+  bool IsEnabled() const;
+  bool IsDisabled() const;
+  bool IsAutonomous() const;
+  bool IsOperatorControl() const;
+  bool IsTest() const;
+  bool IsNewDataAvailable() const;
+  static void startRobotTask(FUNCPTR factory);
+  static void robotTask(FUNCPTR factory, Task *task);
+  virtual void StartCompetition() = 0;
+
+  static void robotSetup(RobotBase *robot);
+
+ protected:
+  RobotBase();
+  virtual ~RobotBase();
+
+  RobotBase(const RobotBase&) = delete;
+  RobotBase& operator=(const RobotBase&) = delete;
+
+  Task *m_task = nullptr;
+  DriverStation &m_ds;
+
+ private:
+  static RobotBase *m_instance;
+};
diff --git a/wpilibc/Athena/include/RobotDrive.h b/wpilibc/Athena/include/RobotDrive.h
new file mode 100644
index 0000000..d91e80d
--- /dev/null
+++ b/wpilibc/Athena/include/RobotDrive.h
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "ErrorBase.h"
+#include <stdlib.h>
+#include <memory>
+#include <sstream>
+#include "HAL/HAL.hpp"
+#include "MotorSafety.h"
+#include "MotorSafetyHelper.h"
+
+class SpeedController;
+class GenericHID;
+
+/**
+ * Utility class for handling Robot drive based on a definition of the motor
+ * configuration.
+ * The robot drive class handles basic driving for a robot. Currently, 2 and 4
+ * motor tank and
+ * mecanum drive trains are supported. In the future other drive types like
+ * swerve might be
+ * implemented. Motor channel numbers are passed supplied on creation of the
+ * class. Those
+ * are used for either the Drive function (intended for hand created drive code,
+ * such as
+ * autonomous) or with the Tank/Arcade functions intended to be used for
+ * Operator Control
+ * driving.
+ */
+class RobotDrive : public MotorSafety, public ErrorBase {
+ public:
+  enum MotorType {
+    kFrontLeftMotor = 0,
+    kFrontRightMotor = 1,
+    kRearLeftMotor = 2,
+    kRearRightMotor = 3
+  };
+
+  RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel);
+  RobotDrive(uint32_t frontLeftMotorChannel, uint32_t rearLeftMotorChannel,
+             uint32_t frontRightMotorChannel, uint32_t rearRightMotorChannel);
+  RobotDrive(SpeedController *leftMotor, SpeedController *rightMotor);
+  RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor);
+  RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+             std::shared_ptr<SpeedController> rightMotor);
+  RobotDrive(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor,
+             SpeedController *frontRightMotor, SpeedController *rearRightMotor);
+  RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
+             SpeedController &frontRightMotor, SpeedController &rearRightMotor);
+  RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+             std::shared_ptr<SpeedController> rearLeftMotor,
+             std::shared_ptr<SpeedController> frontRightMotor,
+             std::shared_ptr<SpeedController> rearRightMotor);
+  virtual ~RobotDrive() = default;
+
+  RobotDrive(const RobotDrive&) = delete;
+  RobotDrive& operator=(const RobotDrive&) = delete;
+
+  void Drive(float outputMagnitude, float curve);
+  void TankDrive(GenericHID *leftStick, GenericHID *rightStick,
+                 bool squaredInputs = true);
+  void TankDrive(GenericHID &leftStick, GenericHID &rightStick,
+                 bool squaredInputs = true);
+  void TankDrive(GenericHID *leftStick, uint32_t leftAxis,
+                 GenericHID *rightStick, uint32_t rightAxis,
+                 bool squaredInputs = true);
+  void TankDrive(GenericHID &leftStick, uint32_t leftAxis,
+                 GenericHID &rightStick, uint32_t rightAxis,
+                 bool squaredInputs = true);
+  void TankDrive(float leftValue, float rightValue, bool squaredInputs = true);
+  void ArcadeDrive(GenericHID *stick, bool squaredInputs = true);
+  void ArcadeDrive(GenericHID &stick, bool squaredInputs = true);
+  void ArcadeDrive(GenericHID *moveStick, uint32_t moveChannel,
+                   GenericHID *rotateStick, uint32_t rotateChannel,
+                   bool squaredInputs = true);
+  void ArcadeDrive(GenericHID &moveStick, uint32_t moveChannel,
+                   GenericHID &rotateStick, uint32_t rotateChannel,
+                   bool squaredInputs = true);
+  void ArcadeDrive(float moveValue, float rotateValue,
+                   bool squaredInputs = true);
+  void MecanumDrive_Cartesian(float x, float y, float rotation,
+                              float gyroAngle = 0.0);
+  void MecanumDrive_Polar(float magnitude, float direction, float rotation);
+  void HolonomicDrive(float magnitude, float direction, float rotation);
+  virtual void SetLeftRightMotorOutputs(float leftOutput, float rightOutput);
+  void SetInvertedMotor(MotorType motor, bool isInverted);
+  void SetSensitivity(float sensitivity);
+  void SetMaxOutput(double maxOutput);
+  void SetCANJaguarSyncGroup(uint8_t syncGroup);
+
+  void SetExpiration(float timeout) override;
+  float GetExpiration() const override;
+  bool IsAlive() const override;
+  void StopMotor() override;
+  bool IsSafetyEnabled() const override;
+  void SetSafetyEnabled(bool enabled) override;
+  void GetDescription(std::ostringstream& desc) const override;
+
+ protected:
+  void InitRobotDrive();
+  float Limit(float num);
+  void Normalize(double *wheelSpeeds);
+  void RotateVector(double &x, double &y, double angle);
+
+  static const int32_t kMaxNumberOfMotors = 4;
+  float m_sensitivity = 0.5;
+  double m_maxOutput = 1.0;
+  std::shared_ptr<SpeedController> m_frontLeftMotor;
+  std::shared_ptr<SpeedController> m_frontRightMotor;
+  std::shared_ptr<SpeedController> m_rearLeftMotor;
+  std::shared_ptr<SpeedController> m_rearRightMotor;
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+  uint8_t m_syncGroup = 0;
+
+ private:
+  int32_t GetNumMotors() {
+    int motors = 0;
+    if (m_frontLeftMotor) motors++;
+    if (m_frontRightMotor) motors++;
+    if (m_rearLeftMotor) motors++;
+    if (m_rearRightMotor) motors++;
+    return motors;
+  }
+};
diff --git a/wpilibc/Athena/include/SPI.h b/wpilibc/Athena/include/SPI.h
new file mode 100644
index 0000000..7b33dd7
--- /dev/null
+++ b/wpilibc/Athena/include/SPI.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "SensorBase.h"
+
+class DigitalOutput;
+class DigitalInput;
+
+/**
+ * SPI bus interface class.
+ *
+ * This class is intended to be used by sensor (and other SPI device) drivers.
+ * It probably should not be used directly.
+ *
+ */
+class SPI : public SensorBase {
+ public:
+  enum Port { kOnboardCS0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP };
+  SPI(Port SPIport);
+  virtual ~SPI();
+
+  SPI(const SPI&) = delete;
+  SPI& operator=(const SPI&) = delete;
+
+  void SetClockRate(double hz);
+
+  void SetMSBFirst();
+  void SetLSBFirst();
+
+  void SetSampleDataOnFalling();
+  void SetSampleDataOnRising();
+
+  void SetClockActiveLow();
+  void SetClockActiveHigh();
+
+  void SetChipSelectActiveHigh();
+  void SetChipSelectActiveLow();
+
+  virtual int32_t Write(uint8_t* data, uint8_t size);
+  virtual int32_t Read(bool initiate, uint8_t* dataReceived, uint8_t size);
+  virtual int32_t Transaction(uint8_t* dataToSend, uint8_t* dataReceived,
+                              uint8_t size);
+
+  void InitAccumulator(double period, uint32_t cmd, uint8_t xfer_size,
+                       uint32_t valid_mask, uint32_t valid_value,
+                       uint8_t data_shift, uint8_t data_size, bool is_signed,
+                       bool big_endian);
+  void FreeAccumulator();
+  void ResetAccumulator();
+  void SetAccumulatorCenter(int32_t center);
+  void SetAccumulatorDeadband(int32_t deadband);
+  int32_t GetAccumulatorLastValue() const;
+  int64_t GetAccumulatorValue() const;
+  uint32_t GetAccumulatorCount() const;
+  double GetAccumulatorAverage() const;
+  void GetAccumulatorOutput(int64_t &value, uint32_t &count) const;
+
+ protected:
+  uint8_t m_port;
+  bool m_msbFirst = false; // default little-endian
+  bool m_sampleOnTrailing = false; // default data updated on falling edge
+  bool m_clk_idle_high = false; // default clock active high
+
+ private:
+  void Init();
+};
diff --git a/wpilibc/Athena/include/SafePWM.h b/wpilibc/Athena/include/SafePWM.h
new file mode 100644
index 0000000..f364626
--- /dev/null
+++ b/wpilibc/Athena/include/SafePWM.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "MotorSafety.h"
+#include "PWM.h"
+#include "MotorSafetyHelper.h"
+#include <memory>
+#include <sstream>
+
+/**
+ * A safe version of the PWM class.
+ * It is safe because it implements the MotorSafety interface that provides
+ * timeouts
+ * in the event that the motor value is not updated before the expiration time.
+ * This delegates the actual work to a MotorSafetyHelper object that is used for
+ * all
+ * objects that implement MotorSafety.
+ */
+class SafePWM : public PWM, public MotorSafety {
+ public:
+  explicit SafePWM(uint32_t channel);
+  virtual ~SafePWM() = default;
+
+  void SetExpiration(float timeout);
+  float GetExpiration() const;
+  bool IsAlive() const;
+  void StopMotor();
+  bool IsSafetyEnabled() const;
+  void SetSafetyEnabled(bool enabled);
+  void GetDescription(std::ostringstream& desc) const;
+
+  virtual void SetSpeed(float speed);
+
+ private:
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+};
diff --git a/wpilibc/Athena/include/SampleRobot.h b/wpilibc/Athena/include/SampleRobot.h
new file mode 100644
index 0000000..64ca32c
--- /dev/null
+++ b/wpilibc/Athena/include/SampleRobot.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "RobotBase.h"
+
+class SampleRobot : public RobotBase {
+ public:
+  SampleRobot();
+  virtual ~SampleRobot() = default;
+  virtual void RobotInit();
+  virtual void Disabled();
+  virtual void Autonomous();
+  virtual void OperatorControl();
+  virtual void Test();
+  virtual void RobotMain();
+  void StartCompetition();
+
+ private:
+  bool m_robotMainOverridden;
+};
diff --git a/wpilibc/Athena/include/SerialPort.h b/wpilibc/Athena/include/SerialPort.h
new file mode 100644
index 0000000..3cd1c1c
--- /dev/null
+++ b/wpilibc/Athena/include/SerialPort.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "ErrorBase.h"
+#include "HAL/HAL.hpp"
+
+/**
+ * Driver for the RS-232 serial port on the RoboRIO.
+ *
+ * The current implementation uses the VISA formatted I/O mode.  This means that
+ *   all traffic goes through the fomatted buffers.  This allows the
+ * intermingled
+ *   use of Printf(), Scanf(), and the raw buffer accessors Read() and Write().
+ *
+ * More information can be found in the NI-VISA User Manual here:
+ *   http://www.ni.com/pdf/manuals/370423a.pdf
+ * and the NI-VISA Programmer's Reference Manual here:
+ *   http://www.ni.com/pdf/manuals/370132c.pdf
+ */
+class SerialPort : public ErrorBase {
+ public:
+  enum Parity {
+    kParity_None = 0,
+    kParity_Odd = 1,
+    kParity_Even = 2,
+    kParity_Mark = 3,
+    kParity_Space = 4
+  };
+  enum StopBits {
+    kStopBits_One = 10,
+    kStopBits_OnePointFive = 15,
+    kStopBits_Two = 20
+  };
+  enum FlowControl {
+    kFlowControl_None = 0,
+    kFlowControl_XonXoff = 1,
+    kFlowControl_RtsCts = 2,
+    kFlowControl_DtrDsr = 4
+  };
+  enum WriteBufferMode { kFlushOnAccess = 1, kFlushWhenFull = 2 };
+  enum Port { kOnboard = 0, kMXP = 1, kUSB = 2 };
+
+  SerialPort(uint32_t baudRate, Port port = kOnboard, uint8_t dataBits = 8,
+             Parity parity = kParity_None, StopBits stopBits = kStopBits_One);
+  ~SerialPort();
+
+  SerialPort(const SerialPort&) = delete;
+  SerialPort& operator=(const SerialPort&) = delete;
+
+  void SetFlowControl(FlowControl flowControl);
+  void EnableTermination(char terminator = '\n');
+  void DisableTermination();
+  int32_t GetBytesReceived();
+  uint32_t Read(char *buffer, int32_t count);
+  uint32_t Write(const std::string &buffer, int32_t count);
+  void SetTimeout(float timeout);
+  void SetReadBufferSize(uint32_t size);
+  void SetWriteBufferSize(uint32_t size);
+  void SetWriteBufferMode(WriteBufferMode mode);
+  void Flush();
+  void Reset();
+
+ private:
+  uint32_t m_resourceManagerHandle = 0;
+  uint32_t m_portHandle = 0;
+  bool m_consoleModeEnabled = false;
+  uint8_t m_port;
+};
diff --git a/wpilibc/Athena/include/Servo.h b/wpilibc/Athena/include/Servo.h
new file mode 100644
index 0000000..040d9d1
--- /dev/null
+++ b/wpilibc/Athena/include/Servo.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SafePWM.h"
+#include "SpeedController.h"
+
+#include <memory>
+
+/**
+ * Standard hobby style servo.
+ *
+ * The range parameters default to the appropriate values for the Hitec HS-322HD
+ * servo provided
+ * in the FIRST Kit of Parts in 2008.
+ */
+class Servo : public SafePWM {
+ public:
+  explicit Servo(uint32_t channel);
+  virtual ~Servo();
+  void Set(float value);
+  void SetOffline();
+  float Get() const;
+  void SetAngle(float angle);
+  float GetAngle() const;
+  static float GetMaxAngle() { return kMaxServoAngle; }
+  static float GetMinAngle() { return kMinServoAngle; }
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  float GetServoAngleRange() const { return kMaxServoAngle - kMinServoAngle; }
+
+  static constexpr float kMaxServoAngle = 180.0;
+  static constexpr float kMinServoAngle = 0.0;
+
+  static constexpr float kDefaultMaxServoPWM = 2.4;
+  static constexpr float kDefaultMinServoPWM = .6;
+};
diff --git a/wpilibc/Athena/include/Solenoid.h b/wpilibc/Athena/include/Solenoid.h
new file mode 100644
index 0000000..dc3d53a
--- /dev/null
+++ b/wpilibc/Athena/include/Solenoid.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SolenoidBase.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITableListener.h"
+
+#include <memory>
+
+/**
+ * Solenoid class for running high voltage Digital Output (PCM).
+ *
+ * The Solenoid class is typically used for pneumatics solenoids, but could be
+ * used
+ * for any device within the current spec of the PCM.
+ */
+class Solenoid : public SolenoidBase,
+                 public LiveWindowSendable,
+                 public ITableListener {
+ public:
+  explicit Solenoid(uint32_t channel);
+  Solenoid(uint8_t moduleNumber, uint32_t channel);
+  virtual ~Solenoid();
+  virtual void Set(bool on);
+  virtual bool Get() const;
+  bool IsBlackListed() const;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew);
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  uint32_t m_channel;  ///< The channel on the module to control.
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/SolenoidBase.h b/wpilibc/Athena/include/SolenoidBase.h
new file mode 100644
index 0000000..159beeb
--- /dev/null
+++ b/wpilibc/Athena/include/SolenoidBase.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "Resource.h"
+#include "SensorBase.h"
+#include "HAL/HAL.hpp"
+#include "HAL/Port.h"
+
+#include <memory>
+
+/**
+ * SolenoidBase class is the common base class for the Solenoid and
+ * DoubleSolenoid classes.
+ */
+class SolenoidBase : public SensorBase {
+ public:
+  virtual ~SolenoidBase() = default;
+  uint8_t GetAll(int module = 0) const;
+
+  uint8_t GetPCMSolenoidBlackList(int module) const;
+  bool GetPCMSolenoidVoltageStickyFault(int module) const;
+  bool GetPCMSolenoidVoltageFault(int module) const;
+  void ClearAllPCMStickyFaults(int module);
+
+ protected:
+  explicit SolenoidBase(uint8_t pcmID);
+  void Set(uint8_t value, uint8_t mask, int module);
+  const static int m_maxModules = 63;
+  const static int m_maxPorts = 8;
+  static void* m_ports[m_maxModules][m_maxPorts];
+  uint32_t m_moduleNumber;  ///< Slot number where the module is plugged into
+                            ///the chassis.
+  static std::unique_ptr<Resource> m_allocated;
+};
diff --git a/wpilibc/Athena/include/SpeedController.h b/wpilibc/Athena/include/SpeedController.h
new file mode 100644
index 0000000..a87ed2b
--- /dev/null
+++ b/wpilibc/Athena/include/SpeedController.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "HAL/HAL.hpp"
+#include "PIDOutput.h"
+
+/**
+ * Interface for speed controlling devices.
+ */
+class SpeedController : public PIDOutput {
+ public:
+  virtual ~SpeedController() = default;
+  /**
+   * Common interface for setting the speed of a speed controller.
+   *
+   * @param speed The speed to set.  Value should be between -1.0 and 1.0.
+   * @param syncGroup The update group to add this Set() to, pending
+   * UpdateSyncGroup().  If 0, update immediately.
+   */
+  virtual void Set(float speed, uint8_t syncGroup = 0) = 0;
+
+  /**
+   * Common interface for getting the current set speed of a speed controller.
+   *
+   * @return The current set speed.  Value is between -1.0 and 1.0.
+   */
+  virtual float Get() const = 0;
+
+  /**
+  * Common interface for inverting direction of a speed controller.
+  * @param isInverted The state of inversion, true is inverted.
+  */
+  virtual void SetInverted(bool isInverted) = 0;
+  /**
+
+   * Common interface for disabling a motor.
+   */
+  virtual void Disable() = 0;
+
+  /**
+   * Common interface for returning the inversion state of a speed controller.
+   * @return isInverted The state of inversion, true is inverted.
+   */
+  virtual bool GetInverted() const = 0;
+};
diff --git a/wpilibc/Athena/include/Talon.h b/wpilibc/Athena/include/Talon.h
new file mode 100644
index 0000000..38764b8
--- /dev/null
+++ b/wpilibc/Athena/include/Talon.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller
+ */
+class Talon : public SafePWM, public SpeedController {
+ public:
+  explicit Talon(uint32_t channel);
+  virtual ~Talon() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+
+  virtual void PIDWrite(float output) override;
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/TalonSRX.h b/wpilibc/Athena/include/TalonSRX.h
new file mode 100644
index 0000000..8819723
--- /dev/null
+++ b/wpilibc/Athena/include/TalonSRX.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control
+ * @see CANTalon for CAN control
+ */
+class TalonSRX : public SafePWM, public SpeedController {
+ public:
+  explicit TalonSRX(uint32_t channel);
+  virtual ~TalonSRX() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+
+  virtual void PIDWrite(float output) override;
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/USBCamera.h b/wpilibc/Athena/include/USBCamera.h
new file mode 100644
index 0000000..d02c5d3
--- /dev/null
+++ b/wpilibc/Athena/include/USBCamera.h
@@ -0,0 +1,121 @@
+/*----------------------------------------------------------------------------*/
+/* 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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "ErrorBase.h"
+#include "nivision.h"
+#include "NIIMAQdx.h"
+#include "HAL/cpp/priority_mutex.h"
+
+#include <string>
+
+typedef enum whiteBalance_enum {
+  kFixedIndoor = 3000,
+  kFixedOutdoor1 = 4000,
+  kFixedOutdoor2 = 5000,
+  kFixedFluorescent1 = 5100,
+  kFixedFlourescent2 = 5200
+} whiteBalance;
+
+class USBCamera : public ErrorBase {
+ private:
+  static constexpr char const *ATTR_WB_MODE =
+      "CameraAttributes::WhiteBalance::Mode";
+  static constexpr char const *ATTR_WB_VALUE =
+      "CameraAttributes::WhiteBalance::Value";
+  static constexpr char const *ATTR_EX_MODE =
+      "CameraAttributes::Exposure::Mode";
+  static constexpr char const *ATTR_EX_VALUE =
+      "CameraAttributes::Exposure::Value";
+  static constexpr char const *ATTR_BR_MODE =
+      "CameraAttributes::Brightness::Mode";
+  static constexpr char const *ATTR_BR_VALUE =
+      "CameraAttributes::Brightness::Value";
+
+  // Constants for the manual and auto types
+  static constexpr char const* AUTO = "Auto";
+  static constexpr char const* MANUAL = "Manual";
+
+ protected:
+  IMAQdxSession m_id = 0;
+  std::string m_name;
+  bool m_useJpeg;
+  bool m_active = false;
+  bool m_open = false;
+
+  priority_recursive_mutex m_mutex;
+
+  unsigned int m_width = 320;
+  unsigned int m_height = 240;
+  double m_fps = 30;
+  std::string m_whiteBalance = AUTO;
+  unsigned int m_whiteBalanceValue = 0;
+  bool m_whiteBalanceValuePresent = false;
+  std::string m_exposure = MANUAL;
+  unsigned int m_exposureValue = 50;
+  bool m_exposureValuePresent = false;
+  unsigned int m_brightness = 80;
+  bool m_needSettingsUpdate = true;
+
+  unsigned int GetJpegSize(void *buffer, unsigned int buffSize);
+
+ public:
+  static constexpr char const *kDefaultCameraName = "cam0";
+
+  USBCamera(std::string name, bool useJpeg);
+
+  void OpenCamera();
+  void CloseCamera();
+  void StartCapture();
+  void StopCapture();
+  void SetFPS(double fps);
+  void SetSize(unsigned int width, unsigned int height);
+
+  void UpdateSettings();
+  /**
+   * Set the brightness, as a percentage (0-100).
+   */
+  void SetBrightness(unsigned int brightness);
+
+  /**
+   * Get the brightness, as a percentage (0-100).
+   */
+  unsigned int GetBrightness();
+
+  /**
+   * Set the white balance to auto
+   */
+  void SetWhiteBalanceAuto();
+
+  /**
+   * Set the white balance to hold current
+   */
+  void SetWhiteBalanceHoldCurrent();
+
+  /**
+   * Set the white balance to manual, with specified color temperature
+   */
+  void SetWhiteBalanceManual(unsigned int wbValue);
+
+  /**
+   * Set the exposure to auto exposure
+   */
+  void SetExposureAuto();
+
+  /**
+   * Set the exposure to hold current
+   */
+  void SetExposureHoldCurrent();
+
+  /**
+   * Set the exposure to manual, with a given percentage (0-100)
+   */
+  void SetExposureManual(unsigned int expValue);
+
+  void GetImage(Image *image);
+  unsigned int GetImageData(void *buffer, unsigned int bufferSize);
+};
diff --git a/wpilibc/Athena/include/Ultrasonic.h b/wpilibc/Athena/include/Ultrasonic.h
new file mode 100644
index 0000000..9f36171
--- /dev/null
+++ b/wpilibc/Athena/include/Ultrasonic.h
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SensorBase.h"
+#include "Counter.h"
+#include "Task.h"
+#include "PIDSource.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include <atomic>
+
+#include "HAL/cpp/priority_mutex.h"
+
+#include <memory>
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * Ultrasonic rangefinder class.
+ * The Ultrasonic rangefinder measures absolute distance based on the round-trip
+ * time
+ * of a ping generated by the controller. These sensors use two transducers, a
+ * speaker and
+ * a microphone both tuned to the ultrasonic range. A common ultrasonic sensor,
+ * the Daventech SRF04
+ * requires a short pulse to be generated on a digital channel. This causes the
+ * chirp to be
+ * emmitted. A second line becomes high as the ping is transmitted and goes low
+ * when
+ * the echo is received. The time that the line is high determines the round
+ * trip distance
+ * (time of flight).
+ */
+class Ultrasonic : public SensorBase,
+                   public PIDSource,
+                   public LiveWindowSendable {
+ public:
+  enum DistanceUnit { kInches = 0, kMilliMeters = 1 };
+
+  Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel,
+             DistanceUnit units = kInches);
+
+  Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel,
+             DistanceUnit units = kInches);
+
+  Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+             std::shared_ptr<DigitalInput> echoChannel,
+             DistanceUnit units = kInches);
+  Ultrasonic(uint32_t pingChannel, uint32_t echoChannel,
+             DistanceUnit units = kInches);
+  virtual ~Ultrasonic();
+
+  void Ping();
+  bool IsRangeValid() const;
+  static void SetAutomaticMode(bool enabling);
+  double GetRangeInches() const;
+  double GetRangeMM() const;
+  bool IsEnabled() const { return m_enabled; }
+  void SetEnabled(bool enable) { m_enabled = enable; }
+
+  double PIDGet() override;
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+  void SetDistanceUnits(DistanceUnit units);
+  DistanceUnit GetDistanceUnits() const;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  void Initialize();
+
+  static void UltrasonicChecker();
+
+  static constexpr double kPingTime =
+      10 * 1e-6;  ///< Time (sec) for the ping trigger pulse.
+  static const uint32_t kPriority =
+      64;  ///< Priority that the ultrasonic round robin task runs.
+  static constexpr double kMaxUltrasonicTime =
+      0.1;  ///< Max time (ms) between readings.
+  static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+
+  static Task m_task;  // task doing the round-robin automatic sensing
+  static Ultrasonic *m_firstSensor;  // head of the ultrasonic sensor list
+  static std::atomic<bool> m_automaticEnabled; // automatic round robin mode
+  static priority_mutex m_mutex;  // synchronize access to the list of sensors
+
+  std::shared_ptr<DigitalOutput> m_pingChannel;
+  std::shared_ptr<DigitalInput> m_echoChannel;
+  bool m_enabled = false;
+  Counter m_counter;
+  Ultrasonic *m_nextSensor;
+  DistanceUnit m_units;
+
+  std::shared_ptr<ITable> m_table;
+};
diff --git a/wpilibc/Athena/include/Victor.h b/wpilibc/Athena/include/Victor.h
new file mode 100644
index 0000000..755955f
--- /dev/null
+++ b/wpilibc/Athena/include/Victor.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Vex Robotics Victor 888 Speed Controller
+ *
+ * The Vex Robotics Victor 884 Speed Controller can also be used with this
+ * class but may need to be calibrated per the Victor 884 user manual.
+ */
+class Victor : public SafePWM, public SpeedController {
+ public:
+  explicit Victor(uint32_t channel);
+  virtual ~Victor() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+
+  virtual void PIDWrite(float output) override;
+
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
diff --git a/wpilibc/Athena/include/VictorSP.h b/wpilibc/Athena/include/VictorSP.h
new file mode 100644
index 0000000..978cd0a
--- /dev/null
+++ b/wpilibc/Athena/include/VictorSP.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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 "SafePWM.h"
+#include "SpeedController.h"
+#include "PIDOutput.h"
+
+/**
+ * Vex Robotics Victor SP Speed Controller
+ */
+class VictorSP : public SafePWM, public SpeedController {
+ public:
+  explicit VictorSP(uint32_t channel);
+  virtual ~VictorSP() = default;
+  virtual void Set(float value, uint8_t syncGroup = 0) override;
+  virtual float Get() const override;
+  virtual void Disable() override;
+
+  virtual void PIDWrite(float output) override;
+
+  virtual void SetInverted(bool isInverted) override;
+  virtual bool GetInverted() const override;
+
+ private:
+  bool m_isInverted = false;
+};
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);
diff --git a/wpilibc/Athena/include/WPILib.h b/wpilibc/Athena/include/WPILib.h
new file mode 100644
index 0000000..0386b03
--- /dev/null
+++ b/wpilibc/Athena/include/WPILib.h
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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
+
+#define REAL
+
+#include "string.h"
+#include <iostream>
+
+#include "ADXL345_I2C.h"
+#include "ADXL345_SPI.h"
+#include "ADXL362.h"
+#include "ADXRS450_Gyro.h"
+#include "AnalogAccelerometer.h"
+#include "AnalogGyro.h"
+#include "AnalogInput.h"
+#include "AnalogOutput.h"
+#include "AnalogPotentiometer.h"
+#include "AnalogTrigger.h"
+#include "AnalogTriggerOutput.h"
+#include "BuiltInAccelerometer.h"
+#include "Buttons/InternalButton.h"
+#include "Buttons/JoystickButton.h"
+#include "Buttons/NetworkButton.h"
+#include "CameraServer.h"
+#include "CANJaguar.h"
+#include "CANTalon.h"
+#include "Commands/Command.h"
+#include "Commands/CommandGroup.h"
+#include "Commands/PIDCommand.h"
+#include "Commands/PIDSubsystem.h"
+#include "Commands/PrintCommand.h"
+#include "Commands/Scheduler.h"
+#include "Commands/StartCommand.h"
+#include "Commands/Subsystem.h"
+#include "Commands/WaitCommand.h"
+#include "Commands/WaitForChildren.h"
+#include "Commands/WaitUntilCommand.h"
+#include "Compressor.h"
+#include "ControllerPower.h"
+#include "Counter.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "DigitalSource.h"
+#include "DoubleSolenoid.h"
+#include "DriverStation.h"
+#include "Encoder.h"
+#include "ErrorBase.h"
+#include "GearTooth.h"
+#include "GenericHID.h"
+#include "interfaces/Accelerometer.h"
+#include "interfaces/Gyro.h"
+#include "interfaces/Potentiometer.h"
+#include "I2C.h"
+#include "IterativeRobot.h"
+#include "InterruptableSensorBase.h"
+#include "Jaguar.h"
+#include "Joystick.h"
+#include "Notifier.h"
+#include "PIDController.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+#include "Preferences.h"
+#include "PowerDistributionPanel.h"
+#include "PWM.h"
+#include "Relay.h"
+#include "Resource.h"
+#include "RobotBase.h"
+#include "RobotDrive.h"
+#include "SensorBase.h"
+#include "SerialPort.h"
+#include "Servo.h"
+#include "SampleRobot.h"
+#include "SmartDashboard/SendableChooser.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "Solenoid.h"
+#include "SpeedController.h"
+#include "SPI.h"
+#include "Talon.h"
+#include "TalonSRX.h"
+#include "Task.h"
+#include "Timer.h"
+#include "Ultrasonic.h"
+#include "Utility.h"
+#include "Victor.h"
+#include "VictorSP.h"
+#include "Vision/AxisCamera.h"
+#include "Vision/BinaryImage.h"
+#include "Vision/ColorImage.h"
+#include "Vision/HSLImage.h"
+#include "Vision/ImageBase.h"
+#include "Vision/MonoImage.h"
+#include "Vision/RGBImage.h"
+#include "Vision/Threshold.h"
+// XXX: #include "Vision/AxisCamera.h"
+#include "WPIErrors.h"
diff --git a/wpilibc/Athena/include/nivision.h b/wpilibc/Athena/include/nivision.h
new file mode 100644
index 0000000..5c56962
--- /dev/null
+++ b/wpilibc/Athena/include/nivision.h
@@ -0,0 +1,8829 @@
+/*============================================================================*/
+/*                        IMAQ Vision                                         */
+/*----------------------------------------------------------------------------*/
+/*    Copyright (c) National Instruments 2001.  All Rights Reserved.          */
+/*----------------------------------------------------------------------------*/
+/*                                                                            */
+/* Title:       NIVision.h                                                    */
+/*                                                                            */
+/*============================================================================*/
+#if !defined(NiVision_h)
+#define NiVision_h
+
+//============================================================================
+//  Includes
+//============================================================================
+#include <stddef.h>
+
+//============================================================================
+//  Control Defines
+//============================================================================
+#if !defined(IMAQ_IMPORT)
+#ifndef __GNUC__
+#define IMAQ_IMPORT __declspec(dllimport)
+#else
+#define IMAQ_IMPORT
+#endif
+#endif
+
+#if !defined(IMAQ_FUNC)
+#if !defined(__cplusplus)
+#define IMAQ_FUNC IMAQ_IMPORT
+#else
+#define IMAQ_FUNC extern "C" IMAQ_IMPORT
+#endif
+#endif
+
+#if !defined(IMAQ_STDCALL)
+#ifndef __GNUC__
+#define IMAQ_STDCALL __stdcall
+#else
+#define IMAQ_STDCALL
+#endif
+#endif
+
+#ifdef _CVI_
+#pragma EnableLibraryRuntimeChecking
+#include <ansi_c.h>
+#endif
+
+#define IMAQ_CALLBACK __cdecl
+
+//============================================================================
+//  Manifest Constants
+//============================================================================
+#ifndef NULL
+#ifdef __cplusplus
+#define NULL ((void*)0)
+#else
+#define NULL 0
+#endif
+#endif
+
+#ifndef FALSE
+#define FALSE 0
+#endif
+
+#ifndef TRUE
+#define TRUE 1
+#endif
+
+#define IMAQ_DEFAULT_SHOW_COORDINATES TRUE
+#define IMAQ_DEFAULT_MAX_ICONS_PER_LINE 4
+#define IMAQ_DEFAULT_LEARNING_MODE IMAQ_LEARN_SHIFT_INFORMATION
+#define IMAQ_DEFAULT_BMP_COMPRESS FALSE
+#define IMAQ_DEFAULT_PNG_QUALITY 750
+#define IMAQ_DEFAULT_JPEG_QUALITY 750
+#define IMAQ_ALL_CONTOURS -1
+#define IMAQ_ALL_WINDOWS -1
+#define IMAQ_SHIFT 1
+#define IMAQ_ALT 2
+#define IMAQ_CTRL 4
+#define IMAQ_CAPS_LOCK 8
+#define IMAQ_MODAL_DIALOG -1
+#define IMAQ_INIT_RGB_TRANSPARENT \
+  { 0, 0, 0, 1 }
+#define IMAQ_INIT_RGB_RED \
+  { 0, 0, 255, 0 }
+#define IMAQ_INIT_RGB_BLUE \
+  { 255, 0, 0, 0 }
+#define IMAQ_INIT_RGB_GREEN \
+  { 0, 255, 0, 0 }
+#define IMAQ_INIT_RGB_YELLOW \
+  { 0, 255, 255, 0 }
+#define IMAQ_INIT_RGB_WHITE \
+  { 255, 255, 255, 0 }
+#define IMAQ_INIT_RGB_BLACK \
+  { 0, 0, 0, 0 }
+#define IMAQ_USE_DEFAULT_QUALITY -1
+#define IMAQ_ALL_SAMPLES -1
+#define IMAQ_ALL_OBJECTS -1
+#define IMAQ_ALL_CHARACTERS -1
+
+//============================================================================
+//  Predefined Valid Characters
+//============================================================================
+#define IMAQ_ANY_CHARACTER ""  // Any Character
+#define IMAQ_ALPHABETIC \
+  "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz"  // Alphabetic
+#define IMAQ_ALPHANUMERIC \
+  "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789"  // Alphanumeric
+#define IMAQ_UPPERCASE_LETTERS "ABCDEFGHIJKLMNOPQRSTUVWXYZ"  // Uppercase
+                                                             // Letters
+#define IMAQ_LOWERCASE_LETTERS "abcdefghijklmnopqrstuvwxyz"  // Lowercase
+                                                             // Letters
+#define IMAQ_DECIMAL_DIGITS "0123456789"  // Decimal Digits
+#define IMAQ_HEXADECIMAL_DIGITS "0123456789ABCDEFabcdef"  // Hexadecimal Digits
+#define IMAQ_PATTERN \
+  "\xFF"  // Pattern (A single character string with the character value set to
+          // 255)
+#define IMAQ_FORCE_SPACE " "  // Force Space
+
+//============================================================================
+//  Macros
+//============================================================================
+#define IMAQ_NO_RECT imaqMakeRect(0, 0, 0x7FFFFFFF, 0x7FFFFFFF)
+#define IMAQ_NO_ROTATED_RECT \
+  imaqMakeRotatedRect(0, 0, 0x7FFFFFFF, 0x7FFFFFFF, 0)
+#define IMAQ_NO_POINT imaqMakePoint(-1, -1)
+#define IMAQ_NO_POINT_FLOAT imaqMakePointFloat(-1.0, -1.0)
+#define IMAQ_NO_OFFSET imaqMakePointFloat(0.0, 0.0)
+
+//============================================================================
+//  When in Borland, some functions must be mapped to different names.
+//  This accomplishes said task.
+//============================================================================
+#if defined(__BORLANDC__) || (defined(_CVI_) && defined(_NI_BC_))
+#define imaqMakePoint imaqMakePoint_BC
+#define imaqMakePointFloat imaqMakePointFloat_BC
+#endif
+
+//============================================================================
+//  When in Watcom, some functions must be mapped to different names.
+//  This accomplishes said task.
+//============================================================================
+#if defined(__WATCOMC__) || (defined(_CVI_) && defined(_NI_WC_))
+#define imaqMakePoint imaqMakePoint_BC
+#define imaqMakePointFloat imaqMakePointFloat_BC
+#endif
+
+//============================================================================
+//  If using Visual C++, force startup & shutdown code to run.
+//============================================================================
+#if defined(_MSC_VER) && !defined(_CVI_) && !defined(__BORLANDC__)
+#pragma comment(linker, "/INCLUDE:_nivision_startup_shutdown")
+#pragma comment(linker, "/DEFAULTLIB:nivision.lib")
+#endif
+
+//============================================================================
+//  Error Codes
+//============================================================================
+#define ERR_SUCCESS 0                 // No error.
+#define ERR_SYSTEM_ERROR -1074396160  // System error.
+#define ERR_OUT_OF_MEMORY \
+  -1074396159  // Not enough memory for requested operation.
+#define ERR_MEMORY_ERROR -1074396158  // Memory error.
+#define ERR_UNREGISTERED -1074396157  // Unlicensed copy of NI Vision.
+#define ERR_NEED_FULL_VERSION \
+  -1074396156  // The function requires an NI Vision 5.0 Advanced license.
+#define ERR_UNINIT -1074396155  // NI Vision did not initialize properly.
+#define ERR_IMAGE_TOO_SMALL \
+  -1074396154  // The image is not large enough for the operation.
+#define ERR_BARCODE_CODABAR \
+  -1074396153  // The barcode is not a valid Codabar barcode.
+#define ERR_BARCODE_CODE39 \
+  -1074396152  // The barcode is not a valid Code 3 of 9 barcode.
+#define ERR_BARCODE_CODE93 \
+  -1074396151  // The barcode is not a valid Code93 barcode.
+#define ERR_BARCODE_CODE128 \
+  -1074396150  // The barcode is not a valid Code128 barcode.
+#define ERR_BARCODE_EAN8 \
+  -1074396149  // The barcode is not a valid EAN8 barcode.
+#define ERR_BARCODE_EAN13 \
+  -1074396148  // The barcode is not a valid EAN13 barcode.
+#define ERR_BARCODE_I25 \
+  -1074396147  // The barcode is not a valid Interleaved 2 of 5 barcode.
+#define ERR_BARCODE_MSI -1074396146  // The barcode is not a valid MSI barcode.
+#define ERR_BARCODE_UPCA \
+  -1074396145  // The barcode is not a valid UPCA barcode.
+#define ERR_BARCODE_CODE93_SHIFT \
+  -1074396144  // The Code93 barcode contains invalid shift encoding.
+#define ERR_BARCODE_TYPE -1074396143  // The barcode type is invalid.
+#define ERR_BARCODE_INVALID \
+  -1074396142  // The image does not represent a valid linear barcode.
+#define ERR_BARCODE_CODE128_FNC \
+  -1074396141  // The FNC value in the Code128 barcode is not located before the
+               // first data value.
+#define ERR_BARCODE_CODE128_SET \
+  -1074396140  // The starting code set in the Code128 barcode is not valid.
+#define ERR_ROLLBACK_RESOURCE_OUT_OF_MEMORY \
+  -1074396139  // Not enough reserved memory in the timed environment for the
+               // requested operation.
+#define ERR_ROLLBACK_NOT_SUPPORTED \
+  -1074396138  // The function is not supported when a time limit is active.
+#define ERR_DIRECTX_DLL_NOT_FOUND \
+  -1074396137  // Quartz.dll not found.  Install DirectX 8.1 or later.
+#define ERR_DIRECTX_INVALID_FILTER_QUALITY \
+  -1074396136  // The filter quality you provided is invalid. Valid quality
+               // values range from -1 to 1000.
+#define ERR_INVALID_BUTTON_LABEL -1074396135  // Invalid button label.
+#define ERR_THREAD_INITIALIZING \
+  -1074396134  // Could not execute the function in the separate thread because
+               // the thread has not completed initialization.
+#define ERR_THREAD_COULD_NOT_INITIALIZE \
+  -1074396133  // Could not execute the function in the separate thread because
+               // the thread could not initialize.
+#define ERR_MASK_NOT_TEMPLATE_SIZE \
+  -1074396132  // The mask must be the same size as the template.
+#define ERR_NOT_RECT_OR_ROTATED_RECT \
+  -1074396130  // The ROI must only have either a single Rectangle contour or a
+               // single Rotated Rectangle contour.
+#define ERR_ROLLBACK_UNBOUNDED_INTERFACE \
+  -1074396129  // During timed execution, you must use the preallocated version
+               // of this operation.
+#define ERR_ROLLBACK_RESOURCE_CONFLICT_3 \
+  -1074396128  // An image being modified by one process cannot be requested by
+               // another process while a time limit is active.
+#define ERR_ROLLBACK_RESOURCE_CONFLICT_2 \
+  -1074396127  // An image with pattern matching, calibration, or overlay
+               // information cannot be manipulated while a time limit is
+               // active.
+#define ERR_ROLLBACK_RESOURCE_CONFLICT_1 \
+  -1074396126  // An image created before a time limit is started cannot be
+               // resized while a time limit is active.
+#define ERR_INVALID_CONTRAST_THRESHOLD \
+  -1074396125  // Invalid contrast threshold. The threshold value must be
+               // greater than 0.
+#define ERR_INVALID_CALIBRATION_ROI_MODE \
+  -1074396124  // NI Vision does not support the calibration ROI mode you
+               // supplied.
+#define ERR_INVALID_CALIBRATION_MODE \
+  -1074396123  // NI Vision does not support the calibration mode you supplied.
+#define ERR_DRAWTEXT_COLOR_MUST_BE_GRAYSCALE \
+  -1074396122  // Set the foreground and background text colors to grayscale to
+               // draw on a U8 image.
+#define ERR_SATURATION_THRESHOLD_OUT_OF_RANGE \
+  -1074396121  // The value of the saturation threshold must be from 0 to 255.
+#define ERR_NOT_IMAGE -1074396120  // Not an image.
+#define ERR_CUSTOMDATA_INVALID_KEY \
+  -1074396119  // They custom data key you supplied is invalid. The only valid
+               // character values are decimal 32-126 and 161-255. There must
+               // also be no repeated, leading, or trailing spaces.
+#define ERR_INVALID_STEP_SIZE \
+  -1074396118  // Step size must be greater than zero and less than Image size
+#define ERR_MATRIX_SIZE \
+  -1074396117  // Invalid matrix size in the structuring element.
+#define ERR_CALIBRATION_INSF_POINTS \
+  -1074396116  // Insufficient number of calibration feature points.
+#define ERR_CALIBRATION_IMAGE_CORRECTED \
+  -1074396115  // The operation is invalid in a corrected image.
+#define ERR_CALIBRATION_INVALID_ROI \
+  -1074396114  // The ROI contains an invalid contour type or is not contained
+               // in the ROI learned for calibration.
+#define ERR_CALIBRATION_IMAGE_UNCALIBRATED \
+  -1074396113  // The source/input image has not been calibrated.
+#define ERR_INCOMP_MATRIX_SIZE \
+  -1074396112  // The number of pixel and real-world coordinates must be equal.
+#define ERR_CALIBRATION_FAILED_TO_FIND_GRID \
+  -1074396111  // Unable to automatically detect grid because the image is too
+               // distorted.
+#define ERR_CALIBRATION_INFO_VERSION \
+  -1074396110  // Invalid calibration information version.
+#define ERR_CALIBRATION_INVALID_SCALING_FACTOR \
+  -1074396109  // Invalid calibration scaling factor.
+#define ERR_CALIBRATION_ERRORMAP \
+  -1074396108  // The calibration error map cannot be computed.
+#define ERR_CALIBRATION_INFO_1 \
+  -1074396107  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_2 \
+  -1074396106  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_3 \
+  -1074396105  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_4 \
+  -1074396104  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_5 \
+  -1074396103  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_6 \
+  -1074396102  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_MICRO_PLANE \
+  -1074396101  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_PERSPECTIVE_PROJECTION \
+  -1074396100  // Invalid calibration template image.
+#define ERR_CALIBRATION_INFO_SIMPLE_TRANSFORM \
+  -1074396099  // Invalid calibration template image.
+#define ERR_RESERVED_MUST_BE_NULL \
+  -1074396098  // You must pass NULL for the reserved parameter.
+#define ERR_INVALID_PARTICLE_PARAMETER_VALUE \
+  -1074396097  // You entered an invalid selection in the particle parameter.
+#define ERR_NOT_AN_OBJECT -1074396096  // Not an object.
+#define ERR_CALIBRATION_DUPLICATE_REFERENCE_POINT \
+  -1074396095  // The reference points passed are inconsistent.  At least two
+               // similar pixel coordinates correspond to different real-world
+               // coordinates.
+#define ERR_ROLLBACK_RESOURCE_CANNOT_UNLOCK \
+  -1074396094  // A resource conflict occurred in the timed environment. Two
+               // processes cannot manage the same resource and be time bounded.
+#define ERR_ROLLBACK_RESOURCE_LOCKED \
+  -1074396093  // A resource conflict occurred in the timed environment. Two
+               // processes cannot access the same resource and be time bounded.
+#define ERR_ROLLBACK_RESOURCE_NON_EMPTY_INITIALIZE \
+  -1074396092  // Multiple timed environments are not supported.
+#define ERR_ROLLBACK_RESOURCE_UNINITIALIZED_ENABLE \
+  -1074396091  // A time limit cannot be started until the timed environment is
+               // initialized.
+#define ERR_ROLLBACK_RESOURCE_ENABLED \
+  -1074396090  // Multiple timed environments are not supported.
+#define ERR_ROLLBACK_RESOURCE_REINITIALIZE \
+  -1074396089  // The timed environment is already initialized.
+#define ERR_ROLLBACK_RESIZE \
+  -1074396088  // The results of the operation exceeded the size limits on the
+               // output data arrays.
+#define ERR_ROLLBACK_STOP_TIMER \
+  -1074396087  // No time limit is available to stop.
+#define ERR_ROLLBACK_START_TIMER -1074396086  // A time limit could not be set.
+#define ERR_ROLLBACK_INIT_TIMER \
+  -1074396085  // The timed environment could not be initialized.
+#define ERR_ROLLBACK_DELETE_TIMER \
+  -1074396084  // No initialized timed environment is available to close.
+#define ERR_ROLLBACK_TIMEOUT -1074396083  // The time limit has expired.
+#define ERR_PALETTE_NOT_SUPPORTED \
+  -1074396082  // Only 8-bit images support the use of palettes.  Either do not
+               // use a palette, or convert your image to an 8-bit image before
+               // using a palette.
+#define ERR_BAD_PASSWORD -1074396081             // Incorrect password.
+#define ERR_INVALID_IMAGE_TYPE -1074396080       // Invalid image type.
+#define ERR_INVALID_METAFILE_HANDLE -1074396079  // Invalid metafile handle.
+#define ERR_INCOMP_TYPE -1074396077              // Incompatible image type.
+#define ERR_COORD_SYS_FIRST_AXIS \
+  -1074396076  // Unable to fit a line for the primary axis.
+#define ERR_COORD_SYS_SECOND_AXIS \
+  -1074396075  // Unable to fit a line for the secondary axis.
+#define ERR_INCOMP_SIZE -1074396074  // Incompatible image size.
+#define ERR_MASK_OUTSIDE_IMAGE \
+  -1074396073  // When the mask's offset was applied, the mask was entirely
+               // outside of the image.
+#define ERR_INVALID_BORDER -1074396072          // Invalid image border.
+#define ERR_INVALID_SCAN_DIRECTION -1074396071  // Invalid scan direction.
+#define ERR_INVALID_FUNCTION -1074396070        // Unsupported function.
+#define ERR_INVALID_COLOR_MODE \
+  -1074396069  // NI Vision does not support the color mode you specified.
+#define ERR_INVALID_ACTION \
+  -1074396068  // The function does not support the requested action.
+#define ERR_IMAGES_NOT_DIFF \
+  -1074396067  // The source image and destination image must be different.
+#define ERR_INVALID_POINTSYMBOL -1074396066  // Invalid point symbol.
+#define ERR_CANT_RESIZE_EXTERNAL \
+  -1074396065  // Cannot resize an image in an acquisition buffer.
+#define ERR_EXTERNAL_NOT_SUPPORTED \
+  -1074396064  // This operation is not supported for images in an acquisition
+               // buffer.
+#define ERR_EXTERNAL_ALIGNMENT \
+  -1074396063  // The external buffer must be aligned on a 4-byte boundary. The
+               // line width and border pixels must be 4-byte aligned, as well.
+#define ERR_INVALID_TOLERANCE \
+  -1074396062  // The tolerance parameter must be greater than or equal to 0.
+#define ERR_INVALID_WINDOW_SIZE \
+  -1074396061  // The size of each dimension of the window must be greater than
+               // 2 and less than or equal to the size of the image in the
+               // corresponding dimension.
+#define ERR_JPEG2000_LOSSLESS_WITH_FLOATING_POINT \
+  -1074396060  // Lossless compression cannot be used with the floating point
+               // wavelet transform mode. Either set the wavelet transform mode
+               // to integer, or use lossy compression.
+#define ERR_INVALID_MAX_ITERATIONS \
+  -1074396059  // Invalid maximum number of iterations. Maximum number of
+               // iterations must be greater than zero.
+#define ERR_INVALID_ROTATION_MODE -1074396058  // Invalid rotation mode.
+#define ERR_INVALID_SEARCH_VECTOR_WIDTH \
+  -1074396057  // Invalid search vector width. The width must be an odd number
+               // greater than zero.
+#define ERR_INVALID_MATRIX_MIRROR_MODE \
+  -1074396056  // Invalid matrix mirror mode.
+#define ERR_INVALID_ASPECT_RATIO \
+  -1074396055  // Invalid aspect ratio. Valid aspect ratios must be greater than
+               // or equal to zero.
+#define ERR_INVALID_CELL_FILL_TYPE -1074396054  // Invalid cell fill type.
+#define ERR_INVALID_BORDER_INTEGRITY \
+  -1074396053  // Invalid border integrity. Valid values range from 0 to 100.
+#define ERR_INVALID_DEMODULATION_MODE -1074396052  // Invalid demodulation mode.
+#define ERR_INVALID_CELL_FILTER_MODE -1074396051   // Invalid cell filter mode.
+#define ERR_INVALID_ECC_TYPE -1074396050           // Invalid ECC type.
+#define ERR_INVALID_MATRIX_POLARITY -1074396049    // Invalid matrix polarity.
+#define ERR_INVALID_CELL_SAMPLE_SIZE -1074396048   // Invalid cell sample size.
+#define ERR_INVALID_LINEAR_AVERAGE_MODE \
+  -1074396047  // Invalid linear average mode.
+#define ERR_INVALID_2D_BARCODE_CONTRAST_FOR_ROI \
+  -1074396046  // When using a region of interest that is not a rectangle, you
+               // must specify the contrast mode of the barcode as either black
+               // on white or white on black.
+#define ERR_INVALID_2D_BARCODE_SUBTYPE \
+  -1074396045  // Invalid 2-D barcode Data Matrix subtype.
+#define ERR_INVALID_2D_BARCODE_SHAPE -1074396044  // Invalid 2-D barcode shape.
+#define ERR_INVALID_2D_BARCODE_CELL_SHAPE \
+  -1074396043  // Invalid 2-D barcode cell shape.
+#define ERR_INVALID_2D_BARCODE_CONTRAST \
+  -1074396042  // Invalid 2-D barcode contrast.
+#define ERR_INVALID_2D_BARCODE_TYPE -1074396041  // Invalid 2-D barcode type.
+#define ERR_DRIVER -1074396040    // Cannot access NI-IMAQ driver.
+#define ERR_IO_ERROR -1074396039  // I/O error.
+#define ERR_FIND_COORDSYS_MORE_THAN_ONE_EDGE \
+  -1074396038  // When searching for a coordinate system, the number of lines to
+               // fit must be 1.
+#define ERR_TIMEOUT -1074396037  // Trigger timeout.
+#define ERR_INVALID_SKELETONMODE \
+  -1074396036  // The Skeleton mode you specified is invalid.
+#define ERR_TEMPLATEIMAGE_NOCIRCLE \
+  -1074396035  // The template image does not contain enough information for
+               // learning the aggressive search strategy.
+#define ERR_TEMPLATEIMAGE_EDGEINFO \
+  -1074396034  // The template image does not contain enough edge information
+               // for the sample size(s) requested.
+#define ERR_TEMPLATEDESCRIPTOR_LEARNSETUPDATA \
+  -1074396033  // Invalid template descriptor.
+#define ERR_TEMPLATEDESCRIPTOR_ROTATION_SEARCHSTRATEGY \
+  -1074396032  // The template descriptor does not contain data required for the
+               // requested search strategy in rotation-invariant matching.
+#define ERR_INVALID_TETRAGON \
+  -1074396031  // The input tetragon must have four points. The points are
+               // specified clockwise starting with the top left point.
+#define ERR_TOO_MANY_CLASSIFICATION_SESSIONS \
+  -1074396030  // There are too many classification sessions open.  You must
+               // close a session before you can open another one.
+#define ERR_TIME_BOUNDED_EXECUTION_NOT_SUPPORTED \
+  -1074396028  // NI Vision no longer supports time-bounded execution.
+#define ERR_INVALID_COLOR_RESOLUTION \
+  -1074396027  // Invalid Color Resolution for the Color Classifier
+#define ERR_INVALID_PROCESS_TYPE_FOR_EDGE_DETECTION \
+  -1074396026  // Invalid process type for edge detection.
+#define ERR_INVALID_ANGLE_RANGE_FOR_STRAIGHT_EDGE \
+  -1074396025  // Angle range value should be equal to or greater than zero.
+#define ERR_INVALID_MIN_COVERAGE_FOR_STRAIGHT_EDGE \
+  -1074396024  // Minimum coverage value should be greater than zero.
+#define ERR_INVALID_ANGLE_TOL_FOR_STRAIGHT_EDGE \
+  -1074396023  // The angle tolerance should be equal to or greater than 0.001.
+#define ERR_INVALID_SEARCH_MODE_FOR_STRAIGHT_EDGE \
+  -1074396022  // Invalid search mode for detecting straight edges
+#define ERR_INVALID_KERNEL_SIZE_FOR_EDGE_DETECTION \
+  -1074396021  // Invalid kernel size for edge detection. The minimum kernel
+               // size is 3, the maximum kernel size is 1073741823 and the
+               // kernel size must be odd.
+#define ERR_INVALID_GRADING_MODE -1074396020  // Invalid grading mode.
+#define ERR_INVALID_THRESHOLD_PERCENTAGE \
+  -1074396019  // Invalid threshold percentage. Valid values range from 0 to
+               // 100.
+#define ERR_INVALID_EDGE_POLARITY_SEARCH_MODE \
+  -1074396018  // Invalid edge polarity search mode.
+#define ERR_OPENING_NEWER_AIM_GRADING_DATA \
+  -1074396017  // The AIM grading data attached to the image you tried to open
+               // was created with a newer version of NI Vision. Upgrade to the
+               // latest version of NI Vision to read this file.
+#define ERR_NO_VIDEO_DRIVER -1074396016  // No video driver is installed.
+#define ERR_RPC_EXECUTE_IVB \
+  -1074396015  // Unable to establish network connection with remote system.
+#define ERR_INVALID_VIDEO_BLIT \
+  -1074396014  // RT Video Out does not support displaying the supplied image
+               // type at the selected color depth.
+#define ERR_INVALID_VIDEO_MODE -1074396013  // Invalid video mode.
+#define ERR_RPC_EXECUTE \
+  -1074396012  // Unable to display remote image on network connection.
+#define ERR_RPC_BIND -1074396011  // Unable to establish network connection.
+#define ERR_INVALID_FRAME_NUMBER -1074396010  // Invalid frame number.
+#define ERR_DIRECTX \
+  -1074396009  // An internal DirectX error has occurred.  Try upgrading to the
+               // latest version of DirectX.
+#define ERR_DIRECTX_NO_FILTER \
+  -1074396008  // An appropriate DirectX filter to process this file could not
+               // be found.  Install the filter that was used to create this
+               // AVI. Upgrading to the latest version of DirectX may correct
+               // this error.  NI Vision requires DirectX 8.1 or higher.
+#define ERR_DIRECTX_INCOMPATIBLE_COMPRESSION_FILTER \
+  -1074396007  // Incompatible compression filter.
+#define ERR_DIRECTX_UNKNOWN_COMPRESSION_FILTER \
+  -1074396006                                // Unknown compression filter.
+#define ERR_INVALID_AVI_SESSION -1074396005  // Invalid AVI session.
+#define ERR_DIRECTX_CERTIFICATION_FAILURE \
+  -1074396004  // A software key is restricting the use of this compression
+               // filter.
+#define ERR_AVI_DATA_EXCEEDS_BUFFER_SIZE \
+  -1074396003  // The data for this frame exceeds the data buffer size specified
+               // when creating the AVI file.
+#define ERR_INVALID_LINEGAUGEMETHOD -1074396002  // Invalid line gauge method.
+#define ERR_TOO_MANY_AVI_SESSIONS \
+  -1074396001  // There are too many AVI sessions open.  You must close a
+               // session before you can open another one.
+#define ERR_FILE_FILE_HEADER -1074396000    // Invalid file header.
+#define ERR_FILE_FILE_TYPE -1074395999      // Invalid file type.
+#define ERR_FILE_COLOR_TABLE -1074395998    // Invalid color table.
+#define ERR_FILE_ARGERR -1074395997         // Invalid parameter.
+#define ERR_FILE_OPEN -1074395996           // File is already open for writing.
+#define ERR_FILE_NOT_FOUND -1074395995      // File not found.
+#define ERR_FILE_TOO_MANY_OPEN -1074395994  // Too many files open.
+#define ERR_FILE_IO_ERR -1074395993         // File I/O error.
+#define ERR_FILE_PERMISSION -1074395992     // File access denied.
+#define ERR_FILE_INVALID_TYPE \
+  -1074395991  // NI Vision does not support the file type you specified.
+#define ERR_FILE_GET_INFO -1074395990   // Could not read Vision info from file.
+#define ERR_FILE_READ -1074395989       // Unable to read data.
+#define ERR_FILE_WRITE -1074395988      // Unable to write data.
+#define ERR_FILE_EOF -1074395987        // Premature end of file.
+#define ERR_FILE_FORMAT -1074395986     // Invalid file format.
+#define ERR_FILE_OPERATION -1074395985  // Invalid file operation.
+#define ERR_FILE_INVALID_DATA_TYPE \
+  -1074395984  // NI Vision does not support the file data type you specified.
+#define ERR_FILE_NO_SPACE -1074395983  // Disk full.
+#define ERR_INVALID_FRAMES_PER_SECOND \
+  -1074395982  // The frames per second in an AVI must be greater than zero.
+#define ERR_INSUFFICIENT_BUFFER_SIZE \
+  -1074395981  // The buffer that was passed in is not big enough to hold all of
+               // the data.
+#define ERR_COM_INITIALIZE -1074395980  // Error initializing COM.
+#define ERR_INVALID_PARTICLE_INFO \
+  -1074395979  // The image has invalid particle information.  Call
+               // imaqCountParticles on the image to create particle
+               // information.
+#define ERR_INVALID_PARTICLE_NUMBER -1074395978  // Invalid particle number.
+#define ERR_AVI_VERSION \
+  -1074395977  // The AVI file was created in a newer version of NI Vision.
+               // Upgrade to the latest version of NI Vision to read this AVI
+               // file.
+#define ERR_NUMBER_OF_PALETTE_COLORS \
+  -1074395976  // The color palette must have exactly 0 or 256 entries.
+#define ERR_AVI_TIMEOUT \
+  -1074395975  // DirectX has timed out reading or writing the AVI file.  When
+               // closing an AVI file, try adding an additional delay.  When
+               // reading an AVI file, try reducing CPU and disk load.
+#define ERR_UNSUPPORTED_JPEG2000_COLORSPACE_METHOD \
+  -1074395974  // NI Vision does not support reading JPEG2000 files with this
+               // colorspace method.
+#define ERR_JPEG2000_UNSUPPORTED_MULTIPLE_LAYERS \
+  -1074395973  // NI Vision does not support reading JPEG2000 files with more
+               // than one layer.
+#define ERR_DIRECTX_ENUMERATE_FILTERS \
+  -1074395972  // DirectX is unable to enumerate the compression filters. This
+               // is caused by a third-party compression filter that is either
+               // improperly installed or is preventing itself from being
+               // enumerated. Remove any recently installed compression filters
+               // and try again.
+#define ERR_INVALID_OFFSET \
+  -1074395971                 // The offset you specified must be size 2.
+#define ERR_INIT -1074395960  // Initialization error.
+#define ERR_CREATE_WINDOW -1074395959  // Unable to create window.
+#define ERR_WINDOW_ID -1074395958      // Invalid window ID.
+#define ERR_ARRAY_SIZE_MISMATCH \
+  -1074395957  // The array sizes are not compatible.
+#define ERR_INVALID_QUALITY \
+  -1074395956  // The quality you provided is invalid. Valid quality values
+               // range from -1 to 1000.
+#define ERR_INVALID_MAX_WAVELET_TRANSFORM_LEVEL \
+  -1074395955  // Invalid maximum wavelet transform level.  Valid values range
+               // from 0 to 255.
+#define ERR_INVALID_QUANTIZATION_STEP_SIZE \
+  -1074395954  // The quantization step size must be greater than or equal to 0.
+#define ERR_INVALID_WAVELET_TRANSFORM_MODE \
+  -1074395953  // Invalid wavelet transform mode.
+#define ERR_ROI_NOT_POINT \
+  -1074395952  // The ROI must only have a single Point contour.
+#define ERR_ROI_NOT_POINTS \
+  -1074395951  // The ROI must only have Point contours.
+#define ERR_ROI_NOT_LINE \
+  -1074395950  // The ROI must only have a single Line contour.
+#define ERR_ROI_NOT_ANNULUS \
+  -1074395949  // The ROI must only have a single Annulus contour.
+#define ERR_INVALID_MEASURE_PARTICLES_CALIBRATION_MODE \
+  -1074395948  // Invalid measure particles calibration mode.
+#define ERR_INVALID_PARTICLE_CLASSIFIER_THRESHOLD_TYPE \
+  -1074395947  // Invalid particle classifier threshold type.
+#define ERR_INVALID_DISTANCE -1074395946  // Invalid Color Segmentation Distance
+#define ERR_INVALID_PARTICLE_AREA \
+  -1074395945  // Invalid Color Segmenation Particle Area
+#define ERR_CLASS_NAME_NOT_FOUND \
+  -1074395944  // Required Class name is not found in trained labels/Class names
+#define ERR_NUMBER_LABEL_LIMIT_EXCEEDED \
+  -1074395943  // Number of Labels exceeded limit of label Image type
+#define ERR_INVALID_DISTANCE_LEVEL \
+  -1074395942  // Invalid Color Segmentation distance level
+#define ERR_INVALID_SVM_TYPE -1074395941    // Invalid SVM model type
+#define ERR_INVALID_SVM_KERNEL -1074395940  // Invalid SVM kernel type
+#define ERR_NO_SUPPORT_VECTOR_FOUND \
+  -1074395939  // No Support Vector is found at SVM training
+#define ERR_COST_LABEL_NOT_FOUND \
+  -1074395938  // Label name is not found in added samples
+#define ERR_EXCEEDED_SVM_MAX_ITERATION \
+  -1074395937  // SVM training exceeded maximim Iteration limit
+#define ERR_INVALID_SVM_PARAMETER -1074395936  // Invalid SVM Parameter
+#define ERR_INVALID_IDENTIFICATION_SCORE \
+  -1074395935  // Invalid Identification score. Must be between 0-1000.
+#define ERR_INVALID_TEXTURE_FEATURE \
+  -1074395934  // Requested for invalid texture feature
+#define ERR_INVALID_COOCCURRENCE_LEVEL \
+  -1074395933  // The coOccurrence Level must lie between 1 and the maximum
+               // pixel value of an image (255 for U8 image)
+#define ERR_INVALID_WAVELET_SUBBAND \
+  -1074395932  // Request for invalid wavelet subBand
+#define ERR_INVALID_FINAL_STEP_SIZE \
+  -1074395931  // The final step size must be lesser than the initial step size
+#define ERR_INVALID_ENERGY \
+  -1074395930  // Minimum Energy should lie between 0 and 100
+#define ERR_INVALID_TEXTURE_LABEL \
+  -1074395929  // The classification label must be texture or defect for texture
+               // defect classifier
+#define ERR_INVALID_WAVELET_TYPE -1074395928  // The wavelet type is invalid
+#define ERR_SAME_WAVELET_BANDS_SELECTED \
+  -1074395927  // Same Wavelet band is selected multiple times
+#define ERR_IMAGE_SIZE_MISMATCH \
+  -1074395926                         // The two input image sizes are different
+#define ERR_NUMBER_CLASS -1074395920  // Invalid number of classes.
+#define ERR_INVALID_LUCAS_KANADE_WINDOW_SIZE \
+  -1074395888  // Both dimensions of the window size should be odd, greater than
+               // 2 and less than 16.
+#define ERR_INVALID_MATRIX_TYPE \
+  -1074395887  // The type of matrix supplied to the function is not supported.
+#define ERR_INVALID_OPTICAL_FLOW_TERMINATION_CRITERIA_TYPE \
+  -1074395886  // An invalid termination criteria was specified for the optical
+               // flow computation.
+#define ERR_LKP_NULL_PYRAMID \
+  -1074395885  // The pyramid levels where not properly allocated.
+#define ERR_INVALID_PYRAMID_LEVEL \
+  -1074395884  // The pyramid level specified cannot be negative
+#define ERR_INVALID_LKP_KERNEL \
+  -1074395883  // The kernel must be symmetric  with non-zero coefficients and
+               // of odd size
+#define ERR_INVALID_HORN_SCHUNCK_LAMBDA \
+  -1074395882  // Invalid smoothing parameter in Horn Schunck operation.
+#define ERR_INVALID_HORN_SCHUNCK_TYPE \
+  -1074395881  // Invalid stopping criteria type for Horn Schunck optical flow.
+#define ERR_PARTICLE -1074395880     // Invalid particle.
+#define ERR_BAD_MEASURE -1074395879  // Invalid measure number.
+#define ERR_PROP_NODE_WRITE_NOT_SUPPORTED \
+  -1074395878  // The Image Display control does not support writing this
+               // property node.
+#define ERR_COLORMODE_REQUIRES_CHANGECOLORSPACE2 \
+  -1074395877  // The specified color mode requires the use of
+               // imaqChangeColorSpace2.
+#define ERR_UNSUPPORTED_COLOR_MODE \
+  -1074395876  // This function does not currently support the color mode you
+               // specified.
+#define ERR_BARCODE_PHARMACODE \
+  -1074395875  // The barcode is not a valid Pharmacode symbol
+#define ERR_BAD_INDEX -1074395840  // Invalid handle table index.
+#define ERR_INVALID_COMPRESSION_RATIO \
+  -1074395837  // The compression ratio must be greater than or equal to 1.
+#define ERR_TOO_MANY_CONTOURS \
+  -1074395801                       // The ROI contains too many contours.
+#define ERR_PROTECTION -1074395800  // Protection error.
+#define ERR_INTERNAL -1074395799    // Internal error.
+#define ERR_INVALID_CUSTOM_SAMPLE \
+  -1074395798  // The size of the feature vector in the custom sample must match
+               // the size of those you have already added.
+#define ERR_INVALID_CLASSIFIER_SESSION \
+  -1074395797  // Not a valid classifier session.
+#define ERR_INVALID_KNN_METHOD \
+  -1074395796  // You requested an invalid Nearest Neighbor classifier method.
+#define ERR_K_TOO_LOW -1074395795  // The k parameter must be greater than two.
+#define ERR_K_TOO_HIGH \
+  -1074395794  // The k parameter must be <= the number of samples in each
+               // class.
+#define ERR_INVALID_OPERATION_ON_COMPACT_SESSION_ATTEMPTED \
+  -1074395793  // This classifier session is compact. Only the Classify and
+               // Dispose functions may be called on a compact classifier
+               // session.
+#define ERR_CLASSIFIER_SESSION_NOT_TRAINED \
+  -1074395792  // This classifier session is not trained. You may only call this
+               // function on a trained classifier session.
+#define ERR_CLASSIFIER_INVALID_SESSION_TYPE \
+  -1074395791  // This classifier function cannot be called on this type of
+               // classifier session.
+#define ERR_INVALID_DISTANCE_METRIC \
+  -1074395790  // You requested an invalid distance metric.
+#define ERR_OPENING_NEWER_CLASSIFIER_SESSION \
+  -1074395789  // The classifier session you tried to open was created with a
+               // newer version of NI Vision. Upgrade to the latest version of
+               // NI Vision to read this file.
+#define ERR_NO_SAMPLES \
+  -1074395788  // This operation cannot be performed because you have not added
+               // any samples.
+#define ERR_INVALID_CLASSIFIER_TYPE \
+  -1074395787  // You requested an invalid classifier type.
+#define ERR_INVALID_PARTICLE_OPTIONS \
+  -1074395786  // The sum of Scale Dependence and Symmetry Dependence must be
+               // less than 1000.
+#define ERR_NO_PARTICLE -1074395785  // The image yielded no particles.
+#define ERR_INVALID_LIMITS \
+  -1074395784  // The limits you supplied are not valid.
+#define ERR_BAD_SAMPLE_INDEX \
+  -1074395783  // The Sample Index fell outside the range of Samples.
+#define ERR_DESCRIPTION_TOO_LONG \
+  -1074395782  // The description must be <= 255 characters.
+#define ERR_CLASSIFIER_INVALID_ENGINE_TYPE \
+  -1074395781  // The engine for this classifier session does not support this
+               // operation.
+#define ERR_INVALID_PARTICLE_TYPE \
+  -1074395780  // You requested an invalid particle type.
+#define ERR_CANNOT_COMPACT_UNTRAINED \
+  -1074395779  // You may only save a session in compact form if it is trained.
+#define ERR_INVALID_KERNEL_SIZE \
+  -1074395778  // The Kernel size must be smaller than the image size.
+#define ERR_INCOMPATIBLE_CLASSIFIER_TYPES \
+  -1074395777  // The session you read from file must be the same type as the
+               // session you passed in.
+#define ERR_INVALID_USE_OF_COMPACT_SESSION_FILE \
+  -1074395776  // You can not use a compact classification file with read
+               // options other than Read All.
+#define ERR_ROI_HAS_OPEN_CONTOURS \
+  -1074395775  // The ROI you passed in may only contain closed contours.
+#define ERR_NO_LABEL -1074395774       // You must pass in a label.
+#define ERR_NO_DEST_IMAGE -1074395773  // You must provide a destination image.
+#define ERR_INVALID_REGISTRATION_METHOD \
+  -1074395772  // You provided an invalid registration method.
+#define ERR_OPENING_NEWER_INSPECTION_TEMPLATE \
+  -1074395771  // The golden template you tried to open was created with a newer
+               // version of NI Vision. Upgrade to the latest version of NI
+               // Vision to read this file.
+#define ERR_INVALID_INSPECTION_TEMPLATE -1074395770  // Invalid golden template.
+#define ERR_INVALID_EDGE_THICKNESS \
+  -1074395769  // Edge Thickness to Ignore must be greater than zero.
+#define ERR_INVALID_SCALE -1074395768  // Scale must be greater than zero.
+#define ERR_INVALID_ALIGNMENT \
+  -1074395767  // The supplied scale is invalid for your template.
+#define ERR_DEPRECATED_FUNCTION \
+  -1074395766  // This backwards-compatibility function can not be used with
+               // this session. Use newer, supported functions instead.
+#define ERR_INVALID_NORMALIZATION_METHOD \
+  -1074395763  // You must provide a valid normalization method.
+#define ERR_INVALID_NIBLACK_DEVIATION_FACTOR \
+  -1074395762  // The deviation factor for Niblack local threshold must be
+               // between 0 and 1.
+#define ERR_BOARD_NOT_FOUND -1074395760         // Board not found.
+#define ERR_BOARD_NOT_OPEN -1074395758          // Board not opened.
+#define ERR_DLL_NOT_FOUND -1074395757           // DLL not found.
+#define ERR_DLL_FUNCTION_NOT_FOUND -1074395756  // DLL function not found.
+#define ERR_TRIG_TIMEOUT -1074395754            // Trigger timeout.
+#define ERR_CONTOUR_INVALID_REFINEMENTS \
+  -1074395746  // Invalid number specified for maximum contour refinements.
+#define ERR_TOO_MANY_CURVES \
+  -1074395745  // Too many curves extracted from image. Raise the edge threshold
+               // or reduce the ROI.
+#define ERR_CONTOUR_INVALID_KERNEL_FOR_SMOOTHING \
+  -1074395744  // Invalid kernel for contour smoothing. Zero indicates no
+               // smoothing, otherwise value must be odd.
+#define ERR_CONTOUR_LINE_INVALID \
+  -1074395743  // The contour line fit is invalid. Line segment start and stop
+               // must differ.
+#define ERR_CONTOUR_TEMPLATE_IMAGE_INVALID \
+  -1074395742  // The template image must be trained with IMAQ Learn Contour
+               // Pattern or be the same size as the target image.
+#define ERR_CONTOUR_GPM_FAIL \
+  -1074395741  // Matching failed to align the template and target contours.
+#define ERR_CONTOUR_OPENING_NEWER_VERSION \
+  -1074395740  // The contour you tried to open was created with a newer version
+               // of NI Vision. Upgrade to the latest version of NI Vision to
+               // read this file.
+#define ERR_CONTOUR_CONNECT_DUPLICATE \
+  -1074395739  // Only one range is allowed per curve connection constraint
+               // type.
+#define ERR_CONTOUR_CONNECT_TYPE \
+  -1074395738  // Invalid contour connection constraint type.
+#define ERR_CONTOUR_MATCH_STR_NOT_APPLICABLE \
+  -1074395737  // In order to use contour matching, you must provide a template
+               // image that has been trained with IMAQ Learn Contour Pattern
+#define ERR_CONTOUR_CURVATURE_KERNEL \
+  -1074395736  // Invalid kernel width for curvature calculation. Must be an odd
+               // value greater than 1.
+#define ERR_CONTOUR_EXTRACT_SELECTION \
+  -1074395735  // Invalid Contour Selection method for contour extraction.
+#define ERR_CONTOUR_EXTRACT_DIRECTION \
+  -1074395734  // Invalid Search Direction for contour extraction.
+#define ERR_CONTOUR_EXTRACT_ROI \
+  -1074395733  // Invalid ROI for contour extraction. The ROI must contain an
+               // annulus, rectangle or rotated rectangle.
+#define ERR_CONTOUR_NO_CURVES -1074395732  // No curves were found in the image.
+#define ERR_CONTOUR_COMPARE_KERNEL \
+  -1074395731  // Invalid Smoothing Kernel width for contour comparison. Must be
+               // zero or an odd positive integer.
+#define ERR_CONTOUR_COMPARE_SINGLE_IMAGE \
+  -1074395730  // If no template image is provided, the target image must
+               // contain both a contour with extracted points and a fitted
+               // equation.
+#define ERR_CONTOUR_INVALID -1074395729  // Invalid contour image.
+#define ERR_INVALID_2D_BARCODE_SEARCH_MODE \
+  -1074395728  // NI Vision does not support the search mode you provided.
+#define ERR_UNSUPPORTED_2D_BARCODE_SEARCH_MODE \
+  -1074395727  // NI Vision does not support the search mode you provided for
+               // the type of 2D barcode for which you are searching.
+#define ERR_MATCHFACTOR_OBSOLETE \
+  -1074395726  // matchFactor has been obsoleted. Instead, set the
+               // initialMatchListLength and matchListReductionFactor in the
+               // MatchPatternAdvancedOptions structure.
+#define ERR_DATA_VERSION \
+  -1074395725  // The data was stored with a newer version of NI Vision. Upgrade
+               // to the latest version of NI Vision to read this data.
+#define ERR_CUSTOMDATA_INVALID_SIZE \
+  -1074395724  // The size you specified is out of the valid range.
+#define ERR_CUSTOMDATA_KEY_NOT_FOUND \
+  -1074395723  // The key you specified cannot be found in the image.
+#define ERR_CLASSIFIER_CLASSIFY_IMAGE_WITH_CUSTOM_SESSION \
+  -1074395722  // Custom classifier sessions only classify feature vectors. They
+               // do not support classifying images.
+#define ERR_INVALID_BIT_DEPTH \
+  -1074395721  // NI Vision does not support the bit depth you supplied for the
+               // image you supplied.
+#define ERR_BAD_ROI -1074395720      // Invalid ROI.
+#define ERR_BAD_ROI_BOX -1074395719  // Invalid ROI global rectangle.
+#define ERR_LAB_VERSION \
+  -1074395718  // The version of LabVIEW or BridgeVIEW you are running does not
+               // support this operation.
+#define ERR_INVALID_RANGE -1074395717  // The range you supplied is invalid.
+#define ERR_INVALID_SCALING_METHOD \
+  -1074395716  // NI Vision does not support the scaling method you provided.
+#define ERR_INVALID_CALIBRATION_UNIT \
+  -1074395715  // NI Vision does not support the calibration unit you supplied.
+#define ERR_INVALID_AXIS_ORIENTATION \
+  -1074395714  // NI Vision does not support the axis orientation you supplied.
+#define ERR_VALUE_NOT_IN_ENUM -1074395713  // Value not in enumeration.
+#define ERR_WRONG_REGION_TYPE \
+  -1074395712  // You selected a region that is not of the right type.
+#define ERR_NOT_ENOUGH_REGIONS \
+  -1074395711  // You specified a viewer that does not contain enough regions.
+#define ERR_TOO_MANY_PARTICLES \
+  -1074395710  // The image has too many particles for this process.
+#define ERR_AVI_UNOPENED_SESSION \
+  -1074395709  // The AVI session has not been opened.
+#define ERR_AVI_READ_SESSION_REQUIRED \
+  -1074395708  // The AVI session is a write session, but this operation
+               // requires a read session.
+#define ERR_AVI_WRITE_SESSION_REQUIRED \
+  -1074395707  // The AVI session is a read session, but this operation requires
+               // a write session.
+#define ERR_AVI_SESSION_ALREADY_OPEN \
+  -1074395706  // This AVI session is already open. You must close it before
+               // calling the Create or Open functions.
+#define ERR_DATA_CORRUPTED \
+  -1074395705  // The data is corrupted and cannot be read.
+#define ERR_INVALID_COMPRESSION_TYPE -1074395704  // Invalid compression type.
+#define ERR_INVALID_TYPE_OF_FLATTEN -1074395703   // Invalid type of flatten.
+#define ERR_INVALID_LENGTH \
+  -1074395702  // The length of the edge detection line must be greater than
+               // zero.
+#define ERR_INVALID_MATRIX_SIZE_RANGE \
+  -1074395701  // The maximum Data Matrix barcode size must be equal to or
+               // greater than the minimum Data Matrix barcode size.
+#define ERR_REQUIRES_WIN2000_OR_NEWER \
+  -1074395700  // The function requires the operating system to be Microsoft
+               // Windows 2000 or newer.
+#define ERR_INVALID_CALIBRATION_METHOD \
+  -1074395662  // Invalid calibration method requested
+#define ERR_INVALID_OPERATION_ON_COMPACT_CALIBRATION_ATTEMPTED \
+  -1074395661  // This calibration is compact. Re-Learning calibration and
+               // retrieving thumbnails are not possible with this calibration
+#define ERR_INVALID_POLYNOMIAL_MODEL_K_COUNT \
+  -1074395660  // Invalid number of K values
+#define ERR_INVALID_DISTORTION_MODEL \
+  -1074395659  // Invalid distortion model type
+#define ERR_CAMERA_MODEL_NOT_AVAILABLE \
+  -1074395658  // Camera Model is not learned
+#define ERR_INVALID_THUMBNAIL_INDEX \
+  -1074395657  // Supplied thumbnail index is invalid
+#define ERR_SMOOTH_CONTOURS_MUST_BE_SAME \
+  -1074395656  // You must specify the same value for the smooth contours
+               // advanced match option for all templates you want to match.
+#define ERR_ENABLE_CALIBRATION_SUPPORT_MUST_BE_SAME \
+  -1074395655  // You must specify the same value for the enable calibration
+               // support advanced match option for all templates you want to
+               // match.
+#define ERR_GRADING_INFORMATION_NOT_FOUND \
+  -1074395654  // The source image does not contain grading information. You
+               // must prepare the source image for grading when reading the
+               // Data Matrix, and you cannot change the contents of the source
+               // image between reading and grading the Data Matrix.
+#define ERR_OPENING_NEWER_MULTIPLE_GEOMETRIC_TEMPLATE \
+  -1074395653  // The multiple geometric matching template you tried to open was
+               // created with a newer version of NI Vision. Upgrade to the
+               // latest version of NI Vision to read this file.
+#define ERR_OPENING_NEWER_GEOMETRIC_MATCHING_TEMPLATE \
+  -1074395652  // The geometric matching template you tried to open was created
+               // with a newer version of NI Vision. Upgrade to the latest
+               // version of NI Vision to read this file.
+#define ERR_EDGE_FILTER_SIZE_MUST_BE_SAME \
+  -1074395651  // You must specify the same edge filter size for all the
+               // templates you want to match.
+#define ERR_CURVE_EXTRACTION_MODE_MUST_BE_SAME \
+  -1074395650  // You must specify the same curve extraction mode for all the
+               // templates you want to match.
+#define ERR_INVALID_GEOMETRIC_FEATURE_TYPE \
+  -1074395649  // The geometric feature type specified is invalid.
+#define ERR_TEMPLATE_NOT_LEARNED \
+  -1074395648  // You supplied a template that was not learned.
+#define ERR_INVALID_MULTIPLE_GEOMETRIC_TEMPLATE \
+  -1074395647  // Invalid multiple geometric template.
+#define ERR_NO_TEMPLATE_TO_LEARN \
+  -1074395646  // Need at least one template to learn.
+#define ERR_INVALID_NUMBER_OF_LABELS \
+  -1074395645  // You supplied an invalid number of labels.
+#define ERR_LABEL_TOO_LONG -1074395644  // Labels must be <= 255 characters.
+#define ERR_INVALID_NUMBER_OF_MATCH_OPTIONS \
+  -1074395643  // You supplied an invalid number of match options.
+#define ERR_LABEL_NOT_FOUND \
+  -1074395642  // Cannot find a label that matches the one you specified.
+#define ERR_DUPLICATE_LABEL -1074395641  // Duplicate labels are not allowed.
+#define ERR_TOO_MANY_ZONES \
+  -1074395640  // The number of zones found exceeded the capacity of the
+               // algorithm.
+#define ERR_INVALID_HATCH_STYLE \
+  -1074395639  // The hatch style for the window background is invalid.
+#define ERR_INVALID_FILL_STYLE \
+  -1074395638  // The fill style for the window background is invalid.
+#define ERR_HARDWARE_DOESNT_SUPPORT_NONTEARING \
+  -1074395637  // Your hardware is not supported by DirectX and cannot be put
+               // into NonTearing mode.
+#define ERR_DIRECTX_NOT_FOUND \
+  -1074395636  // DirectX is required for this feature.  Please install the
+               // latest version..
+#define ERR_INVALID_SHAPE_DESCRIPTOR \
+  -1074395635  // The passed shape descriptor is invalid.
+#define ERR_INVALID_MAX_MATCH_OVERLAP \
+  -1074395634  // Invalid max match overlap.  Values must be between -1 and 100.
+#define ERR_INVALID_MIN_MATCH_SEPARATION_SCALE \
+  -1074395633  // Invalid minimum match separation scale.  Values must be
+               // greater than or equal to -1.
+#define ERR_INVALID_MIN_MATCH_SEPARATION_ANGLE \
+  -1074395632  // Invalid minimum match separation angle.  Values must be
+               // between -1 and 360.
+#define ERR_INVALID_MIN_MATCH_SEPARATION_DISTANCE \
+  -1074395631  // Invalid minimum match separation distance.  Values must be
+               // greater than or equal to -1.
+#define ERR_INVALID_MAXIMUM_FEATURES_LEARNED \
+  -1074395630  // Invalid maximum number of features learn. Values must be
+               // integers greater than zero.
+#define ERR_INVALID_MAXIMUM_PIXEL_DISTANCE_FROM_LINE \
+  -1074395629  // Invalid maximum pixel distance from line. Values must be
+               // positive real numbers.
+#define ERR_INVALID_GEOMETRIC_MATCHING_TEMPLATE \
+  -1074395628  // Invalid geometric matching template image.
+#define ERR_NOT_ENOUGH_TEMPLATE_FEATURES_1 \
+  -1074395627  // The template does not contain enough features for geometric
+               // matching.
+#define ERR_NOT_ENOUGH_TEMPLATE_FEATURES \
+  -1074395626  // The template does not contain enough features for geometric
+               // matching.
+#define ERR_INVALID_MATCH_CONSTRAINT_TYPE \
+  -1074395625  // You specified an invalid value for the match constraint value
+               // of the  range settings.
+#define ERR_INVALID_OCCLUSION_RANGE \
+  -1074395624  // Invalid occlusion range. Valid values for the bounds range
+               // from 0 to 100 and the upper bound must be greater than or
+               // equal to the lower bound.
+#define ERR_INVALID_SCALE_RANGE \
+  -1074395623  // Invalid scale range. Values for the lower bound must be a
+               // positive real numbers and the upper bound must be greater than
+               // or equal to the lower bound.
+#define ERR_INVALID_MATCH_GEOMETRIC_PATTERN_SETUP_DATA \
+  -1074395622  // Invalid match geometric pattern setup data.
+#define ERR_INVALID_LEARN_GEOMETRIC_PATTERN_SETUP_DATA \
+  -1074395621  // Invalid learn geometric pattern setup data.
+#define ERR_INVALID_CURVE_EXTRACTION_MODE \
+  -1074395620  // Invalid curve extraction mode.
+#define ERR_TOO_MANY_OCCLUSION_RANGES \
+  -1074395619  // You can specify only one occlusion range.
+#define ERR_TOO_MANY_SCALE_RANGES \
+  -1074395618  // You can specify only one scale range.
+#define ERR_INVALID_NUMBER_OF_FEATURES_RANGE \
+  -1074395617  // The minimum number of features must be less than or equal to
+               // the maximum number of features.
+#define ERR_INVALID_EDGE_FILTER_SIZE -1074395616  // Invalid edge filter size.
+#define ERR_INVALID_MINIMUM_FEATURE_STRENGTH \
+  -1074395615  // Invalid minimum strength for features. Values must be positive
+               // real numbers.
+#define ERR_INVALID_MINIMUM_FEATURE_ASPECT_RATIO \
+  -1074395614  // Invalid aspect ratio for rectangular features. Values must be
+               // positive real numbers in the range 0.01 to 1.0.
+#define ERR_INVALID_MINIMUM_FEATURE_LENGTH \
+  -1074395613  // Invalid minimum length for linear features. Values must be
+               // integers greater than 0.
+#define ERR_INVALID_MINIMUM_FEATURE_RADIUS \
+  -1074395612  // Invalid minimum radius for circular features. Values must be
+               // integers greater than 0.
+#define ERR_INVALID_MINIMUM_RECTANGLE_DIMENSION \
+  -1074395611  // Invalid minimum rectangle dimension. Values must be integers
+               // greater than 0.
+#define ERR_INVALID_INITIAL_MATCH_LIST_LENGTH \
+  -1074395610  // Invalid initial match list length. Values must be integers
+               // greater than 5.
+#define ERR_INVALID_SUBPIXEL_TOLERANCE \
+  -1074395609  // Invalid subpixel tolerance. Values must be positive real
+               // numbers.
+#define ERR_INVALID_SUBPIXEL_ITERATIONS \
+  -1074395608  // Invalid number of subpixel iterations. Values must be integers
+               // greater 10.
+#define ERR_INVALID_MAXIMUM_FEATURES_PER_MATCH \
+  -1074395607  // Invalid maximum number of features used per match. Values must
+               // be integers greater than or equal to zero.
+#define ERR_INVALID_MINIMUM_FEATURES_TO_MATCH \
+  -1074395606  // Invalid minimum number of features used for matching. Values
+               // must be integers greater than zero.
+#define ERR_INVALID_MAXIMUM_END_POINT_GAP \
+  -1074395605  // Invalid maximum end point gap. Valid values range from 0 to
+               // 32767.
+#define ERR_INVALID_COLUMN_STEP \
+  -1074395604  // Invalid column step. Valid range is 1 to 255.
+#define ERR_INVALID_ROW_STEP \
+  -1074395603  // Invalid row step. Valid range is 1 to 255.
+#define ERR_INVALID_MINIMUM_CURVE_LENGTH \
+  -1074395602  // Invalid minimum length. Valid values must be greater than or
+               // equal to zero.
+#define ERR_INVALID_EDGE_THRESHOLD \
+  -1074395601  // Invalid edge threshold. Valid values range from 1 to 360.
+#define ERR_INFO_NOT_FOUND \
+  -1074395600  // You must provide information about the subimage within the
+               // browser.
+#define ERR_NIOCR_INVALID_ACCEPTANCE_LEVEL \
+  -1074395598  // The acceptance level is outside the valid range of  0 to 1000.
+#define ERR_NIOCR_NOT_A_VALID_SESSION -1074395597  // Not a valid OCR session.
+#define ERR_NIOCR_INVALID_CHARACTER_SIZE \
+  -1074395596  // Invalid character size. Character size must be >= 1.
+#define ERR_NIOCR_INVALID_THRESHOLD_MODE \
+  -1074395595  // Invalid threshold mode value.
+#define ERR_NIOCR_INVALID_SUBSTITUTION_CHARACTER \
+  -1074395594  // Invalid substitution character. Valid substitution characters
+               // are ASCII values that range from 1 to 254.
+#define ERR_NIOCR_INVALID_NUMBER_OF_BLOCKS \
+  -1074395593  // Invalid number of blocks. Number of blocks must be >= 4 and <=
+               // 50.
+#define ERR_NIOCR_INVALID_READ_STRATEGY -1074395592  // Invalid read strategy.
+#define ERR_NIOCR_INVALID_CHARACTER_INDEX \
+  -1074395591  // Invalid character index.
+#define ERR_NIOCR_INVALID_NUMBER_OF_VALID_CHARACTER_POSITIONS \
+  -1074395590  // Invalid number of character positions. Valid values range from
+               // 0 to 255.
+#define ERR_NIOCR_INVALID_LOW_THRESHOLD_VALUE \
+  -1074395589  // Invalid low threshold value. Valid threshold values range from
+               // 0 to 255.
+#define ERR_NIOCR_INVALID_HIGH_THRESHOLD_VALUE \
+  -1074395588  // Invalid high threshold value. Valid threshold values range
+               // from 0 to 255.
+#define ERR_NIOCR_INVALID_THRESHOLD_RANGE \
+  -1074395587  // The low threshold must be less than the high threshold.
+#define ERR_NIOCR_INVALID_LOWER_THRESHOLD_LIMIT \
+  -1074395586  // Invalid lower threshold limit. Valid lower threshold limits
+               // range from 0 to 255.
+#define ERR_NIOCR_INVALID_UPPER_THRESHOLD_LIMIT \
+  -1074395585  // Invalid upper threshold limit. Valid upper threshold limits
+               // range from 0 to 255.
+#define ERR_NIOCR_INVALID_THRESHOLD_LIMITS \
+  -1074395584  // The lower threshold limit must be less than the upper
+               // threshold limit.
+#define ERR_NIOCR_INVALID_MIN_CHAR_SPACING \
+  -1074395583  // Invalid minimum character spacing value. Character spacing
+               // must be >= 1 pixel.
+#define ERR_NIOCR_INVALID_MAX_HORIZ_ELEMENT_SPACING \
+  -1074395582  // Invalid maximum horizontal element spacing value. Maximum
+               // horizontal element spacing must be >= 0.
+#define ERR_NIOCR_INVALID_MAX_VERT_ELEMENT_SPACING \
+  -1074395581  // Invalid maximum vertical element spacing value. Maximum
+               // vertical element spacing must be >= 0.
+#define ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_WIDTH \
+  -1074395580  // Invalid minimum bounding rectangle width. Minimum bounding
+               // rectangle width must be >= 1.
+#define ERR_NIOCR_INVALID_ASPECT_RATIO \
+  -1074395579  // Invalid aspect ratio value. The aspect ratio must be zero or
+               // >= 100.
+#define ERR_NIOCR_INVALID_CHARACTER_SET_FILE \
+  -1074395578  // Invalid or corrupt character set file.
+#define ERR_NIOCR_CHARACTER_VALUE_CANNOT_BE_EMPTYSTRING \
+  -1074395577  // The character value must not be an empty string.
+#define ERR_NIOCR_CHARACTER_VALUE_TOO_LONG \
+  -1074395576  // Character values must be <=255 characters.
+#define ERR_NIOCR_INVALID_NUMBER_OF_EROSIONS \
+  -1074395575  // Invalid number of erosions. The number of erosions must be >=
+               // 0.
+#define ERR_NIOCR_CHARACTER_SET_DESCRIPTION_TOO_LONG \
+  -1074395574  // The character set description must be <=255 characters.
+#define ERR_NIOCR_INVALID_CHARACTER_SET_FILE_VERSION \
+  -1074395573  // The character set file was created by a newer version of NI
+               // Vision. Upgrade to the latest version of NI Vision to read the
+               // character set file.
+#define ERR_NIOCR_INTEGER_VALUE_FOR_STRING_ATTRIBUTE \
+  -1074395572  // You must specify characters for a string. A string cannot
+               // contain integers.
+#define ERR_NIOCR_GET_ONLY_ATTRIBUTE \
+  -1074395571  // This attribute is read-only.
+#define ERR_NIOCR_INTEGER_VALUE_FOR_BOOLEAN_ATTRIBUTE \
+  -1074395570  // This attribute requires a Boolean value.
+#define ERR_NIOCR_INVALID_ATTRIBUTE -1074395569  // Invalid attribute.
+#define ERR_NIOCR_STRING_VALUE_FOR_INTEGER_ATTRIBUTE \
+  -1074395568  // This attribute requires integer values.
+#define ERR_NIOCR_STRING_VALUE_FOR_BOOLEAN_ATTRIBUTE \
+  -1074395567  // String values are invalid for this attribute. Enter a boolean
+               // value.
+#define ERR_NIOCR_BOOLEAN_VALUE_FOR_INTEGER_ATTRIBUTE \
+  -1074395566  // Boolean values are not valid for this attribute. Enter an
+               // integer value.
+#define ERR_NIOCR_MUST_BE_SINGLE_CHARACTER \
+  -1074395565  // Requires a single-character string.
+#define ERR_NIOCR_INVALID_PREDEFINED_CHARACTER \
+  -1074395564                             // Invalid predefined character value.
+#define ERR_NIOCR_UNLICENSED -1074395563  // This copy of NI OCR is unlicensed.
+#define ERR_NIOCR_BOOLEAN_VALUE_FOR_STRING_ATTRIBUTE \
+  -1074395562  // String values are not valid for this attribute. Enter a
+               // Boolean value.
+#define ERR_NIOCR_INVALID_NUMBER_OF_CHARACTERS \
+  -1074395561  // The number of characters in the character value must match the
+               // number of objects in the image.
+#define ERR_NIOCR_INVALID_OBJECT_INDEX -1074395560  // Invalid object index.
+#define ERR_NIOCR_INVALID_READ_OPTION -1074395559   // Invalid read option.
+#define ERR_NIOCR_INVALID_CHARACTER_SIZE_RANGE \
+  -1074395558  // The minimum character size must be less than the maximum
+               // character size.
+#define ERR_NIOCR_INVALID_BOUNDING_RECT_WIDTH_RANGE \
+  -1074395557  // The minimum character bounding rectangle width must be less
+               // than the maximum character bounding rectangle width.
+#define ERR_NIOCR_INVALID_BOUNDING_RECT_HEIGHT_RANGE \
+  -1074395556  // The minimum character bounding rectangle height must be less
+               // than the maximum character bounding rectangle height.
+#define ERR_NIOCR_INVALID_SPACING_RANGE \
+  -1074395555  // The maximum horizontal element spacing value must not exceed
+               // the minimum character spacing value.
+#define ERR_NIOCR_INVALID_READ_RESOLUTION \
+  -1074395554  // Invalid read resolution.
+#define ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_HEIGHT \
+  -1074395553  // Invalid minimum bounding rectangle height. The minimum
+               // bounding rectangle height must be >= 1.
+#define ERR_NIOCR_NOT_A_VALID_CHARACTER_SET \
+  -1074395552  // Not a valid character set.
+#define ERR_NIOCR_RENAME_REFCHAR \
+  -1074395551  // A trained OCR character cannot be renamed while it is a
+               // reference character.
+#define ERR_NIOCR_INVALID_CHARACTER_VALUE \
+  -1074395550  // A character cannot have an ASCII value of 255.
+#define ERR_NIOCR_INVALID_NUMBER_OF_OBJECTS_TO_VERIFY \
+  -1074395549  // The number of objects found does not match the number of
+               // expected characters or patterns to verify.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_PREFILTER_CAP \
+  -1074395421  // The specified value for the filter cap for block matching is
+               // invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_PREFILTER_SIZE \
+  -1074395420  // The specified prefilter size for block matching is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_PREFILTER_TYPE \
+  -1074395419  // The specified prefilter type for block matching is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_NUMDISPARITIES \
+  -1074395418  // The specifed value for number of disparities is invalid.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_WINDOW_SIZE \
+  -1074395417  // The specified window size for block matching is invalid.
+#define ERR_3DVISION_INVALID_SESSION_TYPE \
+  -1074395416  // This 3D vision function cannot be called on this type of 3d
+               // vision session.
+#define ERR_TOO_MANY_3DVISION_SESSIONS \
+  -1074395415  // There are too many 3D vision sessions open.  You must close a
+               // session before you can open another one.
+#define ERR_OPENING_NEWER_3DVISION_SESSION \
+  -1074395414  // The 3D vision session you tried to open was created with a
+               // newer version of NI Vision. Upgrade to the latest version of
+               // NI Vision to read this file.
+#define ERR_INVALID_STEREO_BLOCKMATCHING_FILTERTYPE \
+  -1074395413  // You have specified an invalid filter type for block matching.
+#define ERR_INVALID_STEREO_CAMERA_POSITION \
+  -1074395412  // You have requested results at an invalid camera position in
+               // the stereo setup.
+#define ERR_INVALID_3DVISION_SESSION \
+  -1074395411  // Not a valid 3D Vision session.
+#define ERR_INVALID_ICONS_PER_LINE \
+  -1074395410  // NI Vision does not support less than one icon per line.
+#define ERR_INVALID_SUBPIXEL_DIVISIONS \
+  -1074395409                                   // Invalid subpixel divisions.
+#define ERR_INVALID_DETECTION_MODE -1074395408  // Invalid detection mode.
+#define ERR_INVALID_CONTRAST \
+  -1074395407  // Invalid contrast value. Valid contrast values range from 0 to
+               // 255.
+#define ERR_COORDSYS_NOT_FOUND \
+  -1074395406  // The coordinate system could not be found on this image.
+#define ERR_INVALID_TEXTORIENTATION \
+  -1074395405  // NI Vision does not support the text orientation value you
+               // supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD_FOR_UNWRAP \
+  -1074395404  // UnwrapImage does not support the interpolation method value
+               // you supplied.  Valid interpolation methods are zero order and
+               // bilinear.
+#define ERR_EXTRAINFO_VERSION \
+  -1074395403  // The image was created in a newer version of NI Vision. Upgrade
+               // to the latest version of NI Vision to use this image.
+#define ERR_INVALID_MAXPOINTS \
+  -1074395402  // The function does not support the maximum number of points
+               // that you specified.
+#define ERR_INVALID_MATCHFACTOR \
+  -1074395401  // The function does not support the matchFactor that you
+               // specified.
+#define ERR_MULTICORE_OPERATION \
+  -1074395400  // The operation you have given Multicore Options is invalid.
+               // Please see the available enumeration values for Multicore
+               // Operation.
+#define ERR_MULTICORE_INVALID_ARGUMENT \
+  -1074395399  // You have given Multicore Options an invalid argument.
+#define ERR_COMPLEX_IMAGE_REQUIRED -1074395397  // A complex image is required.
+#define ERR_COLOR_IMAGE_REQUIRED \
+  -1074395395  // The input image must be a color image.
+#define ERR_COLOR_SPECTRUM_MASK \
+  -1074395394  // The color mask removes too much color information.
+#define ERR_COLOR_TEMPLATE_IMAGE_TOO_SMALL \
+  -1074395393  // The color template image is too small.
+#define ERR_COLOR_TEMPLATE_IMAGE_TOO_LARGE \
+  -1074395392  // The color template image is too large.
+#define ERR_COLOR_TEMPLATE_IMAGE_HUE_CONTRAST_TOO_LOW \
+  -1074395391  // The contrast in the hue plane of the image is too low for
+               // learning shape features.
+#define ERR_COLOR_TEMPLATE_IMAGE_LUMINANCE_CONTRAST_TOO_LOW \
+  -1074395390  // The contrast in the luminance plane of the image is too low to
+               // learn shape features.
+#define ERR_COLOR_LEARN_SETUP_DATA \
+  -1074395389  // Invalid color learn setup data.
+#define ERR_COLOR_LEARN_SETUP_DATA_SHAPE \
+  -1074395388  // Invalid color learn setup data.
+#define ERR_COLOR_MATCH_SETUP_DATA \
+  -1074395387  // Invalid color match setup data.
+#define ERR_COLOR_MATCH_SETUP_DATA_SHAPE \
+  -1074395386  // Invalid color match setup data.
+#define ERR_COLOR_ROTATION_REQUIRES_SHAPE_FEATURE \
+  -1074395385  // Rotation-invariant color pattern matching requires a feature
+               // mode including shape.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR \
+  -1074395384  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_1 \
+  -1074395383  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_2 \
+  -1074395382  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_3 \
+  -1074395381  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_4 \
+  -1074395380  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_5 \
+  -1074395379  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_6 \
+  -1074395378  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT \
+  -1074395377  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHIFT \
+  -1074395376  // The color template image does not contain data required for
+               // shift-invariant color matching.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_1 \
+  -1074395375  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_2 \
+  -1074395374  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION \
+  -1074395373  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOROTATION \
+  -1074395372  // The color template image does not contain data required for
+               // rotation-invariant color matching.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_1 \
+  -1074395371  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_2 \
+  -1074395370  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_3 \
+  -1074395369  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_4 \
+  -1074395368  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_5 \
+  -1074395367  // Invalid color template image.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHAPE \
+  -1074395366  // The color template image does not contain data required for
+               // color matching in shape feature mode.
+#define ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSPECTRUM \
+  -1074395365  // The color template image does not contain data required for
+               // color matching in color feature mode.
+#define ERR_IGNORE_COLOR_SPECTRUM_SET \
+  -1074395364  // The ignore color spectra array is invalid.
+#define ERR_INVALID_SUBSAMPLING_RATIO -1074395363  // Invalid subsampling ratio.
+#define ERR_INVALID_WIDTH -1074395362              // Invalid pixel width.
+#define ERR_INVALID_STEEPNESS -1074395361          // Invalid steepness.
+#define ERR_COMPLEX_PLANE -1074395360              // Invalid complex plane.
+#define ERR_INVALID_COLOR_IGNORE_MODE -1074395357  // Invalid color ignore mode.
+#define ERR_INVALID_MIN_MATCH_SCORE \
+  -1074395356  // Invalid minimum match score. Acceptable values range from 0 to
+               // 1000.
+#define ERR_INVALID_NUM_MATCHES_REQUESTED \
+  -1074395355  // Invalid number of matches requested. You must request a
+               // minimum of one match.
+#define ERR_INVALID_COLOR_WEIGHT \
+  -1074395354  // Invalid color weight. Acceptable values range from 0 to 1000.
+#define ERR_INVALID_SEARCH_STRATEGY -1074395353  // Invalid search strategy.
+#define ERR_INVALID_FEATURE_MODE -1074395352     // Invalid feature mode.
+#define ERR_INVALID_RECT \
+  -1074395351  // NI Vision does not support rectangles with negative widths or
+               // negative heights.
+#define ERR_INVALID_VISION_INFO \
+  -1074395350  // NI Vision does not support the vision information type you
+               // supplied.
+#define ERR_INVALID_SKELETONMETHOD \
+  -1074395349  // NI Vision does not support the SkeletonMethod value you
+               // supplied.
+#define ERR_INVALID_3DPLANE \
+  -1074395348  // NI Vision does not support the 3DPlane value you supplied.
+#define ERR_INVALID_3DDIRECTION \
+  -1074395347  // NI Vision does not support the 3DDirection value you supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD_FOR_ROTATE \
+  -1074395346  // imaqRotate does not support the InterpolationMethod value you
+               // supplied.
+#define ERR_INVALID_FLIPAXIS \
+  -1074395345  // NI Vision does not support the axis of symmetry you supplied.
+#define ERR_FILE_FILENAME_NULL \
+  -1074395343  // You must pass a valid file name. Do not pass in NULL.
+#define ERR_INVALID_SIZETYPE \
+  -1074395340  // NI Vision does not support the SizeType value you supplied.
+#define ERR_UNKNOWN_ALGORITHM \
+  -1074395336  // You specified the dispatch status of an unknown algorithm.
+#define ERR_DISPATCH_STATUS_CONFLICT \
+  -1074395335  // You are attempting to set the same algorithm to dispatch and
+               // to not dispatch. Remove one of the conflicting settings.
+#define ERR_INVALID_CONVERSIONSTYLE \
+  -1074395334  // NI Vision does not support the Conversion Method value you
+               // supplied.
+#define ERR_INVALID_VERTICAL_TEXT_ALIGNMENT \
+  -1074395333  // NI Vision does not support the VerticalTextAlignment value you
+               // supplied.
+#define ERR_INVALID_COMPAREFUNCTION \
+  -1074395332  // NI Vision does not support the CompareFunction value you
+               // supplied.
+#define ERR_INVALID_BORDERMETHOD \
+  -1074395331  // NI Vision does not support the BorderMethod value you
+               // supplied.
+#define ERR_INVALID_BORDER_SIZE \
+  -1074395330  // Invalid border size. Acceptable values range from 0 to 50.
+#define ERR_INVALID_OUTLINEMETHOD \
+  -1074395329  // NI Vision does not support the OutlineMethod value you
+               // supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD \
+  -1074395328  // NI Vision does not support the InterpolationMethod value you
+               // supplied.
+#define ERR_INVALID_SCALINGMODE \
+  -1074395327  // NI Vision does not support the ScalingMode value you supplied.
+#define ERR_INVALID_DRAWMODE_FOR_LINE \
+  -1074395326  // imaqDrawLineOnImage does not support the DrawMode value you
+               // supplied.
+#define ERR_INVALID_DRAWMODE \
+  -1074395325  // NI Vision does not support the DrawMode value you supplied.
+#define ERR_INVALID_SHAPEMODE \
+  -1074395324  // NI Vision does not support the ShapeMode value you supplied.
+#define ERR_INVALID_FONTCOLOR \
+  -1074395323  // NI Vision does not support the FontColor value you supplied.
+#define ERR_INVALID_TEXTALIGNMENT \
+  -1074395322  // NI Vision does not support the TextAlignment value you
+               // supplied.
+#define ERR_INVALID_MORPHOLOGYMETHOD \
+  -1074395321  // NI Vision does not support the MorphologyMethod value you
+               // supplied.
+#define ERR_TEMPLATE_EMPTY -1074395320  // The template image is empty.
+#define ERR_INVALID_SUBPIX_TYPE \
+  -1074395319  // NI Vision does not support the interpolation type you
+               // supplied.
+#define ERR_INSF_POINTS \
+  -1074395318  // You supplied an insufficient number of points to perform this
+               // operation.
+#define ERR_UNDEF_POINT \
+  -1074395317  // You specified a point that lies outside the image.
+#define ERR_INVALID_KERNEL_CODE -1074395316  // Invalid kernel code.
+#define ERR_INEFFICIENT_POINTS \
+  -1074395315  // You supplied an inefficient set of points to match the minimum
+               // score.
+#define ERR_WRITE_FILE_NOT_SUPPORTED \
+  -1074395313  // Writing files is not supported on this device.
+#define ERR_LCD_CALIBRATE \
+  -1074395312  // The input image does not seem to be a valid LCD or LED
+               // calibration image.
+#define ERR_INVALID_COLOR_SPECTRUM \
+  -1074395311  // The color spectrum array you provided has an invalid number of
+               // elements or contains an element set to not-a-number (NaN).
+#define ERR_INVALID_PALETTE_TYPE \
+  -1074395310  // NI Vision does not support the PaletteType value you supplied.
+#define ERR_INVALID_WINDOW_THREAD_POLICY \
+  -1074395309  // NI Vision does not support the WindowThreadPolicy value you
+               // supplied.
+#define ERR_INVALID_COLORSENSITIVITY \
+  -1074395308  // NI Vision does not support the ColorSensitivity value you
+               // supplied.
+#define ERR_PRECISION_NOT_GTR_THAN_0 \
+  -1074395307  // The precision parameter must be greater than 0.
+#define ERR_INVALID_TOOL \
+  -1074395306  // NI Vision does not support the Tool value you supplied.
+#define ERR_INVALID_REFERENCEMODE \
+  -1074395305  // NI Vision does not support the ReferenceMode value you
+               // supplied.
+#define ERR_INVALID_MATHTRANSFORMMETHOD \
+  -1074395304  // NI Vision does not support the MathTransformMethod value you
+               // supplied.
+#define ERR_INVALID_NUM_OF_CLASSES \
+  -1074395303  // Invalid number of classes for auto threshold. Acceptable
+               // values range from 2 to 256.
+#define ERR_INVALID_THRESHOLDMETHOD \
+  -1074395302  // NI Vision does not support the threshold method value you
+               // supplied.
+#define ERR_ROI_NOT_2_LINES \
+  -1074395301  // The ROI you passed into imaqGetMeterArc must consist of two
+               // lines.
+#define ERR_INVALID_METERARCMODE \
+  -1074395300  // NI Vision does not support the MeterArcMode value you
+               // supplied.
+#define ERR_INVALID_COMPLEXPLANE \
+  -1074395299  // NI Vision does not support the ComplexPlane value you
+               // supplied.
+#define ERR_COMPLEXPLANE_NOT_REAL_OR_IMAGINARY \
+  -1074395298  // You can perform this operation on a real or an imaginary
+               // ComplexPlane only.
+#define ERR_INVALID_PARTICLEINFOMODE \
+  -1074395297  // NI Vision does not support the ParticleInfoMode value you
+               // supplied.
+#define ERR_INVALID_BARCODETYPE \
+  -1074395296  // NI Vision does not support the BarcodeType value you supplied.
+#define ERR_INVALID_INTERPOLATIONMETHOD_INTERPOLATEPOINTS \
+  -1074395295  // imaqInterpolatePoints does not support the InterpolationMethod
+               // value you supplied.
+#define ERR_CONTOUR_INDEX_OUT_OF_RANGE \
+  -1074395294  // The contour index you supplied is larger than the number of
+               // contours in the ROI.
+#define ERR_CONTOURID_NOT_FOUND \
+  -1074395293  // The supplied ContourID did not correlate to a contour inside
+               // the ROI.
+#define ERR_POINTS_ARE_COLLINEAR \
+  -1074395292  // Do not supply collinear points for this operation.
+#define ERR_SHAPEMATCH_BADIMAGEDATA \
+  -1074395291  // Shape Match requires the image to contain only pixel values of
+               // 0 or 1.
+#define ERR_SHAPEMATCH_BADTEMPLATE \
+  -1074395290  // The template you supplied for ShapeMatch contains no shape
+               // information.
+#define ERR_CONTAINER_CAPACITY_EXCEEDED_UINT_MAX \
+  -1074395289  // The operation would have exceeded the capacity of an internal
+               // container, which is limited to 4294967296 unique elements.
+#define ERR_CONTAINER_CAPACITY_EXCEEDED_INT_MAX \
+  -1074395288  // The operation would have exceeded the capacity of an internal
+               // container, which is limited to 2147483648 unique elements.
+#define ERR_INVALID_LINE \
+  -1074395287  // The line you provided contains two identical points, or one of
+               // the coordinate locations for the line is not a number (NaN).
+#define ERR_INVALID_CONCENTRIC_RAKE_DIRECTION \
+  -1074395286  // Invalid concentric rake direction.
+#define ERR_INVALID_SPOKE_DIRECTION -1074395285  // Invalid spoke direction.
+#define ERR_INVALID_EDGE_PROCESS -1074395284     // Invalid edge process.
+#define ERR_INVALID_RAKE_DIRECTION -1074395283   // Invalid rake direction.
+#define ERR_CANT_DRAW_INTO_VIEWER \
+  -1074395282  // Unable to draw to viewer. You must have the latest version of
+               // the control.
+#define ERR_IMAGE_SMALLER_THAN_BORDER \
+  -1074395281  // Your image must be larger than its border size for this
+               // operation.
+#define ERR_ROI_NOT_RECT \
+  -1074395280  // The ROI must only have a single Rectangle contour.
+#define ERR_ROI_NOT_POLYGON -1074395279  // ROI is not a polygon.
+#define ERR_LCD_NOT_NUMERIC -1074395278  // LCD image is not a number.
+#define ERR_BARCODE_CHECKSUM \
+  -1074395277  // The decoded barcode information did not pass the checksum
+               // test.
+#define ERR_LINES_PARALLEL \
+  -1074395276  // You specified parallel lines for the meter ROI.
+#define ERR_INVALID_BROWSER_IMAGE -1074395275  // Invalid browser image.
+#define ERR_DIV_BY_ZERO -1074395270            // Cannot divide by zero.
+#define ERR_NULL_POINTER -1074395269           // Null pointer.
+#define ERR_LINEAR_COEFF \
+  -1074395268  // The linear equations are not independent.
+#define ERR_COMPLEX_ROOT -1074395267  // The roots of the equation are complex.
+#define ERR_BARCODE \
+  -1074395265  // The barcode does not match the type you specified.
+#define ERR_LCD_NO_SEGMENTS -1074395263  // No lit segment.
+#define ERR_LCD_BAD_MATCH -1074395262    // The LCD does not form a known digit.
+#define ERR_GIP_RANGE \
+  -1074395261  // An internal error occurred while attempting to access an
+               // invalid coordinate on an image.
+#define ERR_HEAP_TRASHED -1074395260  // An internal memory error occurred.
+#define ERR_BAD_FILTER_WIDTH \
+  -1074395258  // The filter width must be odd for the Canny operator.
+#define ERR_INVALID_EDGE_DIR \
+  -1074395257  // You supplied an invalid edge direction in the Canny operator.
+#define ERR_EVEN_WINDOW_SIZE \
+  -1074395256  // The window size must be odd for the Canny operator.
+#define ERR_INVALID_LEARN_MODE -1074395253  // Invalid learn mode.
+#define ERR_LEARN_SETUP_DATA -1074395252    // Invalid learn setup data.
+#define ERR_INVALID_MATCH_MODE -1074395251  // Invalid match mode.
+#define ERR_MATCH_SETUP_DATA -1074395250    // Invalid match setup data.
+#define ERR_ROTATION_ANGLE_RANGE_TOO_LARGE \
+  -1074395249  // At least one range in the array of rotation angle ranges
+               // exceeds 360 degrees.
+#define ERR_TOO_MANY_ROTATION_ANGLE_RANGES \
+  -1074395248  // The array of rotation angle ranges contains too many ranges.
+#define ERR_TEMPLATE_DESCRIPTOR -1074395247    // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_1 -1074395246  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_2 -1074395245  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_3 -1074395244  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_4 \
+  -1074395243  // The template descriptor was created with a newer version of NI
+               // Vision. Upgrade to the latest version of NI Vision to use this
+               // template.
+#define ERR_TEMPLATE_DESCRIPTOR_ROTATION \
+  -1074395242  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_NOROTATION \
+  -1074395241  // The template descriptor does not contain data required for
+               // rotation-invariant matching.
+#define ERR_TEMPLATE_DESCRIPTOR_ROTATION_1 \
+  -1074395240  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_SHIFT \
+  -1074395239  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_NOSHIFT \
+  -1074395238  // The template descriptor does not contain data required for
+               // shift-invariant matching.
+#define ERR_TEMPLATE_DESCRIPTOR_SHIFT_1 \
+  -1074395237  // Invalid template descriptor.
+#define ERR_TEMPLATE_DESCRIPTOR_NOSCALE \
+  -1074395236  // The template descriptor does not contain data required for
+               // scale-invariant matching.
+#define ERR_TEMPLATE_IMAGE_CONTRAST_TOO_LOW \
+  -1074395235  // The template image does not contain enough contrast.
+#define ERR_TEMPLATE_IMAGE_TOO_SMALL \
+  -1074395234  // The template image is too small.
+#define ERR_TEMPLATE_IMAGE_TOO_LARGE \
+  -1074395233  // The template image is too large.
+#define ERR_TOO_MANY_OCR_SESSIONS \
+  -1074395214  // There are too many OCR sessions open.  You must close a
+               // session before you can open another one.
+#define ERR_OCR_TEMPLATE_WRONG_SIZE \
+  -1074395212  // The size of the template string must match the size of the
+               // string you are trying to correct.
+#define ERR_OCR_BAD_TEXT_TEMPLATE \
+  -1074395211  // The supplied text template contains nonstandard characters
+               // that cannot be generated by OCR.
+#define ERR_OCR_CANNOT_MATCH_TEXT_TEMPLATE \
+  -1074395210  // At least one character in the text template was of a lexical
+               // class that did not match the supplied character reports.
+#define ERR_OCR_LIB_INIT \
+  -1074395203  // The OCR library cannot be initialized correctly.
+#define ERR_OCR_LOAD_LIBRARY \
+  -1074395201  // There was a failure when loading one of the internal OCR
+               // engine or LabView libraries.
+#define ERR_OCR_INVALID_PARAMETER \
+  -1074395200  // One of the parameters supplied to the OCR function that
+               // generated this error is invalid.
+#define ERR_MARKER_INFORMATION_NOT_SUPPLIED \
+  -1074395199  // Marker image and points are not supplied
+#define ERR_INCOMPATIBLE_MARKER_IMAGE_SIZE \
+  -1074395198  // Source Image and Marker Image should be of same size.
+#define ERR_BOTH_MARKER_INPUTS_SUPPLIED \
+  -1074395197  // Both Marker Image and Points are supplied.
+#define ERR_INVALID_MORPHOLOGICAL_OPERATION \
+  -1074395196  // Invalid Morphological Operation.
+#define ERR_IMAGE_CONTAINS_NAN_VALUES \
+  -1074395195  // Float image contains NaN values
+#define ERR_OVERLAY_EXTRAINFO_OPENING_NEW_VERSION \
+  -1074395194  // The overlay information you tried to open was created with a
+               // newer version of NI Vision. Upgrade to the latest version of
+               // NI Vision to read this file.
+#define ERR_NO_CLAMP_FOUND \
+  -1074395193  // No valid clamp was found with the current configuration
+#define ERR_NO_CLAMP_WITHIN_ANGLE_RANGE \
+  -1074395192  // Supplied angle range for clamp is insufficient
+#define ERR_GHT_INVALID_USE_ALL_CURVES_VALUE \
+  -1074395188  // The use all curves advanced option specified during learn is
+               // not supported
+#define ERR_INVALID_GAUSS_SIGMA_VALUE \
+  -1074395187  // The sigma value specified for the Gaussian filter is too
+               // small.
+#define ERR_INVALID_GAUSS_FILTER_TYPE \
+  -1074395186  // The specified Gaussian filter type is not supported.
+#define ERR_INVALID_CONTRAST_REVERSAL_MODE \
+  -1074395185  // The contrast reversal mode specified during matching is
+               // invalid.
+#define ERR_INVALID_ROTATION_RANGE \
+  -1074395184  // Invalid roation angle range. The upper bound must be greater
+               // than or equal to the lower bound.
+#define ERR_GHT_INVALID_MINIMUM_LEARN_ANGLE_VALUE \
+  -1074395183  // The minimum rotation angle value specifed during learning of
+               // the template is not supported.
+#define ERR_GHT_INVALID_MAXIMUM_LEARN_ANGLE_VALUE \
+  -1074395182  // The maximum rotation angle value specifed during learning of
+               // the template is not supported.
+#define ERR_GHT_INVALID_MAXIMUM_LEARN_SCALE_FACTOR \
+  -1074395181  // The maximum scale factor specifed during learning of the
+               // template is not supported.
+#define ERR_GHT_INVALID_MINIMUM_LEARN_SCALE_FACTOR \
+  -1074395180  // The minimum scale factor specifed during learning of the
+               // template is not supported.
+#define ERR_OCR_PREPROCESSING_FAILED \
+  -1074395179  // The OCR engine failed during the preprocessing stage.
+#define ERR_OCR_RECOGNITION_FAILED \
+  -1074395178  // The OCR engine failed during the recognition stage.
+#define ERR_OCR_BAD_USER_DICTIONARY \
+  -1074395175  // The provided filename is not valid user dictionary filename.
+#define ERR_OCR_INVALID_AUTOORIENTMODE \
+  -1074395174  // NI Vision does not support the AutoOrientMode value you
+               // supplied.
+#define ERR_OCR_INVALID_LANGUAGE \
+  -1074395173  // NI Vision does not support the Language value you supplied.
+#define ERR_OCR_INVALID_CHARACTERSET \
+  -1074395172  // NI Vision does not support the CharacterSet value you
+               // supplied.
+#define ERR_OCR_INI_FILE_NOT_FOUND \
+  -1074395171  // The system could not locate the initialization file required
+               // for OCR initialization.
+#define ERR_OCR_INVALID_CHARACTERTYPE \
+  -1074395170  // NI Vision does not support the CharacterType value you
+               // supplied.
+#define ERR_OCR_INVALID_RECOGNITIONMODE \
+  -1074395169  // NI Vision does not support the RecognitionMode value you
+               // supplied.
+#define ERR_OCR_INVALID_AUTOCORRECTIONMODE \
+  -1074395168  // NI Vision does not support the AutoCorrectionMode value you
+               // supplied.
+#define ERR_OCR_INVALID_OUTPUTDELIMITER \
+  -1074395167  // NI Vision does not support the OutputDelimiter value you
+               // supplied.
+#define ERR_OCR_BIN_DIR_NOT_FOUND \
+  -1074395166  // The system could not locate the OCR binary directory required
+               // for OCR initialization.
+#define ERR_OCR_WTS_DIR_NOT_FOUND \
+  -1074395165  // The system could not locate the OCR weights directory required
+               // for OCR initialization.
+#define ERR_OCR_ADD_WORD_FAILED \
+  -1074395164  // The supplied word could not be added to the user dictionary.
+#define ERR_OCR_INVALID_CHARACTERPREFERENCE \
+  -1074395163  // NI Vision does not support the CharacterPreference value you
+               // supplied.
+#define ERR_OCR_INVALID_CORRECTIONMODE \
+  -1074395162  // NI Vision does not support the CorrectionMethod value you
+               // supplied.
+#define ERR_OCR_INVALID_CORRECTIONLEVEL \
+  -1074395161  // NI Vision does not support the CorrectionLevel value you
+               // supplied.
+#define ERR_OCR_INVALID_MAXPOINTSIZE \
+  -1074395160  // NI Vision does not support the maximum point size you
+               // supplied.  Valid values range from 4 to 72.
+#define ERR_OCR_INVALID_TOLERANCE \
+  -1074395159  // NI Vision does not support the tolerance value you supplied.
+               // Valid values are non-negative.
+#define ERR_OCR_INVALID_CONTRASTMODE \
+  -1074395158  // NI Vision does not support the ContrastMode value you
+               // supplied.
+#define ERR_OCR_SKEW_DETECT_FAILED \
+  -1074395156  // The OCR attempted to detected the text skew and failed.
+#define ERR_OCR_ORIENT_DETECT_FAILED \
+  -1074395155  // The OCR attempted to detected the text orientation and failed.
+#define ERR_FONT_FILE_FORMAT -1074395153     // Invalid font file format.
+#define ERR_FONT_FILE_NOT_FOUND -1074395152  // Font file not found.
+#define ERR_OCR_CORRECTION_FAILED \
+  -1074395151  // The OCR engine failed during the correction stage.
+#define ERR_INVALID_ROUNDING_MODE \
+  -1074395150  // NI Vision does not support the RoundingMode value you
+               // supplied.
+#define ERR_DUPLICATE_TRANSFORM_TYPE \
+  -1074395149  // Found a duplicate transform type in the properties array. Each
+               // properties array may only contain one behavior for each
+               // transform type.
+#define ERR_OVERLAY_GROUP_NOT_FOUND -1074395148  // Overlay Group Not Found.
+#define ERR_BARCODE_RSSLIMITED \
+  -1074395147  // The barcode is not a valid RSS Limited symbol
+#define ERR_QR_DETECTION_VERSION \
+  -1074395146  // Couldn't determine the correct version of the QR code.
+#define ERR_QR_INVALID_READ -1074395145  // Invalid read of the QR code.
+#define ERR_QR_INVALID_BARCODE \
+  -1074395144  // The barcode that was read contains invalid parameters.
+#define ERR_QR_DETECTION_MODE \
+  -1074395143  // The data stream that was demodulated could not be read because
+               // the mode was not detected.
+#define ERR_QR_DETECTION_MODELTYPE \
+  -1074395142  // Couldn't determine the correct model of the QR code.
+#define ERR_OCR_NO_TEXT_FOUND \
+  -1074395141  // The OCR engine could not find any text in the supplied region.
+#define ERR_OCR_CHAR_REPORT_CORRUPTED \
+  -1074395140  // One of the character reports is no longer usable by the
+               // system.
+#define ERR_IMAQ_QR_DIMENSION_INVALID -1074395139  // Invalid Dimensions.
+#define ERR_OCR_REGION_TOO_SMALL \
+  -1074395138  // The OCR region provided was too small to have contained any
+               // characters.
+#define _FIRST_ERR ERR_SYSTEM_ERROR
+#define _LAST_ERR ERR_OCR_REGION_TOO_SMALL
+
+//============================================================================
+//  Enumerated Types
+//============================================================================
+typedef enum PointSymbol_enum {
+  IMAQ_POINT_AS_PIXEL = 0,  // A single pixel represents a point in the overlay.
+  IMAQ_POINT_AS_CROSS = 1,  // A cross represents a point in the overlay.
+  IMAQ_POINT_USER_DEFINED =
+      2,  // The pattern supplied by the user represents a point in the overlay.
+  IMAQ_POINT_SYMBOL_SIZE_GUARD = 0xFFFFFFFF
+} PointSymbol;
+
+typedef enum MeasurementValue_enum {
+  IMAQ_AREA = 0,  // Surface area of the particle in pixels.
+  IMAQ_AREA_CALIBRATED =
+      1,  // Surface area of the particle in calibrated units.
+  IMAQ_NUM_HOLES = 2,  // Number of holes in the particle.
+  IMAQ_AREA_OF_HOLES = 3,  // Surface area of the holes in calibrated units.
+  IMAQ_TOTAL_AREA =
+      4,  // Total surface area (holes and particle) in calibrated units.
+  IMAQ_IMAGE_AREA = 5,  // Surface area of the entire image in calibrated units.
+  IMAQ_PARTICLE_TO_IMAGE = 6,  // Ratio, expressed as a percentage, of the
+                               // surface area of a particle in relation to the
+                               // total area of the particle.
+  IMAQ_PARTICLE_TO_TOTAL = 7,  // Ratio, expressed as a percentage, of the
+                               // surface area of a particle in relation to the
+                               // total area of the particle.
+  IMAQ_CENTER_MASS_X = 8,  // X-coordinate of the center of mass.
+  IMAQ_CENTER_MASS_Y = 9,  // Y-coordinate of the center of mass.
+  IMAQ_LEFT_COLUMN = 10,  // Left edge of the bounding rectangle.
+  IMAQ_TOP_ROW = 11,  // Top edge of the bounding rectangle.
+  IMAQ_RIGHT_COLUMN = 12,  // Right edge of the bounding rectangle.
+  IMAQ_BOTTOM_ROW = 13,  // Bottom edge of bounding rectangle.
+  IMAQ_WIDTH = 14,  // Width of bounding rectangle in calibrated units.
+  IMAQ_HEIGHT = 15,  // Height of bounding rectangle in calibrated units.
+  IMAQ_MAX_SEGMENT_LENGTH = 16,  // Length of longest horizontal line segment.
+  IMAQ_MAX_SEGMENT_LEFT_COLUMN =
+      17,  // Leftmost x-coordinate of longest horizontal line segment.
+  IMAQ_MAX_SEGMENT_TOP_ROW =
+      18,  // Y-coordinate of longest horizontal line segment.
+  IMAQ_PERIMETER = 19,  // Outer perimeter of the particle.
+  IMAQ_PERIMETER_OF_HOLES = 20,  // Perimeter of all holes within the particle.
+  IMAQ_SIGMA_X = 21,  // Sum of the particle pixels on the x-axis.
+  IMAQ_SIGMA_Y = 22,  // Sum of the particle pixels on the y-axis.
+  IMAQ_SIGMA_XX = 23,  // Sum of the particle pixels on the x-axis squared.
+  IMAQ_SIGMA_YY = 24,  // Sum of the particle pixels on the y-axis squared.
+  IMAQ_SIGMA_XY = 25,  // Sum of the particle pixels on the x-axis and y-axis.
+  IMAQ_PROJ_X = 26,  // Projection corrected in X.
+  IMAQ_PROJ_Y = 27,  // Projection corrected in Y.
+  IMAQ_INERTIA_XX = 28,  // Inertia matrix coefficient in XX.
+  IMAQ_INERTIA_YY = 29,  // Inertia matrix coefficient in YY.
+  IMAQ_INERTIA_XY = 30,  // Inertia matrix coefficient in XY.
+  IMAQ_MEAN_H = 31,  // Mean length of horizontal segments.
+  IMAQ_MEAN_V = 32,  // Mean length of vertical segments.
+  IMAQ_MAX_INTERCEPT = 33,  // Length of longest segment of the convex hull.
+  IMAQ_MEAN_INTERCEPT = 34,  // Mean length of the chords in an object
+                             // perpendicular to its max intercept.
+  IMAQ_ORIENTATION = 35,  // The orientation based on the inertia of the pixels
+                          // in the particle.
+  IMAQ_EQUIV_ELLIPSE_MINOR = 36,  // Total length of the axis of the ellipse
+                                  // having the same area as the particle and a
+                                  // major axis equal to half the max intercept.
+  IMAQ_ELLIPSE_MAJOR = 37,  // Total length of major axis having the same area
+                            // and perimeter as the particle in calibrated
+                            // units.
+  IMAQ_ELLIPSE_MINOR = 38,  // Total length of minor axis having the same area
+                            // and perimeter as the particle in calibrated
+                            // units.
+  IMAQ_ELLIPSE_RATIO = 39,  // Fraction of major axis to minor axis.
+  IMAQ_RECT_LONG_SIDE = 40,  // Length of the long side of a rectangle having
+                             // the same area and perimeter as the particle in
+                             // calibrated units.
+  IMAQ_RECT_SHORT_SIDE = 41,  // Length of the short side of a rectangle having
+                              // the same area and perimeter as the particle in
+                              // calibrated units.
+  IMAQ_RECT_RATIO =
+      42,  // Ratio of rectangle long side to rectangle short side.
+  IMAQ_ELONGATION = 43,  // Max intercept/mean perpendicular intercept.
+  IMAQ_COMPACTNESS = 44,  // Particle area/(height x width).
+  IMAQ_HEYWOOD = 45,  // Particle perimeter/perimeter of the circle having the
+                      // same area as the particle.
+  IMAQ_TYPE_FACTOR = 46,  // A complex factor relating the surface area to the
+                          // moment of inertia.
+  IMAQ_HYDRAULIC = 47,  // Particle area/particle perimeter.
+  IMAQ_WADDLE_DISK = 48,  // Diameter of the disk having the same area as the
+                          // particle in user units.
+  IMAQ_DIAGONAL = 49,  // Diagonal of an equivalent rectangle in user units.
+  IMAQ_MEASUREMENT_VALUE_SIZE_GUARD = 0xFFFFFFFF
+} MeasurementValue;
+
+typedef enum ScalingMode_enum {
+  IMAQ_SCALE_LARGER =
+      0,  // The function duplicates pixels to make the image larger.
+  IMAQ_SCALE_SMALLER =
+      1,  // The function subsamples pixels to make the image smaller.
+  IMAQ_SCALING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ScalingMode;
+
+typedef enum ScalingMethod_enum {
+  IMAQ_SCALE_TO_PRESERVE_AREA = 0,  // Correction functions scale the image such
+                                    // that the features in the corrected image
+                                    // have the same area as the features in the
+                                    // input image.
+  IMAQ_SCALE_TO_FIT = 1,  // Correction functions scale the image such that the
+                          // corrected image is the same size as the input
+                          // image.
+  IMAQ_SCALING_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} ScalingMethod;
+
+typedef enum ReferenceMode_enum {
+  IMAQ_COORD_X_Y =
+      0,  // This method requires three elements in the points array.
+  IMAQ_COORD_ORIGIN_X =
+      1,  // This method requires two elements in the points array.
+  IMAQ_REFERENCE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ReferenceMode;
+
+typedef enum RectOrientation_enum {
+  IMAQ_BASE_INSIDE = 0,  // Specifies that the base of the rectangular image
+                         // lies along the inside edge of the annulus.
+  IMAQ_BASE_OUTSIDE = 1,  // Specifies that the base of the rectangular image
+                          // lies along the outside edge of the annulus.
+  IMAQ_TEXT_ORIENTATION_SIZE_GUARD = 0xFFFFFFFF
+} RectOrientation;
+
+typedef enum ShapeMode_enum {
+  IMAQ_SHAPE_RECT = 1,  // The function draws a rectangle.
+  IMAQ_SHAPE_OVAL = 2,  // The function draws an oval.
+  IMAQ_SHAPE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ShapeMode;
+
+typedef enum PolarityType_enum {
+  IMAQ_EDGE_RISING = 1,  // The edge is a rising edge.
+  IMAQ_EDGE_FALLING = -1,  // The edge is a falling edge.
+  IMAQ_POLARITY_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} PolarityType;
+
+typedef enum SizeType_enum {
+  IMAQ_KEEP_LARGE =
+      0,  // The function keeps large particles remaining after the erosion.
+  IMAQ_KEEP_SMALL =
+      1,  // The function keeps small particles eliminated by the erosion.
+  IMAQ_SIZE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} SizeType;
+
+typedef enum Plane3D_enum {
+  IMAQ_3D_REAL = 0,  // The function shows the real part of complex images.
+  IMAQ_3D_IMAGINARY =
+      1,  // The function shows the imaginary part of complex images.
+  IMAQ_3D_MAGNITUDE =
+      2,  // The function shows the magnitude part of complex images.
+  IMAQ_3D_PHASE = 3,  // The function shows the phase part of complex images.
+  IMAQ_PLANE_3D_SIZE_GUARD = 0xFFFFFFFF
+} Plane3D;
+
+typedef enum PhotometricMode_enum {
+  IMAQ_WHITE_IS_ZERO =
+      0,  // The function interprets zero-value pixels as white.
+  IMAQ_BLACK_IS_ZERO =
+      1,  // The function interprets zero-value pixels as black.
+  IMAQ_PHOTOMETRIC_MODE_SIZE_GUARD = 0xFFFFFFFF
+} PhotometricMode;
+
+typedef enum ParticleInfoMode_enum {
+  IMAQ_BASIC_INFO = 0,  // The function returns only the following elements of
+                        // each report: area, calibratedArea, boundingRect.
+  IMAQ_ALL_INFO =
+      1,  // The function returns all the information about each particle.
+  IMAQ_PARTICLE_INFO_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ParticleInfoMode;
+
+typedef enum OutlineMethod_enum {
+  IMAQ_EDGE_DIFFERENCE = 0,  // The function uses a method that produces
+                             // continuous contours by highlighting each pixel
+                             // where an intensity variation occurs between
+                             // itself and its three upper-left neighbors.
+  IMAQ_EDGE_GRADIENT = 1,  // The function uses a method that outlines contours
+                           // where an intensity variation occurs along the
+                           // vertical axis.
+  IMAQ_EDGE_PREWITT = 2,  // The function uses a method that extracts the outer
+                          // contours of objects.
+  IMAQ_EDGE_ROBERTS = 3,  // The function uses a method that outlines the
+                          // contours that highlight pixels where an intensity
+                          // variation occurs along the diagonal axes.
+  IMAQ_EDGE_SIGMA = 4,  // The function uses a method that outlines contours and
+                        // details by setting pixels to the mean value found in
+                        // their neighborhood, if their deviation from this
+                        // value is not significant.
+  IMAQ_EDGE_SOBEL = 5,  // The function uses a method that extracts the outer
+                        // contours of objects.
+  IMAQ_OUTLINE_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} OutlineMethod;
+
+typedef enum MorphologyMethod_enum {
+  IMAQ_AUTOM = 0,  // The function uses a transformation that generates simpler
+                   // particles that contain fewer details.
+  IMAQ_CLOSE = 1,  // The function uses a transformation that fills tiny holes
+                   // and smooths boundaries.
+  IMAQ_DILATE = 2,  // The function uses a transformation that eliminates tiny
+                    // holes isolated in particles and expands the contour of
+                    // the particles according to the template defined by the
+                    // structuring element.
+  IMAQ_ERODE = 3,  // The function uses a transformation that eliminates pixels
+                   // isolated in the background and erodes the contour of
+                   // particles according to the template defined by the
+                   // structuring element.
+  IMAQ_GRADIENT = 4,  // The function uses a transformation that leaves only the
+                      // pixels that would be added by the dilation process or
+                      // eliminated by the erosion process.
+  IMAQ_GRADIENTOUT = 5,  // The function uses a transformation that leaves only
+                         // the pixels that would be added by the dilation
+                         // process.
+  IMAQ_GRADIENTIN = 6,  // The function uses a transformation that leaves only
+                        // the pixels that would be eliminated by the erosion
+                        // process.
+  IMAQ_HITMISS = 7,  // The function uses a transformation that extracts each
+                     // pixel located in a neighborhood exactly matching the
+                     // template defined by the structuring element.
+  IMAQ_OPEN = 8,  // The function uses a transformation that removes small
+                  // particles and smooths boundaries.
+  IMAQ_PCLOSE = 9,  // The function uses a transformation that fills tiny holes
+                    // and smooths the inner contour of particles according to
+                    // the template defined by the structuring element.
+  IMAQ_POPEN = 10,  // The function uses a transformation that removes small
+                    // particles and smooths the contour of particles according
+                    // to the template defined by the structuring element.
+  IMAQ_THICK = 11,  // The function uses a transformation that adds to an image
+                    // those pixels located in a neighborhood that matches a
+                    // template specified by the structuring element.
+  IMAQ_THIN = 12,  // The function uses a transformation that eliminates pixels
+                   // that are located in a neighborhood matching a template
+                   // specified by the structuring element.
+  IMAQ_MORPHOLOGY_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} MorphologyMethod;
+
+typedef enum MeterArcMode_enum {
+  IMAQ_METER_ARC_ROI = 0,  // The function uses the roi parameter and ignores
+                           // the base, start, and end parameters.
+  IMAQ_METER_ARC_POINTS = 1,  // The function uses the base,start, and end
+                              // parameters and ignores the roi parameter.
+  IMAQ_METER_ARC_MODE_SIZE_GUARD = 0xFFFFFFFF
+} MeterArcMode;
+
+typedef enum RakeDirection_enum {
+  IMAQ_LEFT_TO_RIGHT = 0,  // The function searches from the left side of the
+                           // search area to the right side of the search area.
+  IMAQ_RIGHT_TO_LEFT = 1,  // The function searches from the right side of the
+                           // search area to the left side of the search area.
+  IMAQ_TOP_TO_BOTTOM = 2,  // The function searches from the top side of the
+                           // search area to the bottom side of the search area.
+  IMAQ_BOTTOM_TO_TOP = 3,  // The function searches from the bottom side of the
+                           // search area to the top side of the search area.
+  IMAQ_RAKE_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} RakeDirection;
+
+typedef enum TruncateMode_enum {
+  IMAQ_TRUNCATE_LOW = 0,  // The function truncates low frequencies.
+  IMAQ_TRUNCATE_HIGH = 1,  // The function truncates high frequencies.
+  IMAQ_TRUNCATE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} TruncateMode;
+
+typedef enum AttenuateMode_enum {
+  IMAQ_ATTENUATE_LOW = 0,  // The function attenuates low frequencies.
+  IMAQ_ATTENUATE_HIGH = 1,  // The function attenuates high frequencies.
+  IMAQ_ATTENUATE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} AttenuateMode;
+
+typedef enum WindowThreadPolicy_enum {
+  IMAQ_CALLING_THREAD = 0,  // Using this policy, NI Vision creates windows in
+                            // the thread that makes the first display function
+                            // call for a given window number.
+  IMAQ_SEPARATE_THREAD = 1,  // Using this policy, NI Vision creates windows in
+                             // a separate thread and processes messages for the
+                             // windows automatically.
+  IMAQ_WINDOW_THREAD_POLICY_SIZE_GUARD = 0xFFFFFFFF
+} WindowThreadPolicy;
+
+typedef enum WindowOptions_enum {
+  IMAQ_WIND_RESIZABLE =
+      1,  // When present, the user may resize the window interactively.
+  IMAQ_WIND_TITLEBAR =
+      2,  // When present, the title bar on the window is visible.
+  IMAQ_WIND_CLOSEABLE = 4,  // When present, the close box is available.
+  IMAQ_WIND_TOPMOST = 8,  // When present, the window is always on top.
+  IMAQ_WINDOW_OPTIONS_SIZE_GUARD = 0xFFFFFFFF
+} WindowOptions;
+
+typedef enum WindowEventType_enum {
+  IMAQ_NO_EVENT =
+      0,  // No event occurred since the last call to imaqGetLastEvent().
+  IMAQ_CLICK_EVENT = 1,  // The user clicked on a window.
+  IMAQ_DRAW_EVENT = 2,  // The user drew an ROI in a window.
+  IMAQ_MOVE_EVENT = 3,  // The user moved a window.
+  IMAQ_SIZE_EVENT = 4,  // The user sized a window.
+  IMAQ_SCROLL_EVENT = 5,  // The user scrolled a window.
+  IMAQ_ACTIVATE_EVENT = 6,  // The user activated a window.
+  IMAQ_CLOSE_EVENT = 7,  // The user closed a window.
+  IMAQ_DOUBLE_CLICK_EVENT = 8,  // The user double-clicked in a window.
+  IMAQ_WINDOW_EVENT_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} WindowEventType;
+
+typedef enum VisionInfoType_enum {
+  IMAQ_ANY_VISION_INFO = 0,  // The function checks if any extra vision
+                             // information is associated with the image.
+  IMAQ_PATTERN_MATCHING_INFO = 1,  // The function checks if any pattern
+                                   // matching template information is
+                                   // associated with the image.
+  IMAQ_CALIBRATION_INFO = 2,  // The function checks if any calibration
+                              // information is associated with the image.
+  IMAQ_OVERLAY_INFO = 3,  // The function checks if any overlay information is
+                          // associated with the image.
+  IMAQ_VISION_INFO_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} VisionInfoType;
+
+typedef enum SearchStrategy_enum {
+  IMAQ_CONSERVATIVE = 1,  // Instructs the pattern matching algorithm to use the
+                          // largest possible amount of information from the
+                          // image at the expense of slowing down the speed of
+                          // the algorithm.
+  IMAQ_BALANCED = 2,  // Instructs the pattern matching algorithm to balance the
+                      // amount of information from the image it uses with the
+                      // speed of the algorithm.
+  IMAQ_AGGRESSIVE = 3,  // Instructs the pattern matching algorithm to use a
+                        // lower amount of information from the image, which
+                        // allows the algorithm to run quickly but at the
+                        // expense of accuracy.
+  IMAQ_VERY_AGGRESSIVE = 4,  // Instructs the pattern matching algorithm to use
+                             // the smallest possible amount of information from
+                             // the image, which allows the algorithm to run at
+                             // the highest speed possible but at the expense of
+                             // accuracy.
+  IMAQ_SEARCH_STRATEGY_SIZE_GUARD = 0xFFFFFFFF
+} SearchStrategy;
+
+typedef enum TwoEdgePolarityType_enum {
+  IMAQ_NONE = 0,  // The function ignores the polarity of the edges.
+  IMAQ_RISING_FALLING = 1,  // The polarity of the first edge is rising (dark to
+                            // light) and the polarity of the second edge is
+                            // falling (light to dark).
+  IMAQ_FALLING_RISING = 2,  // The polarity of the first edge is falling (light
+                            // to dark) and the polarity of the second edge is
+                            // rising (dark to light).
+  IMAQ_RISING_RISING = 3,  // The polarity of the first edge is rising (dark to
+                           // light) and the polarity of the second edge is
+                           // rising (dark to light).
+  IMAQ_FALLING_FALLING = 4,  // The polarity of the first edge is falling (light
+                             // to dark) and the polarity of the second edge is
+                             // falling (light to dark).
+  IMAQ_TWO_EDGE_POLARITY_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} TwoEdgePolarityType;
+
+typedef enum ObjectType_enum {
+  IMAQ_BRIGHT_OBJECTS = 0,  // The function detects bright objects.
+  IMAQ_DARK_OBJECTS = 1,  // The function detects dark objects.
+  IMAQ_OBJECT_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ObjectType;
+
+typedef enum Tool_enum {
+  IMAQ_NO_TOOL = -1,  // No tool is in the selected state.
+  IMAQ_SELECTION_TOOL =
+      0,  // The selection tool selects an existing ROI in an image.
+  IMAQ_POINT_TOOL = 1,  // The point tool draws a point on the image.
+  IMAQ_LINE_TOOL = 2,  // The line tool draws a line on the image.
+  IMAQ_RECTANGLE_TOOL =
+      3,  // The rectangle tool draws a rectangle on the image.
+  IMAQ_OVAL_TOOL = 4,  // The oval tool draws an oval on the image.
+  IMAQ_POLYGON_TOOL = 5,  // The polygon tool draws a polygon on the image.
+  IMAQ_CLOSED_FREEHAND_TOOL =
+      6,  // The closed freehand tool draws closed freehand shapes on the image.
+  IMAQ_ANNULUS_TOOL = 7,  // The annulus tool draws annuluses on the image.
+  IMAQ_ZOOM_TOOL = 8,  // The zoom tool controls the zoom of an image.
+  IMAQ_PAN_TOOL = 9,  // The pan tool shifts the view of the image.
+  IMAQ_POLYLINE_TOOL = 10,  // The polyline tool draws a series of connected
+                            // straight lines on the image.
+  IMAQ_FREEHAND_TOOL =
+      11,  // The freehand tool draws freehand lines on the image.
+  IMAQ_ROTATED_RECT_TOOL =
+      12,  // The rotated rectangle tool draws rotated rectangles on the image.
+  IMAQ_ZOOM_OUT_TOOL = 13,  // The zoom out tool controls the zoom of an image.
+  IMAQ_TOOL_SIZE_GUARD = 0xFFFFFFFF
+} Tool;
+
+typedef enum TIFFCompressionType_enum {
+  IMAQ_NO_COMPRESSION = 0,  // The function does not compress the TIFF file.
+  IMAQ_JPEG = 1,  // The function uses the JPEG compression algorithm to
+                  // compress the TIFF file.
+  IMAQ_RUN_LENGTH = 2,  // The function uses a run length compression algorithm
+                        // to compress the TIFF file.
+  IMAQ_ZIP = 3,  // The function uses the ZIP compression algorithm to compress
+                 // the TIFF file.
+  IMAQ_TIFF_COMPRESSION_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} TIFFCompressionType;
+
+typedef enum ThresholdMethod_enum {
+  IMAQ_THRESH_CLUSTERING = 0,  // The function uses a method that sorts the
+                               // histogram of the image within a discrete
+                               // number of classes corresponding to the number
+                               // of phases perceived in an image.
+  IMAQ_THRESH_ENTROPY = 1,  // The function uses a method that is best for
+                            // detecting particles that are present in minuscule
+                            // proportions on the image.
+  IMAQ_THRESH_METRIC = 2,  // The function uses a method that is well-suited for
+                           // images in which classes are not too
+                           // disproportionate.
+  IMAQ_THRESH_MOMENTS = 3,  // The function uses a method that is suited for
+                            // images that have poor contrast.
+  IMAQ_THRESH_INTERCLASS = 4,  // The function uses a method that is well-suited
+                               // for images in which classes have well
+                               // separated pixel value distributions.
+  IMAQ_THRESHOLD_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} ThresholdMethod;
+
+typedef enum TextAlignment_enum {
+  IMAQ_LEFT = 0,  // Left aligns the text at the reference point.
+  IMAQ_CENTER = 1,  // Centers the text around the reference point.
+  IMAQ_RIGHT = 2,  // Right aligns the text at the reference point.
+  IMAQ_TEXT_ALIGNMENT_SIZE_GUARD = 0xFFFFFFFF
+} TextAlignment;
+
+typedef enum SpokeDirection_enum {
+  IMAQ_OUTSIDE_TO_INSIDE = 0,  // The function searches from the outside of the
+                               // search area to the inside of the search area.
+  IMAQ_INSIDE_TO_OUTSIDE = 1,  // The function searches from the inside of the
+                               // search area to the outside of the search area.
+  IMAQ_SPOKE_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} SpokeDirection;
+
+typedef enum SkeletonMethod_enum {
+  IMAQ_SKELETON_L =
+      0,  // Uses an L-shaped structuring element in the skeleton function.
+  IMAQ_SKELETON_M =
+      1,  // Uses an M-shaped structuring element in the skeleton function.
+  IMAQ_SKELETON_INVERSE = 2,  // Uses an L-shaped structuring element on an
+                              // inverse of the image in the skeleton function.
+  IMAQ_SKELETON_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} SkeletonMethod;
+
+typedef enum VerticalTextAlignment_enum {
+  IMAQ_BOTTOM = 0,  // Aligns the bottom of the text at the reference point.
+  IMAQ_TOP = 1,  // Aligns the top of the text at the reference point.
+  IMAQ_BASELINE = 2,  // Aligns the baseline of the text at the reference point.
+  IMAQ_VERTICAL_TEXT_ALIGNMENT_SIZE_GUARD = 0xFFFFFFFF
+} VerticalTextAlignment;
+
+typedef enum CalibrationROI_enum {
+  IMAQ_FULL_IMAGE = 0,  // The correction function corrects the whole image,
+                        // regardless of the user-defined or calibration-defined
+                        // ROIs.
+  IMAQ_CALIBRATION_ROI = 1,  // The correction function corrects the area
+                             // defined by the calibration ROI.
+  IMAQ_USER_ROI = 2,  // The correction function corrects the area defined by
+                      // the user-defined ROI.
+  IMAQ_CALIBRATION_AND_USER_ROI =
+      3,  // The correction function corrects the area defined by the
+          // intersection of the user-defined ROI and the calibration ROI.
+  IMAQ_CALIBRATION_OR_USER_ROI =
+      4,  // The correction function corrects the area defined by the union of
+          // the user-defined ROI and the calibration ROI.
+  IMAQ_CALIBRATION_ROI_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationROI;
+
+typedef enum ContourType_enum {
+  IMAQ_EMPTY_CONTOUR = 0,  // The contour is empty.
+  IMAQ_POINT = 1,  // The contour represents a point.
+  IMAQ_LINE = 2,  // The contour represents a line.
+  IMAQ_RECT = 3,  // The contour represents a rectangle.
+  IMAQ_OVAL = 4,  // The contour represents an oval.
+  IMAQ_CLOSED_CONTOUR = 5,  // The contour represents a series of connected
+                            // points where the last point connects to the
+                            // first.
+  IMAQ_OPEN_CONTOUR = 6,  // The contour represents a series of connected points
+                          // where the last point does not connect to the first.
+  IMAQ_ANNULUS = 7,  // The contour represents an annulus.
+  IMAQ_ROTATED_RECT = 8,  // The contour represents a rotated rectangle.
+  IMAQ_CONTOUR_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ContourType;
+
+typedef enum MathTransformMethod_enum {
+  IMAQ_TRANSFORM_LINEAR = 0,  // The function uses linear remapping.
+  IMAQ_TRANSFORM_LOG = 1,  // The function uses logarithmic remapping.
+  IMAQ_TRANSFORM_EXP = 2,  // The function uses exponential remapping.
+  IMAQ_TRANSFORM_SQR = 3,  // The function uses square remapping.
+  IMAQ_TRANSFORM_SQRT = 4,  // The function uses square root remapping.
+  IMAQ_TRANSFORM_POWX = 5,  // The function uses power X remapping.
+  IMAQ_TRANSFORM_POW1X = 6,  // The function uses power 1/X remapping.
+  IMAQ_MATH_TRANSFORM_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} MathTransformMethod;
+
+typedef enum ComplexPlane_enum {
+  IMAQ_REAL =
+      0,  // The function operates on the real plane of the complex image.
+  IMAQ_IMAGINARY =
+      1,  // The function operates on the imaginary plane of the complex image.
+  IMAQ_MAGNITUDE =
+      2,  // The function operates on the magnitude plane of the complex image.
+  IMAQ_PHASE =
+      3,  // The function operates on the phase plane of the complex image.
+  IMAQ_COMPLEX_PLANE_SIZE_GUARD = 0xFFFFFFFF
+} ComplexPlane;
+
+typedef enum PaletteType_enum {
+  IMAQ_PALETTE_GRAY = 0,  // The function uses a palette that has a gradual
+                          // gray-level variation from black to white.
+  IMAQ_PALETTE_BINARY = 1,  // The function uses a palette of 16 cycles of 16
+                            // different colors that is useful with binary
+                            // images.
+  IMAQ_PALETTE_GRADIENT = 2,  // The function uses a palette that has a
+                              // gradation from red to white with a prominent
+                              // range of light blue in the upper value range.
+  IMAQ_PALETTE_RAINBOW = 3,  // The function uses a palette that has a gradation
+                             // from blue to red with a prominent range of
+                             // greens in the middle value range.
+  IMAQ_PALETTE_TEMPERATURE = 4,  // The function uses a palette that has a
+                                 // gradation from light brown to dark brown.
+  IMAQ_PALETTE_USER = 5,  // The function uses a palette defined by the user.
+  IMAQ_PALETTE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} PaletteType;
+
+typedef enum ColorSensitivity_enum {
+  IMAQ_SENSITIVITY_LOW = 0,  // Instructs the algorithm to divide the hue plane
+                             // into a low number of sectors, allowing for
+                             // simple color analysis.
+  IMAQ_SENSITIVITY_MED = 1,  // Instructs the algorithm to divide the hue plane
+                             // into a medium number of sectors, allowing for
+                             // color analysis that balances sensitivity and
+                             // complexity.
+  IMAQ_SENSITIVITY_HIGH = 2,  // Instructs the algorithm to divide the hue plane
+                              // into a high number of sectors, allowing for
+                              // complex, sensitive color analysis.
+  IMAQ_COLOR_SENSITIVITY_SIZE_GUARD = 0xFFFFFFFF
+} ColorSensitivity;
+
+typedef enum ColorMode_enum {
+  IMAQ_RGB =
+      0,  // The function operates in the RGB (Red, Blue, Green) color space.
+  IMAQ_HSL = 1,  // The function operates in the HSL (Hue, Saturation,
+                 // Luminance) color space.
+  IMAQ_HSV = 2,  // The function operates in the HSV (Hue, Saturation, Value)
+                 // color space.
+  IMAQ_HSI = 3,  // The function operates in the HSI (Hue, Saturation,
+                 // Intensity) color space.
+  IMAQ_CIE = 4,  // The function operates in the CIE L*a*b* color space.
+  IMAQ_CIEXYZ = 5,  // The function operates in the CIE XYZ color space.
+  IMAQ_COLOR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ColorMode;
+
+typedef enum DetectionMode_enum {
+  IMAQ_DETECT_PEAKS = 0,  // The function detects peaks.
+  IMAQ_DETECT_VALLEYS = 1,  // The function detects valleys.
+  IMAQ_DETECTION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DetectionMode;
+
+typedef enum CalibrationUnit_enum {
+  IMAQ_UNDEFINED = 0,  // The image does not have a defined unit of measurement.
+  IMAQ_ANGSTROM = 1,  // The unit of measure for the image is angstroms.
+  IMAQ_MICROMETER = 2,  // The unit of measure for the image is micrometers.
+  IMAQ_MILLIMETER = 3,  // The unit of measure for the image is millimeters.
+  IMAQ_CENTIMETER = 4,  // The unit of measure for the image is centimeters.
+  IMAQ_METER = 5,  // The unit of measure for the image is meters.
+  IMAQ_KILOMETER = 6,  // The unit of measure for the image is kilometers.
+  IMAQ_MICROINCH = 7,  // The unit of measure for the image is microinches.
+  IMAQ_INCH = 8,  // The unit of measure for the image is inches.
+  IMAQ_FOOT = 9,  // The unit of measure for the image is feet.
+  IMAQ_NAUTICMILE = 10,  // The unit of measure for the image is nautical miles.
+  IMAQ_GROUNDMILE = 11,  // The unit of measure for the image is ground miles.
+  IMAQ_STEP = 12,  // The unit of measure for the image is steps.
+  IMAQ_CALIBRATION_UNIT_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationUnit;
+
+typedef enum ConcentricRakeDirection_enum {
+  IMAQ_COUNTER_CLOCKWISE = 0,  // The function searches the search area in a
+                               // counter-clockwise direction.
+  IMAQ_CLOCKWISE =
+      1,  // The function searches the search area in a clockwise direction.
+  IMAQ_CONCENTRIC_RAKE_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} ConcentricRakeDirection;
+
+typedef enum CalibrationMode_enum {
+  IMAQ_PERSPECTIVE = 0,  // Functions correct for distortion caused by the
+                         // camera's perspective.
+  IMAQ_NONLINEAR =
+      1,  // Functions correct for distortion caused by the camera's lens.
+  IMAQ_SIMPLE_CALIBRATION = 2,  // Functions do not correct for distortion.
+  IMAQ_CORRECTED_IMAGE = 3,  // The image is already corrected.
+  IMAQ_CALIBRATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationMode;
+
+typedef enum BrowserLocation_enum {
+  IMAQ_INSERT_FIRST_FREE =
+      0,  // Inserts the thumbnail in the first available cell.
+  IMAQ_INSERT_END = 1,  // Inserts the thumbnail after the last occupied cell.
+  IMAQ_BROWSER_LOCATION_SIZE_GUARD = 0xFFFFFFFF
+} BrowserLocation;
+
+typedef enum BrowserFrameStyle_enum {
+  IMAQ_RAISED_FRAME = 0,  // Each thumbnail has a raised frame.
+  IMAQ_BEVELLED_FRAME = 1,  // Each thumbnail has a beveled frame.
+  IMAQ_OUTLINE_FRAME = 2,  // Each thumbnail has an outlined frame.
+  IMAQ_HIDDEN_FRAME = 3,  // Each thumbnail has a hidden frame.
+  IMAQ_STEP_FRAME = 4,  // Each thumbnail has a stepped frame.
+  IMAQ_RAISED_OUTLINE_FRAME =
+      5,  // Each thumbnail has a raised, outlined frame.
+  IMAQ_BROWSER_FRAME_STYLE_SIZE_GUARD = 0xFFFFFFFF
+} BrowserFrameStyle;
+
+typedef enum BorderMethod_enum {
+  IMAQ_BORDER_MIRROR =
+      0,  // Symmetrically copies pixel values from the image into the border.
+  IMAQ_BORDER_COPY = 1,  // Copies the value of the pixel closest to the edge of
+                         // the image into the border.
+  IMAQ_BORDER_CLEAR = 2,  // Sets all pixels in the border to 0.
+  IMAQ_BORDER_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} BorderMethod;
+
+typedef enum BarcodeType_enum {
+  IMAQ_INVALID = -1,  // The barcode is not of a type known by NI Vision.
+  IMAQ_CODABAR = 1,  // The barcode is of type Codabar.
+  IMAQ_CODE39 = 2,  // The barcode is of type Code 39.
+  IMAQ_CODE93 = 4,  // The barcode is of type Code 93.
+  IMAQ_CODE128 = 8,  // The barcode is of type Code 128.
+  IMAQ_EAN8 = 16,  // The barcode is of type EAN 8.
+  IMAQ_EAN13 = 32,  // The barcode is of type EAN 13.
+  IMAQ_I2_OF_5 = 64,  // The barcode is of type Code 25.
+  IMAQ_MSI = 128,  // The barcode is of type MSI code.
+  IMAQ_UPCA = 256,  // The barcode is of type UPC A.
+  IMAQ_PHARMACODE = 512,  // The barcode is of type Pharmacode.
+  IMAQ_RSS_LIMITED = 1024,  // The barcode is of type RSS Limited.
+  IMAQ_BARCODE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} BarcodeType;
+
+typedef enum AxisOrientation_enum {
+  IMAQ_DIRECT = 0,  // The y-axis direction corresponds to the y-axis direction
+                    // of the Cartesian coordinate system.
+  IMAQ_INDIRECT = 1,  // The y-axis direction corresponds to the y-axis
+                      // direction of an image.
+  IMAQ_AXIS_ORIENTATION_SIZE_GUARD = 0xFFFFFFFF
+} AxisOrientation;
+
+typedef enum ColorIgnoreMode_enum {
+  IMAQ_IGNORE_NONE =
+      0,  // Specifies that the function does not ignore any pixels.
+  IMAQ_IGNORE_BLACK = 1,  // Specifies that the function ignores black pixels.
+  IMAQ_IGNORE_WHITE = 2,  // Specifies that the function ignores white pixels.
+  IMAQ_IGNORE_BLACK_AND_WHITE =
+      3,  // Specifies that the function ignores black pixels and white pixels.
+  IMAQ_BLACK_WHITE_IGNORE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ColorIgnoreMode;
+
+typedef enum LevelType_enum {
+  IMAQ_ABSOLUTE = 0,  // The function evaluates the threshold and hysteresis
+                      // values as absolute values.
+  IMAQ_RELATIVE = 1,  // The function evaluates the threshold and hysteresis
+                      // values relative to the dynamic range of the given path.
+  IMAQ_LEVEL_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} LevelType;
+
+typedef enum MatchingMode_enum {
+  IMAQ_MATCH_SHIFT_INVARIANT = 1,  // Searches for occurrences of the template
+                                   // image anywhere in the searchRect, assuming
+                                   // that the pattern is not rotated more than
+                                   // plus or minus 4 degrees.
+  IMAQ_MATCH_ROTATION_INVARIANT = 2,  // Searches for occurrences of the pattern
+                                      // in the image with no restriction on the
+                                      // rotation of the pattern.
+  IMAQ_MATCHING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} MatchingMode;
+
+typedef enum MappingMethod_enum {
+  IMAQ_FULL_DYNAMIC = 0,  //(Obsolete) When the image bit depth is 0, the
+                          //function maps the full dynamic range of the 16-bit
+                          //image to an 8-bit scale.
+  IMAQ_DOWNSHIFT = 1,  //(Obsolete) When the image bit depth is 0, the function
+                       //shifts the 16-bit image pixels to the right the number
+                       //of times specified by the shiftCount element of the
+                       //DisplayMapping structure.
+  IMAQ_RANGE = 2,  //(Obsolete) When the image bit depth is 0, the function maps
+                   //the pixel values in the range specified by the minimumValue
+                   //and maximumValue elements of the DisplayMapping structure
+                   //to an 8-bit scale.
+  IMAQ_90_PCT_DYNAMIC =
+      3,  //(Obsolete) When the image bit depth to 0, the function maps the
+          //dynamic range containing the middle 90 percent of the cumulated
+          //histogram of the image to an 8-bit (256 grayscale values) scale.
+  IMAQ_PERCENT_RANGE = 4,  //(Obsolete) When the image bit depth is 0, the
+                           //function maps the pixel values in the relative
+                           //percentage range (0 to 100) of the cumulated
+                           //histogram specified by minimumValue and
+                           //maximumValue to an 8-bit scale.
+  IMAQ_DEFAULT_MAPPING =
+      10,  // If the bit depth is 0, the function maps the 16-bit image to 8
+           // bits by following the IMAQ_FULL_DYNAMIC_ALWAYS behavior;
+           // otherwise, the function shifts the image data to the right
+           // according to the IMAQ_MOST_SIGNIFICANT behavior.
+  IMAQ_MOST_SIGNIFICANT = 11,  // The function shifts the 16-bit image pixels to
+                               // the right until the 8 most significant bits of
+                               // the image data are remaining.
+  IMAQ_FULL_DYNAMIC_ALWAYS = 12,  // The function maps the full dynamic range of
+                                  // the 16-bit image to an 8-bit scale.
+  IMAQ_DOWNSHIFT_ALWAYS = 13,  // The function shifts the 16-bit image pixels to
+                               // the right the number of times specified by the
+                               // shiftCount element of the DisplayMapping
+                               // structure.
+  IMAQ_RANGE_ALWAYS = 14,  // The function maps the pixel values in the range
+                           // specified by the minimumValue and maximumValue
+                           // elements of the DisplayMapping structure to an
+                           // 8-bit scale.
+  IMAQ_90_PCT_DYNAMIC_ALWAYS = 15,  // The function maps the dynamic range
+                                    // containing the middle 90 percent of the
+                                    // cumulated histogram of the image to an
+                                    // 8-bit (256 grayscale values) scale.
+  IMAQ_PERCENT_RANGE_ALWAYS =
+      16,  // The function maps the pixel values in the relative percentage
+           // range (0 to 100) of the cumulated histogram specified by
+           // minimumValue and maximumValue to an 8-bit scale.
+  IMAQ_MAPPING_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} MappingMethod;
+
+typedef enum ComparisonFunction_enum {
+  IMAQ_CLEAR_LESS = 0,  // The comparison is true if the source pixel value is
+                        // less than the comparison image pixel value.
+  IMAQ_CLEAR_LESS_OR_EQUAL = 1,  // The comparison is true if the source pixel
+                                 // value is less than or equal to the
+                                 // comparison image pixel value.
+  IMAQ_CLEAR_EQUAL = 2,  // The comparison is true if the source pixel value is
+                         // equal to the comparison image pixel value.
+  IMAQ_CLEAR_GREATER_OR_EQUAL = 3,  // The comparison is true if the source
+                                    // pixel value is greater than or equal to
+                                    // the comparison image pixel value.
+  IMAQ_CLEAR_GREATER = 4,  // The comparison is true if the source pixel value
+                           // is greater than the comparison image pixel value.
+  IMAQ_COMPARE_FUNCTION_SIZE_GUARD = 0xFFFFFFFF
+} ComparisonFunction;
+
+typedef enum LineGaugeMethod_enum {
+  IMAQ_EDGE_TO_EDGE = 0,  // Measures from the first edge on the line to the
+                          // last edge on the line.
+  IMAQ_EDGE_TO_POINT = 1,  // Measures from the first edge on the line to the
+                           // end point of the line.
+  IMAQ_POINT_TO_EDGE = 2,  // Measures from the start point of the line to the
+                           // first edge on the line.
+  IMAQ_POINT_TO_POINT = 3,  // Measures from the start point of the line to the
+                            // end point of the line.
+  IMAQ_LINE_GAUGE_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} LineGaugeMethod;
+
+typedef enum Direction3D_enum {
+  IMAQ_3D_NW = 0,  // The viewing angle for the 3D image is from the northwest.
+  IMAQ_3D_SW = 1,  // The viewing angle for the 3D image is from the southwest.
+  IMAQ_3D_SE = 2,  // The viewing angle for the 3D image is from the southeast.
+  IMAQ_3D_NE = 3,  // The viewing angle for the 3D image is from the northeast.
+  IMAQ_DIRECTION_3D_SIZE_GUARD = 0xFFFFFFFF
+} Direction3D;
+
+typedef enum LearningMode_enum {
+  IMAQ_LEARN_ALL = 0,  // The function extracts information for shift- and
+                       // rotation-invariant matching.
+  IMAQ_LEARN_SHIFT_INFORMATION =
+      1,  // The function extracts information for shift-invariant matching.
+  IMAQ_LEARN_ROTATION_INFORMATION =
+      2,  // The function extracts information for rotation-invariant matching.
+  IMAQ_LEARNING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} LearningMode;
+
+typedef enum KernelFamily_enum {
+  IMAQ_GRADIENT_FAMILY = 0,  // The kernel is in the gradient family.
+  IMAQ_LAPLACIAN_FAMILY = 1,  // The kernel is in the Laplacian family.
+  IMAQ_SMOOTHING_FAMILY = 2,  // The kernel is in the smoothing family.
+  IMAQ_GAUSSIAN_FAMILY = 3,  // The kernel is in the Gaussian family.
+  IMAQ_KERNEL_FAMILY_SIZE_GUARD = 0xFFFFFFFF
+} KernelFamily;
+
+typedef enum InterpolationMethod_enum {
+  IMAQ_ZERO_ORDER = 0,  // The function uses an interpolation method that
+                        // interpolates new pixel values using the nearest valid
+                        // neighboring pixel.
+  IMAQ_BILINEAR = 1,  // The function uses an interpolation method that
+                      // interpolates new pixel values using a bidirectional
+                      // average of the neighboring pixels.
+  IMAQ_QUADRATIC = 2,  // The function uses an interpolation method that
+                       // interpolates new pixel values using a quadratic
+                       // approximating polynomial.
+  IMAQ_CUBIC_SPLINE = 3,  // The function uses an interpolation method that
+                          // interpolates new pixel values by fitting them to a
+                          // cubic spline curve, where the curve is based on
+                          // known pixel values from the image.
+  IMAQ_BILINEAR_FIXED = 4,  // The function uses an interpolation method that
+                            // interpolates new pixel values using a
+                            // bidirectional average of the neighboring pixels.
+  IMAQ_INTERPOLATION_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} InterpolationMethod;
+
+typedef enum ImageType_enum {
+  IMAQ_IMAGE_U8 = 0,  // The image type is 8-bit unsigned integer grayscale.
+  IMAQ_IMAGE_U16 = 7,  // The image type is 16-bit unsigned integer grayscale.
+  IMAQ_IMAGE_I16 = 1,  // The image type is 16-bit signed integer grayscale.
+  IMAQ_IMAGE_SGL = 2,  // The image type is 32-bit floating-point grayscale.
+  IMAQ_IMAGE_COMPLEX = 3,  // The image type is complex.
+  IMAQ_IMAGE_RGB = 4,  // The image type is RGB color.
+  IMAQ_IMAGE_HSL = 5,  // The image type is HSL color.
+  IMAQ_IMAGE_RGB_U64 = 6,  // The image type is 64-bit unsigned RGB color.
+  IMAQ_IMAGE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ImageType;
+
+typedef enum ImageFeatureMode_enum {
+  IMAQ_COLOR_AND_SHAPE_FEATURES = 0,  // Instructs the function to use the color
+                                      // and the shape features of the color
+                                      // pattern.
+  IMAQ_COLOR_FEATURES = 1,  // Instructs the function to use the color features
+                            // of the color pattern.
+  IMAQ_SHAPE_FEATURES = 2,  // Instructs the function to use the shape features
+                            // of the color pattern.
+  IMAQ_FEATURE_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ImageFeatureMode;
+
+typedef enum FontColor_enum {
+  IMAQ_WHITE = 0,  // Draws text in white.
+  IMAQ_BLACK = 1,  // Draws text in black.
+  IMAQ_INVERT = 2,  // Inverts the text pixels.
+  IMAQ_BLACK_ON_WHITE = 3,  // Draws text in black with a white background.
+  IMAQ_WHITE_ON_BLACK = 4,  // Draws text in white with a black background.
+  IMAQ_FONT_COLOR_SIZE_GUARD = 0xFFFFFFFF
+} FontColor;
+
+typedef enum FlipAxis_enum {
+  IMAQ_HORIZONTAL_AXIS =
+      0,  // Flips the image over the central horizontal axis.
+  IMAQ_VERTICAL_AXIS = 1,  // Flips the image over the central vertical axis.
+  IMAQ_CENTER_AXIS =
+      2,  // Flips the image over both the central vertical and horizontal axes.
+  IMAQ_DIAG_L_TO_R_AXIS = 3,  // Flips the image over an axis from the upper
+                              // left corner to lower right corner.
+  IMAQ_DIAG_R_TO_L_AXIS = 4,  // Flips the image over an axis from the upper
+                              // right corner to lower left corner.
+  IMAQ_FLIP_AXIS_SIZE_GUARD = 0xFFFFFFFF
+} FlipAxis;
+
+typedef enum EdgeProcess_enum {
+  IMAQ_FIRST = 0,  // The function looks for the first edge.
+  IMAQ_FIRST_AND_LAST = 1,  // The function looks for the first and last edge.
+  IMAQ_ALL = 2,  // The function looks for all edges.
+  IMAQ_BEST = 3,  // The function looks for the best edge.
+  IMAQ_EDGE_PROCESS_SIZE_GUARD = 0xFFFFFFFF
+} EdgeProcess;
+
+typedef enum DrawMode_enum {
+  IMAQ_DRAW_VALUE =
+      0,  // Draws the boundary of the object with the specified pixel value.
+  IMAQ_DRAW_INVERT =
+      2,  // Inverts the pixel values of the boundary of the object.
+  IMAQ_PAINT_VALUE = 1,  // Fills the object with the given pixel value.
+  IMAQ_PAINT_INVERT = 3,  // Inverts the pixel values of the object.
+  IMAQ_HIGHLIGHT_VALUE = 4,  // The function fills the object by highlighting
+                             // the enclosed pixels with the color of the
+                             // object.
+  IMAQ_DRAW_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DrawMode;
+
+typedef enum NearestNeighborMetric_enum {
+  IMAQ_METRIC_MAXIMUM = 0,  // The maximum metric.
+  IMAQ_METRIC_SUM = 1,  // The sum metric.
+  IMAQ_METRIC_EUCLIDEAN = 2,  // The Euclidean metric.
+  IMAQ_NEAREST_NEIGHBOR_METRIC_SIZE_GUARD = 0xFFFFFFFF
+} NearestNeighborMetric;
+
+typedef enum ReadResolution_enum {
+  IMAQ_LOW_RESOLUTION =
+      0,  // Configures NI Vision to use low resolution during the read process.
+  IMAQ_MEDIUM_RESOLUTION = 1,  // Configures NI Vision to use medium resolution
+                               // during the read process.
+  IMAQ_HIGH_RESOLUTION = 2,  // Configures NI Vision to use high resolution
+                             // during the read process.
+  IMAQ_READ_RESOLUTION_SIZE_GUARD = 0xFFFFFFFF
+} ReadResolution;
+
+typedef enum ThresholdMode_enum {
+  IMAQ_FIXED_RANGE = 0,  // Performs thresholding using the values you provide
+                         // in the lowThreshold and highThreshold elements of
+                         // OCRProcessingOptions.
+  IMAQ_COMPUTED_UNIFORM =
+      1,  // Calculates a single threshold value for the entire ROI.
+  IMAQ_COMPUTED_LINEAR = 2,  // Calculates a value on the left side of the ROI,
+                             // calculates a value on the right side of the ROI,
+                             // and linearly fills the middle values from left
+                             // to right.
+  IMAQ_COMPUTED_NONLINEAR = 3,  // Divides the ROI into the number of blocks
+                                // specified by the blockCount element of
+                                // OCRProcessingOptions and calculates a
+                                // threshold value for each block.
+  IMAQ_THRESHOLD_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ThresholdMode;
+
+typedef enum ReadStrategy_enum {
+  IMAQ_READ_AGGRESSIVE = 0,  // Configures NI Vision to perform fewer checks
+                             // when analyzing objects to determine if they
+                             // match trained characters.
+  IMAQ_READ_CONSERVATIVE = 1,  // Configures NI Vision to perform more checks to
+                               // determine if an object matches a trained
+                               // character.
+  IMAQ_READ_STRATEGY_SIZE_GUARD = 0xFFFFFFFF
+} ReadStrategy;
+
+typedef enum MeasurementType_enum {
+  IMAQ_MT_CENTER_OF_MASS_X = 0,  // X-coordinate of the point representing the
+                                 // average position of the total particle mass,
+                                 // assuming every point in the particle has a
+                                 // constant density.
+  IMAQ_MT_CENTER_OF_MASS_Y = 1,  // Y-coordinate of the point representing the
+                                 // average position of the total particle mass,
+                                 // assuming every point in the particle has a
+                                 // constant density.
+  IMAQ_MT_FIRST_PIXEL_X =
+      2,  // X-coordinate of the highest, leftmost particle pixel.
+  IMAQ_MT_FIRST_PIXEL_Y =
+      3,  // Y-coordinate of the highest, leftmost particle pixel.
+  IMAQ_MT_BOUNDING_RECT_LEFT =
+      4,  // X-coordinate of the leftmost particle point.
+  IMAQ_MT_BOUNDING_RECT_TOP = 5,  // Y-coordinate of highest particle point.
+  IMAQ_MT_BOUNDING_RECT_RIGHT =
+      6,  // X-coordinate of the rightmost particle point.
+  IMAQ_MT_BOUNDING_RECT_BOTTOM =
+      7,  // Y-coordinate of the lowest particle point.
+  IMAQ_MT_MAX_FERET_DIAMETER_START_X =
+      8,  // X-coordinate of the start of the line segment connecting the two
+          // perimeter points that are the furthest apart.
+  IMAQ_MT_MAX_FERET_DIAMETER_START_Y =
+      9,  // Y-coordinate of the start of the line segment connecting the two
+          // perimeter points that are the furthest apart.
+  IMAQ_MT_MAX_FERET_DIAMETER_END_X =
+      10,  // X-coordinate of the end of the line segment connecting the two
+           // perimeter points that are the furthest apart.
+  IMAQ_MT_MAX_FERET_DIAMETER_END_Y =
+      11,  // Y-coordinate of the end of the line segment connecting the two
+           // perimeter points that are the furthest apart.
+  IMAQ_MT_MAX_HORIZ_SEGMENT_LENGTH_LEFT =
+      12,  // X-coordinate of the leftmost pixel in the longest row of
+           // contiguous pixels in the particle.
+  IMAQ_MT_MAX_HORIZ_SEGMENT_LENGTH_RIGHT =
+      13,  // X-coordinate of the rightmost pixel in the longest row of
+           // contiguous pixels in the particle.
+  IMAQ_MT_MAX_HORIZ_SEGMENT_LENGTH_ROW =
+      14,  // Y-coordinate of all of the pixels in the longest row of contiguous
+           // pixels in the particle.
+  IMAQ_MT_BOUNDING_RECT_WIDTH =
+      16,  // Distance between the x-coordinate of the leftmost particle point
+           // and the x-coordinate of the rightmost particle point.
+  IMAQ_MT_BOUNDING_RECT_HEIGHT =
+      17,  // Distance between the y-coordinate of highest particle point and
+           // the y-coordinate of the lowest particle point.
+  IMAQ_MT_BOUNDING_RECT_DIAGONAL =
+      18,  // Distance between opposite corners of the bounding rectangle.
+  IMAQ_MT_PERIMETER = 19,  // Length of the outer boundary of the particle.
+  IMAQ_MT_CONVEX_HULL_PERIMETER = 20,  // Perimeter of the smallest convex
+                                       // polygon containing all points in the
+                                       // particle.
+  IMAQ_MT_HOLES_PERIMETER =
+      21,  // Sum of the perimeters of each hole in the particle.
+  IMAQ_MT_MAX_FERET_DIAMETER = 22,  // Distance between the start and end of the
+                                    // line segment connecting the two perimeter
+                                    // points that are the furthest apart.
+  IMAQ_MT_EQUIVALENT_ELLIPSE_MAJOR_AXIS =
+      23,  // Length of the major axis of the ellipse with the same perimeter
+           // and area as the particle.
+  IMAQ_MT_EQUIVALENT_ELLIPSE_MINOR_AXIS =
+      24,  // Length of the minor axis of the ellipse with the same perimeter
+           // and area as the particle.
+  IMAQ_MT_EQUIVALENT_ELLIPSE_MINOR_AXIS_FERET =
+      25,  // Length of the minor axis of the ellipse with the same area as the
+           // particle, and Major Axis equal in length to the Max Feret
+           // Diameter.
+  IMAQ_MT_EQUIVALENT_RECT_LONG_SIDE = 26,  // Longest side of the rectangle with
+                                           // the same perimeter and area as the
+                                           // particle.
+  IMAQ_MT_EQUIVALENT_RECT_SHORT_SIDE = 27,  // Shortest side of the rectangle
+                                            // with the same perimeter and area
+                                            // as the particle.
+  IMAQ_MT_EQUIVALENT_RECT_DIAGONAL = 28,  // Distance between opposite corners
+                                          // of the rectangle with the same
+                                          // perimeter and area as the particle.
+  IMAQ_MT_EQUIVALENT_RECT_SHORT_SIDE_FERET =
+      29,  // Shortest side of the rectangle with the same area as the particle,
+           // and longest side equal in length to the Max Feret Diameter.
+  IMAQ_MT_AVERAGE_HORIZ_SEGMENT_LENGTH =
+      30,  // Average length of a horizontal segment in the particle.
+  IMAQ_MT_AVERAGE_VERT_SEGMENT_LENGTH =
+      31,  // Average length of a vertical segment in the particle.
+  IMAQ_MT_HYDRAULIC_RADIUS =
+      32,  // The particle area divided by the particle perimeter.
+  IMAQ_MT_WADDEL_DISK_DIAMETER =
+      33,  // Diameter of a disk with the same area as the particle.
+  IMAQ_MT_AREA = 35,  // Area of the particle.
+  IMAQ_MT_HOLES_AREA = 36,  // Sum of the areas of each hole in the particle.
+  IMAQ_MT_PARTICLE_AND_HOLES_AREA =
+      37,  // Area of a particle that completely covers the image.
+  IMAQ_MT_CONVEX_HULL_AREA = 38,  // Area of the smallest convex polygon
+                                  // containing all points in the particle.
+  IMAQ_MT_IMAGE_AREA = 39,  // Area of the image.
+  IMAQ_MT_NUMBER_OF_HOLES = 41,  // Number of holes in the particle.
+  IMAQ_MT_NUMBER_OF_HORIZ_SEGMENTS =
+      42,  // Number of horizontal segments in the particle.
+  IMAQ_MT_NUMBER_OF_VERT_SEGMENTS =
+      43,  // Number of vertical segments in the particle.
+  IMAQ_MT_ORIENTATION = 45,  // The angle of the line that passes through the
+                             // particle Center of Mass about which the particle
+                             // has the lowest moment of inertia.
+  IMAQ_MT_MAX_FERET_DIAMETER_ORIENTATION =
+      46,  // The angle of the line segment connecting the two perimeter points
+           // that are the furthest apart.
+  IMAQ_MT_AREA_BY_IMAGE_AREA =
+      48,  // Percentage of the particle Area covering the Image Area.
+  IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA = 49,  // Percentage of the particle
+                                                 // Area in relation to its
+                                                 // Particle and Holes Area.
+  IMAQ_MT_RATIO_OF_EQUIVALENT_ELLIPSE_AXES = 50,  // Equivalent Ellipse Major
+                                                  // Axis divided by Equivalent
+                                                  // Ellipse Minor Axis.
+  IMAQ_MT_RATIO_OF_EQUIVALENT_RECT_SIDES =
+      51,  // Equivalent Rect Long Side divided by Equivalent Rect Short Side.
+  IMAQ_MT_ELONGATION_FACTOR =
+      53,  // Max Feret Diameter divided by Equivalent Rect Short Side (Feret).
+  IMAQ_MT_COMPACTNESS_FACTOR = 54,  // Area divided by the product of Bounding
+                                    // Rect Width and Bounding Rect Height.
+  IMAQ_MT_HEYWOOD_CIRCULARITY_FACTOR = 55,  // Perimeter divided by the
+                                            // circumference of a circle with
+                                            // the same area.
+  IMAQ_MT_TYPE_FACTOR = 56,  // Factor relating area to moment of inertia.
+  IMAQ_MT_SUM_X = 58,  // The sum of all x-coordinates in the particle.
+  IMAQ_MT_SUM_Y = 59,  // The sum of all y-coordinates in the particle.
+  IMAQ_MT_SUM_XX = 60,  // The sum of all x-coordinates squared in the particle.
+  IMAQ_MT_SUM_XY =
+      61,  // The sum of all x-coordinates times y-coordinates in the particle.
+  IMAQ_MT_SUM_YY = 62,  // The sum of all y-coordinates squared in the particle.
+  IMAQ_MT_SUM_XXX = 63,  // The sum of all x-coordinates cubed in the particle.
+  IMAQ_MT_SUM_XXY = 64,  // The sum of all x-coordinates squared times
+                         // y-coordinates in the particle.
+  IMAQ_MT_SUM_XYY = 65,  // The sum of all x-coordinates times y-coordinates
+                         // squared in the particle.
+  IMAQ_MT_SUM_YYY = 66,  // The sum of all y-coordinates cubed in the particle.
+  IMAQ_MT_MOMENT_OF_INERTIA_XX =
+      68,  // The moment of inertia in the x-direction twice.
+  IMAQ_MT_MOMENT_OF_INERTIA_XY =
+      69,  // The moment of inertia in the x and y directions.
+  IMAQ_MT_MOMENT_OF_INERTIA_YY =
+      70,  // The moment of inertia in the y-direction twice.
+  IMAQ_MT_MOMENT_OF_INERTIA_XXX =
+      71,  // The moment of inertia in the x-direction three times.
+  IMAQ_MT_MOMENT_OF_INERTIA_XXY = 72,  // The moment of inertia in the
+                                       // x-direction twice and the y-direction
+                                       // once.
+  IMAQ_MT_MOMENT_OF_INERTIA_XYY = 73,  // The moment of inertia in the
+                                       // x-direction once and the y-direction
+                                       // twice.
+  IMAQ_MT_MOMENT_OF_INERTIA_YYY =
+      74,  // The moment of inertia in the y-direction three times.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_XX =
+      75,  // The normalized moment of inertia in the x-direction twice.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_XY =
+      76,  // The normalized moment of inertia in the x- and y-directions.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_YY =
+      77,  // The normalized moment of inertia in the y-direction twice.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_XXX =
+      78,  // The normalized moment of inertia in the x-direction three times.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_XXY = 79,  // The normalized moment of inertia
+                                            // in the x-direction twice and the
+                                            // y-direction once.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_XYY = 80,  // The normalized moment of inertia
+                                            // in the x-direction once and the
+                                            // y-direction twice.
+  IMAQ_MT_NORM_MOMENT_OF_INERTIA_YYY =
+      81,  // The normalized moment of inertia in the y-direction three times.
+  IMAQ_MT_HU_MOMENT_1 = 82,  // The first Hu moment.
+  IMAQ_MT_HU_MOMENT_2 = 83,  // The second Hu moment.
+  IMAQ_MT_HU_MOMENT_3 = 84,  // The third Hu moment.
+  IMAQ_MT_HU_MOMENT_4 = 85,  // The fourth Hu moment.
+  IMAQ_MT_HU_MOMENT_5 = 86,  // The fifth Hu moment.
+  IMAQ_MT_HU_MOMENT_6 = 87,  // The sixth Hu moment.
+  IMAQ_MT_HU_MOMENT_7 = 88,  // The seventh Hu moment.
+  IMAQ_MEASUREMENT_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} MeasurementType;
+
+typedef enum GeometricMatchingMode_enum {
+  IMAQ_GEOMETRIC_MATCH_SHIFT_INVARIANT =
+      0,  // Searches for occurrences of the pattern in the image, assuming that
+          // the pattern is not rotated more than plus or minus 5 degrees.
+  IMAQ_GEOMETRIC_MATCH_ROTATION_INVARIANT =
+      1,  // Searches for occurrences of the pattern in the image with reduced
+          // restriction on the rotation of the pattern.
+  IMAQ_GEOMETRIC_MATCH_SCALE_INVARIANT =
+      2,  // Searches for occurrences of the pattern in the image with reduced
+          // restriction on the size of the pattern.
+  IMAQ_GEOMETRIC_MATCH_OCCLUSION_INVARIANT =
+      4,  // Searches for occurrences of the pattern in the image, allowing for
+          // a specified percentage of the pattern to be occluded.
+  IMAQ_GEOMETRIC_MATCHING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} GeometricMatchingMode;
+
+typedef enum ButtonLabel_enum {
+  IMAQ_BUTTON_OK = 0,  // The label "OK".
+  IMAQ_BUTTON_SAVE = 1,  // The label "Save".
+  IMAQ_BUTTON_SELECT = 2,  // The label "Select".
+  IMAQ_BUTTON_LOAD = 3,  // The label "Load".
+  IMAQ_BUTTON_LABEL_SIZE_GUARD = 0xFFFFFFFF
+} ButtonLabel;
+
+typedef enum NearestNeighborMethod_enum {
+  IMAQ_MINIMUM_MEAN_DISTANCE = 0,  // The minimum mean distance method.
+  IMAQ_K_NEAREST_NEIGHBOR = 1,  // The k-nearest neighbor method.
+  IMAQ_NEAREST_PROTOTYPE = 2,  // The nearest prototype method.
+  IMAQ_NEAREST_NEIGHBOR_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} NearestNeighborMethod;
+
+typedef enum QRMirrorMode_enum {
+  IMAQ_QR_MIRROR_MODE_AUTO_DETECT =
+      -2,  // The function should determine if the QR code is mirrored.
+  IMAQ_QR_MIRROR_MODE_MIRRORED =
+      1,  // The function should expect the QR code to appear mirrored.
+  IMAQ_QR_MIRROR_MODE_NORMAL =
+      0,  // The function should expect the QR code to appear normal.
+  IMAQ_QR_MIRROR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRMirrorMode;
+
+typedef enum ColumnProcessingMode_enum {
+  IMAQ_AVERAGE_COLUMNS = 0,  // Averages the data extracted for edge detection.
+  IMAQ_MEDIAN_COLUMNS =
+      1,  // Takes the median of the data extracted for edge detection.
+  IMAQ_COLUMN_PROCESSING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ColumnProcessingMode;
+
+typedef enum FindReferenceDirection_enum {
+  IMAQ_LEFT_TO_RIGHT_DIRECT = 0,  // Searches from the left side of the search
+                                  // area to the right side of the search area
+                                  // for a direct axis.
+  IMAQ_LEFT_TO_RIGHT_INDIRECT = 1,  // Searches from the left side of the search
+                                    // area to the right side of the search area
+                                    // for an indirect axis.
+  IMAQ_TOP_TO_BOTTOM_DIRECT = 2,  // Searches from the top of the search area to
+                                  // the bottom of the search area for a direct
+                                  // axis.
+  IMAQ_TOP_TO_BOTTOM_INDIRECT = 3,  // Searches from the top of the search area
+                                    // to the bottom of the search area for an
+                                    // indirect axis.
+  IMAQ_RIGHT_TO_LEFT_DIRECT = 4,  // Searches from the right side of the search
+                                  // area to the left side of the search area
+                                  // for a direct axis.
+  IMAQ_RIGHT_TO_LEFT_INDIRECT = 5,  // Searches from the right side of the
+                                    // search area to the left side of the
+                                    // search area for an indirect axis.
+  IMAQ_BOTTOM_TO_TOP_DIRECT = 6,  // Searches from the bottom of the search area
+                                  // to the top of the search area for a direct
+                                  // axis.
+  IMAQ_BOTTOM_TO_TOP_INDIRECT = 7,  // Searches from the bottom of the search
+                                    // area to the top of the search area for an
+                                    // indirect axis.
+  IMAQ_FIND_COORD_SYS_DIR_SIZE_GUARD = 0xFFFFFFFF
+} FindReferenceDirection;
+
+typedef enum MulticoreOperation_enum {
+  IMAQ_GET_CORES =
+      0,  // The number of processor cores NI Vision is currently using.
+  IMAQ_SET_CORES = 1,  // The number of processor cores for NI Vision to use.
+  IMAQ_USE_MAX_AVAILABLE =
+      2,  // Use the maximum number of available processor cores.
+  IMAQ_MULTICORE_OPERATION_SIZE_GUARD = 0xFFFFFFFF
+} MulticoreOperation;
+
+typedef enum GroupBehavior_enum {
+  IMAQ_GROUP_CLEAR = 0,  // Sets the behavior of the overlay group to clear the
+                         // current settings when an image is transformed.
+  IMAQ_GROUP_KEEP = 1,  // Sets the behavior of the overlay group to keep the
+                        // current settings when an image is transformed.
+  IMAQ_GROUP_TRANSFORM =
+      2,  // Sets the behavior of the overlay group to transform with the image.
+  IMAQ_GROUP_BEHAVIOR_SIZE_GUARD = 0xFFFFFFFF
+} GroupBehavior;
+
+typedef enum QRDimensions_enum {
+  IMAQ_QR_DIMENSIONS_AUTO_DETECT = 0,  // The function will automatically
+                                       // determine the dimensions of the QR
+                                       // code.
+  IMAQ_QR_DIMENSIONS_11x11 =
+      11,  // Specifies the dimensions of the QR code as 11 x 11.
+  IMAQ_QR_DIMENSIONS_13x13 =
+      13,  // Specifies the dimensions of the QR code as 13 x 13.
+  IMAQ_QR_DIMENSIONS_15x15 =
+      15,  // Specifies the dimensions of the QR code as 15 x 15.
+  IMAQ_QR_DIMENSIONS_17x17 =
+      17,  // Specifies the dimensions of the QR code as 17 x 17.
+  IMAQ_QR_DIMENSIONS_21x21 =
+      21,  // Specifies the dimensions of the QR code as 21 x 21.
+  IMAQ_QR_DIMENSIONS_25x25 =
+      25,  // Specifies the dimensions of the QR code as 25 x 25.
+  IMAQ_QR_DIMENSIONS_29x29 =
+      29,  // Specifies the dimensions of the QR code as 29 x 29.
+  IMAQ_QR_DIMENSIONS_33x33 =
+      33,  // Specifies the dimensions of the QR code as 33 x 33.
+  IMAQ_QR_DIMENSIONS_37x37 =
+      37,  // Specifies the dimensions of the QR code as 37 x 37.
+  IMAQ_QR_DIMENSIONS_41x41 =
+      41,  // Specifies the dimensions of the QR code as 41 x 41.
+  IMAQ_QR_DIMENSIONS_45x45 =
+      45,  // Specifies the dimensions of the QR code as 45 x 45.
+  IMAQ_QR_DIMENSIONS_49x49 =
+      49,  // Specifies the dimensions of the QR code as 49 x 49.
+  IMAQ_QR_DIMENSIONS_53x53 =
+      53,  // Specifies the dimensions of the QR code as 53 x 53.
+  IMAQ_QR_DIMENSIONS_57x57 =
+      57,  // Specifies the dimensions of the QR code as 57 x 57.
+  IMAQ_QR_DIMENSIONS_61x61 =
+      61,  // Specifies the dimensions of the QR code as 61 x 61.
+  IMAQ_QR_DIMENSIONS_65x65 =
+      65,  // Specifies the dimensions of the QR code as 65 x 65.
+  IMAQ_QR_DIMENSIONS_69x69 =
+      69,  // Specifies the dimensions of the QR code as 69 x 69.
+  IMAQ_QR_DIMENSIONS_73x73 =
+      73,  // Specifies the dimensions of the QR code as 73 x 73.
+  IMAQ_QR_DIMENSIONS_77x77 =
+      77,  // Specifies the dimensions of the QR code as 77 x 77.
+  IMAQ_QR_DIMENSIONS_81x81 =
+      81,  // Specifies the dimensions of the QR code as 81 x 81.
+  IMAQ_QR_DIMENSIONS_85x85 =
+      85,  // Specifies the dimensions of the QR code as 85 x 85.
+  IMAQ_QR_DIMENSIONS_89x89 =
+      89,  // Specifies the dimensions of the QR code as 89 x 89.
+  IMAQ_QR_DIMENSIONS_93x93 =
+      93,  // Specifies the dimensions of the QR code as 93 x 93.
+  IMAQ_QR_DIMENSIONS_97x97 =
+      97,  // Specifies the dimensions of the QR code as 97 x 97.
+  IMAQ_QR_DIMENSIONS_101x101 =
+      101,  // Specifies the dimensions of the QR code as 101 x 101.
+  IMAQ_QR_DIMENSIONS_105x105 =
+      105,  // Specifies the dimensions of the QR code as 105 x 105.
+  IMAQ_QR_DIMENSIONS_109x109 =
+      109,  // Specifies the dimensions of the QR code as 109 x 109.
+  IMAQ_QR_DIMENSIONS_113x113 =
+      113,  // Specifies the dimensions of the QR code as 113 x 113.
+  IMAQ_QR_DIMENSIONS_117x117 =
+      117,  // Specifies the dimensions of the QR code as 117 x 117.
+  IMAQ_QR_DIMENSIONS_121x121 =
+      121,  // Specifies the dimensions of the QR code as 121 x 121.
+  IMAQ_QR_DIMENSIONS_125x125 =
+      125,  // Specifies the dimensions of the QR code as 125 x 125.
+  IMAQ_QR_DIMENSIONS_129x129 =
+      129,  // Specifies the dimensions of the QR code as 129 x 129.
+  IMAQ_QR_DIMENSIONS_133x133 =
+      133,  // Specifies the dimensions of the QR code as 133 x 133.
+  IMAQ_QR_DIMENSIONS_137x137 =
+      137,  // Specifies the dimensions of the QR code as 137 x 137.
+  IMAQ_QR_DIMENSIONS_141x141 =
+      141,  // Specifies the dimensions of the QR code as 141 x 141.
+  IMAQ_QR_DIMENSIONS_145x145 =
+      145,  // Specifies the dimensions of the QR code as 145 x 145.
+  IMAQ_QR_DIMENSIONS_149x149 =
+      149,  // Specifies the dimensions of the QR code as 149 x 149.
+  IMAQ_QR_DIMENSIONS_153x153 =
+      153,  // Specifies the dimensions of the QR code as 153 x 153.
+  IMAQ_QR_DIMENSIONS_157x157 =
+      157,  // Specifies the dimensions of the QR code as 157 x 1537.
+  IMAQ_QR_DIMENSIONS_161x161 =
+      161,  // Specifies the dimensions of the QR code as 161 x 161.
+  IMAQ_QR_DIMENSIONS_165x165 =
+      165,  // Specifies the dimensions of the QR code as 165 x 165.
+  IMAQ_QR_DIMENSIONS_169x169 =
+      169,  // Specifies the dimensions of the QR code as 169 x 169.
+  IMAQ_QR_DIMENSIONS_173x173 =
+      173,  // Specifies the dimensions of the QR code as 173 x 173.
+  IMAQ_QR_DIMENSIONS_177x177 =
+      177,  // Specifies the dimensions of the QR code as 177 x 177.
+  IMAQ_QR_DIMENSIONS_SIZE_GUARD = 0xFFFFFFFF
+} QRDimensions;
+
+typedef enum QRCellFilterMode_enum {
+  IMAQ_QR_CELL_FILTER_MODE_AUTO_DETECT =
+      -2,  // The function will try all filter modes and uses the one that
+           // decodes the QR code within the fewest iterations and utilizing the
+           // least amount of error correction.
+  IMAQ_QR_CELL_FILTER_MODE_AVERAGE = 0,  // The function sets the pixel value
+                                         // for the cell to the average of the
+                                         // sampled pixels.
+  IMAQ_QR_CELL_FILTER_MODE_MEDIAN = 1,  // The function sets the pixel value for
+                                        // the cell to the median of the sampled
+                                        // pixels.
+  IMAQ_QR_CELL_FILTER_MODE_CENTRAL_AVERAGE =
+      2,  // The function sets the pixel value for the cell to the average of
+          // the pixels in the center of the cell sample.
+  IMAQ_QR_CELL_FILTER_MODE_HIGH_AVERAGE =
+      3,  // The function sets the pixel value for the cell to the average value
+          // of the half of the sampled pixels with the highest pixel values.
+  IMAQ_QR_CELL_FILTER_MODE_LOW_AVERAGE =
+      4,  // The function sets the pixel value for the cell to the average value
+          // of the half of the sampled pixels with the lowest pixel values.
+  IMAQ_QR_CELL_FILTER_MODE_VERY_HIGH_AVERAGE =
+      5,  // The function sets the pixel value for the cell to the average value
+          // of the ninth of the sampled pixels with the highest pixel values.
+  IMAQ_QR_CELL_FILTER_MODE_VERY_LOW_AVERAGE =
+      6,  // The function sets the pixel value for the cell to the average value
+          // of the ninth of the sampled pixels with the lowest pixel values.
+  IMAQ_QR_CELL_FILTER_MODE_ALL =
+      8,  // The function tries each filter mode, starting with
+          // IMAQ_QR_CELL_FILTER_MODE_AVERAGE and ending with
+          // IMAQ_QR_CELL_FILTER_MODE_VERY_LOW_AVERAGE, stopping once a filter
+          // mode decodes correctly.
+  IMAQ_QR_CELL_FILTER_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRCellFilterMode;
+
+typedef enum RoundingMode_enum {
+  IMAQ_ROUNDING_MODE_OPTIMIZE =
+      0,  // Rounds the result of a division using the best available method.
+  IMAQ_ROUNDING_MODE_TRUNCATE = 1,  // Truncates the result of a division.
+  IMAQ_ROUNDING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} RoundingMode;
+
+typedef enum QRDemodulationMode_enum {
+  IMAQ_QR_DEMODULATION_MODE_AUTO_DETECT =
+      -2,  // The function will try each demodulation mode and use the one which
+           // decodes the QR code within the fewest iterations and utilizing the
+           // least amount of error correction.
+  IMAQ_QR_DEMODULATION_MODE_HISTOGRAM = 0,  // The function uses a histogram of
+                                            // all of the QR cells to calculate
+                                            // a threshold.
+  IMAQ_QR_DEMODULATION_MODE_LOCAL_CONTRAST =
+      1,  // The function examines each of the cell's neighbors to determine if
+          // the cell is on or off.
+  IMAQ_QR_DEMODULATION_MODE_COMBINED = 2,  // The function uses the histogram of
+                                           // the QR code to calculate a
+                                           // threshold.
+  IMAQ_QR_DEMODULATION_MODE_ALL =
+      3,  // The function tries IMAQ_QR_DEMODULATION_MODE_HISTOGRAM, then
+          // IMAQ_QR_DEMODULATION_MODE_LOCAL_CONTRAST and then
+          // IMAQ_QR_DEMODULATION_MODE_COMBINED, stopping once one mode is
+          // successful.
+  IMAQ_QR_DEMODULATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRDemodulationMode;
+
+typedef enum ContrastMode_enum {
+  IMAQ_ORIGINAL_CONTRAST = 0,  // Instructs the geometric matching algorithm to
+                               // find matches with the same contrast as the
+                               // template.
+  IMAQ_REVERSED_CONTRAST = 1,  // Instructs the geometric matching algorithm to
+                               // find matches with the inverted contrast of the
+                               // template.
+  IMAQ_BOTH_CONTRASTS = 2,  // Instructs the geometric matching algorithm to
+                            // find matches with the same and inverted contrast
+                            // of the template.
+} ContrastMode;
+
+typedef enum QRPolarities_enum {
+  IMAQ_QR_POLARITY_AUTO_DETECT =
+      -2,  // The function should determine the polarity of the QR code.
+  IMAQ_QR_POLARITY_BLACK_ON_WHITE = 0,  // The function should search for a QR
+                                        // code with dark data on a bright
+                                        // background.
+  IMAQ_QR_POLARITY_WHITE_ON_BLACK = 1,  // The function should search for a QR
+                                        // code with bright data on a dark
+                                        // background.
+  IMAQ_QR_POLARITY_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRPolarities;
+
+typedef enum QRRotationMode_enum {
+  IMAQ_QR_ROTATION_MODE_UNLIMITED =
+      0,  // The function allows for unlimited rotation.
+  IMAQ_QR_ROTATION_MODE_0_DEGREES =
+      1,  // The function allows for ??? 5 degrees of rotation.
+  IMAQ_QR_ROTATION_MODE_90_DEGREES =
+      2,  // The function allows for between 85 and 95 degrees of rotation.
+  IMAQ_QR_ROTATION_MODE_180_DEGREES =
+      3,  // The function allows for between 175 and 185 degrees of rotation.
+  IMAQ_QR_ROTATION_MODE_270_DEGREES =
+      4,  // The function allows for between 265 and 275 degrees of rotation.
+  IMAQ_QR_ROTATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRRotationMode;
+
+typedef enum QRGradingMode_enum {
+  IMAQ_QR_NO_GRADING =
+      0,  // The function does not make any preparatory calculations.
+  IMAQ_QR_GRADING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRGradingMode;
+
+typedef enum StraightEdgeSearchMode_enum {
+  IMAQ_USE_FIRST_RAKE_EDGES =
+      0,  // Fits a straight edge on the first points detected using a rake.
+  IMAQ_USE_BEST_RAKE_EDGES =
+      1,  // Fits a straight edge on the best points detected using a rake.
+  IMAQ_USE_BEST_HOUGH_LINE = 2,  // Finds the strongest straight edge using all
+                                 // points detected on a rake.
+  IMAQ_USE_FIRST_PROJECTION_EDGE =
+      3,  // Uses the location of the first projected edge as the straight edge.
+  IMAQ_USE_BEST_PROJECTION_EDGE = 4,  // Finds the strongest projected edge
+                                      // location to determine the straight
+                                      // edge.
+  IMAQ_STRAIGHT_EDGE_SEARCH_SIZE_GUARD = 0xFFFFFFFF
+} StraightEdgeSearchMode;
+
+typedef enum SearchDirection_enum {
+  IMAQ_SEARCH_DIRECTION_LEFT_TO_RIGHT = 0,  // Searches from the left side of
+                                            // the search area to the right side
+                                            // of the search area.
+  IMAQ_SEARCH_DIRECTION_RIGHT_TO_LEFT = 1,  // Searches from the right side of
+                                            // the search area to the left side
+                                            // of the search area.
+  IMAQ_SEARCH_DIRECTION_TOP_TO_BOTTOM = 2,  // Searches from the top side of the
+                                            // search area to the bottom side of
+                                            // the search area.
+  IMAQ_SEARCH_DIRECTION_BOTTOM_TO_TOP = 3,  // Searches from the bottom side of
+                                            // the search area to the top side
+                                            // of the search area.
+  IMAQ_SEARCH_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} SearchDirection;
+
+typedef enum QRStreamMode_enum {
+  IMAQ_QR_MODE_NUMERIC =
+      0,  // Specifies that the data was encoded using numeric mode.
+  IMAQ_QR_MODE_ALPHANUMERIC =
+      1,  // Specifies that the data was encoded using alpha-numeric mode.
+  IMAQ_QR_MODE_RAW_BYTE = 2,  // Specifies that the data was not encoded but is
+                              // only raw binary bytes, or encoded in JIS-8.
+  IMAQ_QR_MODE_EAN128_TOKEN = 3,  // Specifies that the data has a special
+                                  // meaning represented by the application ID.
+  IMAQ_QR_MODE_EAN128_DATA = 4,  // Specifies that the data has a special
+                                 // meaning represented by the application ID.
+  IMAQ_QR_MODE_ECI = 5,  // Specifies that the data was meant to be read using
+                         // the language represented in the language ID.
+  IMAQ_QR_MODE_KANJI =
+      6,  // Specifies that the data was encoded in Shift-JIS16 Japanese.
+  IMAQ_QR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} QRStreamMode;
+
+typedef enum ParticleClassifierType_enum {
+  IMAQ_PARTICLE_LARGEST = 0,  // Use only the largest particle in the image.
+  IMAQ_PARTICLE_ALL = 1,  // Use all particles in the image.
+  IMAQ_PARTICLE_CLASSIFIER_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ParticleClassifierType;
+
+typedef enum QRCellSampleSize_enum {
+  IMAQ_QR_CELL_SAMPLE_SIZE_AUTO_DETECT =
+      -2,  // The function will try each sample size and use the one which
+           // decodes the QR code within the fewest iterations and utilizing the
+           // least amount of error correction.
+  IMAQ_QR_CELL_SAMPLE_SIZE1X1 =
+      1,  // The function will use a 1x1 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_SIZE2X2 =
+      2,  // The function will use a 2x2 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_SIZE3X3 =
+      3,  // The function will use a 3x3 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_SIZE4X4 =
+      4,  // The function will use a 4x4 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_SIZE5X5 =
+      5,  // The function will use a 5x5 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_SIZE6X6 =
+      6,  // The function will use a 6x6 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_SIZE7X7 =
+      7,  // The function will use a 7x7 sized sample from each cell.
+  IMAQ_QR_CELL_SAMPLE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} QRCellSampleSize;
+
+typedef enum RakeProcessType_enum {
+  IMAQ_GET_FIRST_EDGES = 0,
+  IMAQ_GET_FIRST_AND_LAST_EDGES = 1,
+  IMAQ_GET_ALL_EDGES = 2,
+  IMAQ_GET_BEST_EDGES = 3,
+  IMAQ_RAKE_PROCESS_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} RakeProcessType;
+
+typedef enum GeometricSetupDataItem_enum {
+  IMAQ_CURVE_EXTRACTION_MODE =
+      0,  // Specifies how the function identifies curves in the image.
+  IMAQ_CURVE_EDGE_THRSHOLD = 1,  // Specifies the minimum contrast an edge pixel
+                                 // must have for it to be considered part of a
+                                 // curve.
+  IMAQ_CURVE_EDGE_FILTER = 2,  // Specifies the width of the edge filter that
+                               // the function uses to identify curves in the
+                               // image.
+  IMAQ_MINIMUM_CURVE_LENGTH = 3,  // Specifies the length, in pixels, of the
+                                  // smallest curve that you want the function
+                                  // to identify.
+  IMAQ_CURVE_ROW_SEARCH_STEP_SIZE =
+      4,  // Specifies the distance, in the y direction, between the image rows
+          // that the algorithm inspects for curve seed points.
+  IMAQ_CURVE_COL_SEARCH_STEP_SIZE =
+      5,  // Specifies the distance, in the x direction, between the image
+          // columns that the algorithm inspects for curve seed points.
+  IMAQ_CURVE_MAX_END_POINT_GAP =
+      6,  // Specifies the maximum gap, in pixels, between the endpoints of a
+          // curve that the function identifies as a closed curve.
+  IMAQ_EXTRACT_CLOSED_CURVES =
+      7,  // Specifies whether to identify only closed curves in the image.
+  IMAQ_ENABLE_SUBPIXEL_CURVE_EXTRACTION =
+      8,  // The function ignores this option.
+  IMAQ_ENABLE_CORRELATION_SCORE = 9,  // Specifies that the function should
+                                      // calculate the Correlation Score and
+                                      // return it for each match result.
+  IMAQ_ENABLE_SUBPIXEL_ACCURACY = 10,  // Determines whether to return the match
+                                       // results with subpixel accuracy.
+  IMAQ_SUBPIXEL_ITERATIONS = 11,  // Specifies the maximum number of incremental
+                                  // improvements used to refine matches using
+                                  // subpixel information.
+  IMAQ_SUBPIXEL_TOLERANCE =
+      12,  // Specifies the maximum amount of change, in pixels, between
+           // consecutive incremental improvements in the match position before
+           // the function stops refining the match position.
+  IMAQ_INITIAL_MATCH_LIST_LENGTH =
+      13,  // Specifies the maximum size of the match list.
+  IMAQ_ENABLE_TARGET_TEMPLATE_CURVESCORE =
+      14,  // Specifies whether the function should calculate the match curve to
+           // template curve score and return it for each match result.
+  IMAQ_MINIMUM_MATCH_SEPARATION_DISTANCE =
+      15,  // Specifies the minimum separation distance, in pixels, between the
+           // origins of two matches that have unique positions.
+  IMAQ_MINIMUM_MATCH_SEPARATION_ANGLE =
+      16,  // Specifies the minimum angular difference, in degrees, between two
+           // matches that have unique angles.
+  IMAQ_MINIMUM_MATCH_SEPARATION_SCALE =
+      17,  // Specifies the minimum difference in scale, expressed as a
+           // percentage, between two matches that have unique scales.
+  IMAQ_MAXIMUM_MATCH_OVERLAP = 18,  // Specifies whether you want the algorithm
+                                    // to spend less time accurately estimating
+                                    // the location of a match.
+  IMAQ_ENABLE_COARSE_RESULT = 19,  // Specifies whether you want the algorithm
+                                   // to spend less time accurately estimating
+                                   // the location of a match.
+  IMAQ_ENABLE_CALIBRATION_SUPPORT = 20,  // Specifies whether or not the
+                                         // algorithm treat the inspection image
+                                         // as a calibrated image.
+  IMAQ_ENABLE_CONTRAST_REVERSAL =
+      21,  // Specifies the contrast of the matches to search for.
+  IMAQ_SEARCH_STRATEGY = 22,  // Specifies the aggressiveness of the strategy
+                              // used to find matches in the image.
+  IMAQ_REFINEMENT_MATCH_FACTOR =
+      23,  // Specifies the factor applied to the number of matches requested to
+           // determine how many matches are refined in the pyramid stage.
+  IMAQ_SUBPIXEL_MATCH_FACTOR = 24,  // Specifies the factor applied to the
+                                    // number for matches requested to determine
+                                    // how many matches are used for the final
+                                    // (subpixel) stage.
+  IMAQ_MAX_REFINEMENT_ITERATIONS =
+      25,  // Specifies maximum refinement iteration.
+} GeometricSetupDataItem;
+
+typedef enum DistortionModel_enum {
+  IMAQ_POLYNOMIAL_MODEL = 0,  // Polynomial model.
+  IMAQ_DIVISION_MODEL = 1,  // Division Model.
+  IMAQ_NO_DISTORTION_MODEL = -1,  // Not a distortion model.
+} DistortionModel;
+
+typedef enum CalibrationThumbnailType_enum {
+  IMAQ_CAMARA_MODEL_TYPE = 0,  // Camara model thumbnail type.
+  IMAQ_PERSPECTIVE_TYPE = 1,  // Perspective thumbnail type.
+  IMAQ_MICRO_PLANE_TYPE = 2,  // Micro Plane thumbnail type.
+  IMAQ_CALIBRATION_THUMBNAIL_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationThumbnailType;
+
+typedef enum SettingType_enum {
+  IMAQ_ROTATION_ANGLE_RANGE = 0,  // Set a range for this option to specify the
+                                  // angles at which you expect the Function to
+                                  // find template matches in the inspection
+                                  // image.
+  IMAQ_SCALE_RANGE = 1,  // Set a range for this option to specify the sizes at
+                         // which you expect the Function to find template
+                         // matches in the inspection image.
+  IMAQ_OCCLUSION_RANGE = 2,  // Set a range for this option to specify the
+                             // amount of occlusion you expect for a match in
+                             // the inspection image.
+  IMAQ_SETTING_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} SettingType;
+
+typedef enum SegmentationDistanceLevel_enum {
+  IMAQ_SEGMENTATION_LEVEL_CONSERVATIVE =
+      0,  // Uses extensive criteria to determine the Maximum Distance.
+  IMAQ_SEGMENTATION_LEVEL_AGGRESSIVE =
+      1,  // Uses few criteria to determine the Maximum Distance.
+  IMAQ_SEGMENTATION_LEVEL_SIZE_GUARD = 0xFFFFFFFF
+} SegmentationDistanceLevel;
+
+typedef enum ExtractContourSelection_enum {
+  IMAQ_CLOSEST = 0,  // Selects the curve closest to the ROI.
+  IMAQ_LONGEST = 1,  // Selects the longest curve.
+  IMAQ_STRONGEST = 2,  // Selects the curve with the highest edge strength
+                       // averaged from each point on the curve.
+  IMAQ_EXTRACT_CONTOUR_SELECTION_SIZE_GUARD = 0xFFFFFFFF
+} ExtractContourSelection;
+
+typedef enum FindTransformMode_enum {
+  IMAQ_FIND_REFERENCE = 0,  // Update both parts of the coordinate system.
+  IMAQ_UPDATE_TRANSFORM = 1,  // Update only the new reference system.
+  IMAQ_FIND_TRANSFORM_MODE_SIZE_GUARD = 0xFFFFFFFF
+} FindTransformMode;
+
+typedef enum ExtractContourDirection_enum {
+  IMAQ_RECT_LEFT_RIGHT = 0,  // Searches the ROI from left to right.
+  IMAQ_RECT_RIGHT_LEFT = 1,  // Searches the ROI from right to left.
+  IMAQ_RECT_TOP_BOTTOM = 2,  // Searches the ROI from top to bottom.
+  IMAQ_RECT_BOTTOM_TOP = 3,  // Searches the ROI from bottom to top.
+  IMAQ_ANNULUS_INNER_OUTER =
+      4,  // Searches the ROI from the inner radius to the outer radius.
+  IMAQ_ANNULUS_OUTER_INNER =
+      5,  // Searches the ROI from the outer radius to the inner radius.
+  IMAQ_ANNULUS_START_STOP =
+      6,  // Searches the ROI from start angle to end angle.
+  IMAQ_ANNULUS_STOP_START =
+      7,  // Searches the ROI from end angle to start angle.
+  IMAQ_EXTRACT_CONTOUR_DIRECTION_SIZE_GUARD = 0xFFFFFFFF
+} ExtractContourDirection;
+
+typedef enum EdgePolaritySearchMode_enum {
+  IMAQ_SEARCH_FOR_ALL_EDGES = 0,  // Searches for all edges.
+  IMAQ_SEARCH_FOR_RISING_EDGES = 1,  // Searches for rising edges only.
+  IMAQ_SEARCH_FOR_FALLING_EDGES = 2,  // Searches for falling edges only.
+  IMAQ_EDGE_POLARITY_MODE_SIZE_GUARD = 0xFFFFFFFF
+} EdgePolaritySearchMode;
+
+typedef enum Connectivity_enum {
+  IMAQ_FOUR_CONNECTED =
+      0,  // Morphological reconstruction is performed in connectivity mode 4.
+  IMAQ_EIGHT_CONNECTED =
+      1,  // Morphological reconstruction is performed in connectivity mode 8.
+  IMAQ_CONNECTIVITY_SIZE_GUARD = 0xFFFFFFFF
+} Connectivity;
+
+typedef enum MorphologyReconstructOperation_enum {
+  IMAQ_DILATE_RECONSTRUCT = 0,  // Performs Reconstruction by dilation.
+  IMAQ_ERODE_RECONSTRUCT = 1,  // Performs Reconstruction by erosion.
+  IMAQ_MORPHOLOGY_RECONSTRUCT_OPERATION_SIZE_GUARD = 0xFFFFFFFF
+} MorphologyReconstructOperation;
+
+typedef enum WaveletType_enum {
+  IMAQ_DB02 = 0,
+  IMAQ_DB03 = 1,
+  IMAQ_DB04 = 2,  // Specifies the Wavelet Type as DB02.
+  IMAQ_DB05 = 3,
+  IMAQ_DB06 = 4,
+  IMAQ_DB07 = 5,
+  IMAQ_DB08 = 6,
+  IMAQ_DB09 = 7,
+  IMAQ_DB10 = 8,
+  IMAQ_DB11 = 9,
+  IMAQ_DB12 = 10,
+  IMAQ_DB13 = 11,
+  IMAQ_DB14 = 12,
+  IMAQ_HAAR = 13,
+  IMAQ_BIOR1_3 = 14,
+  IMAQ_BIOR1_5 = 15,
+  IMAQ_BIOR2_2 = 16,
+  IMAQ_BIOR2_4 = 17,
+  IMAQ_BIOR2_6 = 18,
+  IMAQ_BIOR2_8 = 19,
+  IMAQ_BIOR3_1 = 20,
+  IMAQ_BIOR3_3 = 21,
+  IMAQ_BIOR3_5 = 22,
+  IMAQ_BIOR3_7 = 23,
+  IMAQ_BIOR3_9 = 24,
+  IMAQ_BIOR4_4 = 25,
+  IMAQ_COIF1 = 26,
+  IMAQ_COIF2 = 27,
+  IMAQ_COIF3 = 28,
+  IMAQ_COIF4 = 29,
+  IMAQ_COIF5 = 30,
+  IMAQ_SYM2 = 31,
+  IMAQ_SYM3 = 32,
+  IMAQ_SYM4 = 33,
+  IMAQ_SYM5 = 34,
+  IMAQ_SYM6 = 35,
+  IMAQ_SYM7 = 36,
+  IMAQ_SYM8 = 37,
+  IMAQ_BIOR5_5 = 38,
+  IMAQ_BIOR6_8 = 39,
+  IMAQ_WAVE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} WaveletType;
+
+typedef enum ParticleClassifierThresholdType_enum {
+  IMAQ_THRESHOLD_MANUAL = 0,  // The classifier performs a manual threshold on
+                              // the image during preprocessing.
+  IMAQ_THRESHOLD_AUTO = 1,  // The classifier performs an auto threshold on the
+                            // image during preprocessing.
+  IMAQ_THRESHOLD_LOCAL = 2,  // The classifier performs a local threshold on the
+                             // image during preprocessing.
+} ParticleClassifierThresholdType;
+
+typedef enum MeasureParticlesCalibrationMode_enum {
+  IMAQ_CALIBRATION_MODE_PIXEL = 0,  // The function takes only pixel
+                                    // measurements on the particles in the
+                                    // image.
+  IMAQ_CALIBRATION_MODE_CALIBRATED = 1,  // The function takes only calibrated
+                                         // measurements on the particles in the
+                                         // image.
+  IMAQ_CALIBRATION_MODE_BOTH = 2,  // The function takes both pixel and
+                                   // calibrated measurements on the particles
+                                   // in the image.
+  IMAQ_MEASURE_PARTICLES_CALIBRATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} MeasureParticlesCalibrationMode;
+
+typedef enum GeometricMatchingSearchStrategy_enum {
+  IMAQ_GEOMETRIC_MATCHING_CONSERVATIVE =
+      0,  // Instructs the pattern matching algorithm to use the largest
+          // possible amount of information from the image at the expense of
+          // slowing down the speed of the algorithm.
+  IMAQ_GEOMETRIC_MATCHING_BALANCED =
+      1,  // Instructs the pattern matching algorithm to balance the amount of
+          // information from the image it uses with the speed of the algorithm.
+  IMAQ_GEOMETRIC_MATCHING_AGGRESSIVE =
+      2,  // Instructs the pattern matching algorithm to use a lower amount of
+          // information from the image, which allows the algorithm to run
+          // quickly but at the expense of accuracy.
+  IMAQ_GEOMETRIC_MATCHING_SEARCH_STRATEGY_SIZE_GUARD = 0xFFFFFFFF
+} GeometricMatchingSearchStrategy;
+
+typedef enum ColorClassificationResolution_enum {
+  IMAQ_CLASSIFIER_LOW_RESOLUTION =
+      0,  // Low resolution version of the color classifier.
+  IMAQ_CLASSIFIER_MEDIUM_RESOLUTION =
+      1,  // Medium resolution version of the color classifier.
+  IMAQ_CLASSIFIER_HIGH_RESOLUTION =
+      2,  // High resolution version of the color classifier.
+  IMAQ_CLASSIFIER_RESOLUTION_SIZE_GUARD = 0xFFFFFFFF
+} ColorClassificationResolution;
+
+typedef enum ConnectionConstraintType_enum {
+  IMAQ_DISTANCE_CONSTRAINT = 0,  // Specifies the distance, in pixels, within
+                                 // which the end points of two curves must lie
+                                 // in order to be considered part of a contour.
+  IMAQ_ANGLE_CONSTRAINT =
+      1,  // Specifies the range, in degrees, within which the difference
+          // between the angle of two curves, measured at the end points, must
+          // lie in order for the two curves to be considered part of a contour.
+  IMAQ_CONNECTIVITY_CONSTRAINT =
+      2,  // Specifies the distance, in pixels, within which a line extended
+          // from the end point of a curve must pass the end point of another
+          // curve in order for the two curves to be considered part of a
+          // contour.
+  IMAQ_GRADIENT_CONSTRAINT =
+      3,  // Specifies the range, in degrees, within which the gradient angles
+          // of two curves, measured at the end points, must lie in order for
+          // the two curves to be considered part of a contour.
+  IMAQ_NUM_CONNECTION_CONSTRAINT_TYPES = 4,  //.
+  IMAQ_CONNECTION_CONSTRAINT_SIZE_GUARD = 0xFFFFFFFF
+} ConnectionConstraintType;
+
+typedef enum Barcode2DContrast_enum {
+  IMAQ_ALL_BARCODE_2D_CONTRASTS =
+      0,  // The function searches for barcodes of each contrast type.
+  IMAQ_BLACK_ON_WHITE_BARCODE_2D = 1,  // The function searches for 2D barcodes
+                                       // containing black data on a white
+                                       // background.
+  IMAQ_WHITE_ON_BLACK_BARCODE_2D = 2,  // The function searches for 2D barcodes
+                                       // containing white data on a black
+                                       // background.
+  IMAQ_BARCODE_2D_CONTRAST_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DContrast;
+
+typedef enum QRModelType_enum {
+  IMAQ_QR_MODELTYPE_AUTO_DETECT =
+      0,  // Specifies that the function will auto-detect the type of QR code.
+  IMAQ_QR_MODELTYPE_MICRO = 1,  // Specifies the QR code is of a micro type.
+  IMAQ_QR_MODELTYPE_MODEL1 = 2,  // Specifies the QR code is of a model1 type.
+  IMAQ_QR_MODELTYPE_MODEL2 = 3,  // Specifies the QR code is of a model2 type.
+  IMAQ_QR_MODEL_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} QRModelType;
+
+typedef enum WindowBackgroundFillStyle_enum {
+  IMAQ_FILL_STYLE_SOLID = 0,  // Fill the display window with a solid color.
+  IMAQ_FILL_STYLE_HATCH = 2,  // Fill the display window with a pattern defined
+                              // by WindowBackgroundHatchStyle.
+  IMAQ_FILL_STYLE_DEFAULT =
+      3,  // Fill the display window with the NI Vision default pattern.
+  IMAQ_FILL_STYLE_SIZE_GUARD = 0xFFFFFFFF
+} WindowBackgroundFillStyle;
+
+typedef enum ExtractionMode_enum {
+  IMAQ_NORMAL_IMAGE = 0,  // Specifies that the function makes no assumptions
+                          // about the uniformity of objects in the image or the
+                          // image background.
+  IMAQ_UNIFORM_REGIONS = 1,  // Specifies that the function assumes that either
+                             // the objects in the image or the image background
+                             // consists of uniform pixel values.
+  IMAQ_EXTRACTION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} ExtractionMode;
+
+typedef enum EdgeFilterSize_enum {
+  IMAQ_FINE =
+      0,  // Specifies that the function uses a fine (narrow) edge filter.
+  IMAQ_NORMAL = 1,  // Specifies that the function uses a normal edge filter.
+  IMAQ_CONTOUR_TRACING = 2,  // Sets the Edge Filter Size to contour tracing,
+                             // which provides the best results for contour
+                             // extraction but increases the time required to
+                             // process the image.
+  IMAQ_EDGE_FILTER_SIZE_SIZE_GUARD = 0xFFFFFFFF
+} EdgeFilterSize;
+
+typedef enum Barcode2DSearchMode_enum {
+  IMAQ_SEARCH_MULTIPLE = 0,  // The function searches for multiple 2D barcodes.
+  IMAQ_SEARCH_SINGLE_CONSERVATIVE =
+      1,  // The function searches for 2D barcodes using the same searching
+          // algorithm as IMAQ_SEARCH_MULTIPLE but stops searching after
+          // locating one valid barcode.
+  IMAQ_SEARCH_SINGLE_AGGRESSIVE =
+      2,  // The function searches for a single 2D barcode using a method that
+          // assumes the barcode occupies a majority of the search region.
+  IMAQ_BARCODE_2D_SEARCH_MODE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DSearchMode;
+
+typedef enum DataMatrixSubtype_enum {
+  IMAQ_ALL_DATA_MATRIX_SUBTYPES =
+      0,  // The function searches for Data Matrix barcodes of all subtypes.
+  IMAQ_DATA_MATRIX_SUBTYPES_ECC_000_ECC_140 =
+      1,  // The function searches for Data Matrix barcodes of subtypes ECC 000,
+          // ECC 050, ECC 080, ECC 100 and ECC 140.
+  IMAQ_DATA_MATRIX_SUBTYPE_ECC_200 =
+      2,  // The function searches for Data Matrix ECC 200 barcodes.
+  IMAQ_DATA_MATRIX_SUBTYPE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixSubtype;
+
+typedef enum FeatureType_enum {
+  IMAQ_NOT_FOUND_FEATURE = 0,  // Specifies the feature is not found.
+  IMAQ_CIRCLE_FEATURE = 1,  // Specifies the feature is a circle.
+  IMAQ_ELLIPSE_FEATURE = 2,  // Specifies the feature is an ellipse.
+  IMAQ_CONST_CURVE_FEATURE = 3,  // Specifies the features is a constant curve.
+  IMAQ_RECTANGLE_FEATURE = 4,  // Specifies the feature is a rectangle.
+  IMAQ_LEG_FEATURE = 5,  // Specifies the feature is a leg.
+  IMAQ_CORNER_FEATURE = 6,  // Specifies the feature is a corner.
+  IMAQ_PARALLEL_LINE_PAIR_FEATURE =
+      7,  // Specifies the feature is a parallel line pair.
+  IMAQ_PAIR_OF_PARALLEL_LINE_PAIRS_FEATURE =
+      8,  // Specifies the feature is a pair of parallel line pairs.
+  IMAQ_LINE_FEATURE = 9,  // Specifies the feature is a line.
+  IMAQ_CLOSED_CURVE_FEATURE = 10,  // Specifies the feature is a closed curve.
+  IMAQ_FEATURE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} FeatureType;
+
+typedef enum Barcode2DCellShape_enum {
+  IMAQ_SQUARE_CELLS = 0,  // The function uses an algorithm for decoding the 2D
+                          // barcode that works with square data cells.
+  IMAQ_ROUND_CELLS = 1,  // The function uses an algorithm for decoding the 2D
+                         // barcode that works with round data cells.
+  IMAQ_BARCODE_2D_CELL_SHAPE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DCellShape;
+
+typedef enum LocalThresholdMethod_enum {
+  IMAQ_NIBLACK = 0,  // The function computes thresholds for each pixel based on
+                     // its local statistics using the Niblack local
+                     // thresholding algorithm.
+  IMAQ_BACKGROUND_CORRECTION =
+      1,  // The function performs background correction first to eliminate
+          // non-uniform lighting effects, then performs thresholding using the
+          // Otsu thresholding algorithm.
+  IMAQ_LOCAL_THRESHOLD_METHOD_SIZE_GUARD = 0xFFFFFFFF
+} LocalThresholdMethod;
+
+typedef enum Barcode2DType_enum {
+  IMAQ_PDF417 = 0,  // The 2D barcode is of type PDF417.
+  IMAQ_DATA_MATRIX_ECC_000 =
+      1,  // The 2D barcode is of type Data Matrix ECC 000.
+  IMAQ_DATA_MATRIX_ECC_050 =
+      2,  // The 2D barcode is of type Data Matrix ECC 050.
+  IMAQ_DATA_MATRIX_ECC_080 =
+      3,  // The 2D barcode is of type Data Matrix ECC 080.
+  IMAQ_DATA_MATRIX_ECC_100 =
+      4,  // The 2D barcode is of type Data Matrix ECC 100.
+  IMAQ_DATA_MATRIX_ECC_140 =
+      5,  // The 2D barcode is of type Data Matrix ECC 140.
+  IMAQ_DATA_MATRIX_ECC_200 =
+      6,  // The 2D barcode is of type Data Matrix ECC 200.
+  IMAQ_BARCODE_2D_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DType;
+
+typedef enum ClassifierEngineType_enum {
+  IMAQ_ENGINE_NONE = 0,  // No engine has been set on this classifier session.
+  IMAQ_ENGINE_NEAREST_NEIGHBOR = 1,  // Nearest neighbor engine.
+  IMAQ_ENGINE_SUPPORT_VECTOR_MACHINE = 2,
+  IMAQ_CLASSIFIER_ENGINE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ClassifierEngineType;
+
+typedef enum ClassifierType_enum {
+  IMAQ_CLASSIFIER_CUSTOM =
+      0,  // The classifier session classifies vectors of doubles.
+  IMAQ_CLASSIFIER_PARTICLE =
+      1,  // The classifier session classifies particles in binary images.
+  IMAQ_CLASSIFIER_COLOR =
+      2,  // The classifier session classifies an image based on its color.
+  IMAQ_CLASSIFIER_TEXTURE =
+      3,  // The classifier session classifies an image based on its texture.
+  IMAQ_CLASSIFIER_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ClassifierType;
+
+typedef enum ParticleType_enum {
+  IMAQ_PARTICLE_BRIGHT = 0,  // Bright particles.
+  IMAQ_PARTICLE_DARK = 1,  // Dark particles.
+  IMAQ_PARTICLE_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} ParticleType;
+
+typedef enum VisionInfoType2_enum {
+  IMAQ_VISIONINFO_CALIBRATION = 0x01,  // Used to indicate interaction with the
+                                       // Calibration information in an image.
+  IMAQ_VISIONINFO_OVERLAY = 0x02,  // Used to indicate interaction with the
+                                   // Overlay information in an image.
+  IMAQ_VISIONINFO_GRAYTEMPLATE = 0x04,  // Used to indicate interaction with the
+                                        // grayscale template information in an
+                                        // image.
+  IMAQ_VISIONINFO_COLORTEMPLATE = 0x08,  // Used to indicate interaction with
+                                         // the color template information in an
+                                         // image.
+  IMAQ_VISIONINFO_GEOMETRICTEMPLATE = 0x10,  // Used to indicate interaction
+                                             // with the geometric template
+                                             // information in an image.
+  IMAQ_VISIONINFO_CUSTOMDATA = 0x20,  // Used to indicate interaction with the
+                                      // binary or text Custom Data in an image.
+  IMAQ_VISIONINFO_GOLDENTEMPLATE = 0x40,  // Used to indicate interaction with
+                                          // the golden template information in
+                                          // an image.
+  IMAQ_VISIONINFO_GEOMETRICTEMPLATE2 = 0x80,  // Used to indicate interaction
+                                              // with the geometric template 2
+                                              // information in an image.
+  IMAQ_VISIONINFO_ALL = 0xFFFFFFFF,  // Removes, checks for, or indicates the
+                                     // presence of all types of extra
+                                     // information in an image.
+} VisionInfoType2;
+
+typedef enum ReadClassifierFileMode_enum {
+  IMAQ_CLASSIFIER_READ_ALL =
+      0,  // Read all information from the classifier file.
+  IMAQ_CLASSIFIER_READ_SAMPLES =
+      1,  // Read only the samples from the classifier file.
+  IMAQ_CLASSIFIER_READ_PROPERTIES =
+      2,  // Read only the properties from the classifier file.
+  IMAQ_READ_CLASSIFIER_FILE_MODES_SIZE_GUARD = 0xFFFFFFFF
+} ReadClassifierFileMode;
+
+typedef enum WriteClassifierFileMode_enum {
+  IMAQ_CLASSIFIER_WRITE_ALL =
+      0,  // Writes all information to the classifier file.
+  IMAQ_CLASSIFIER_WRITE_CLASSIFY_ONLY = 1,  // Write only the information needed
+                                            // to classify to the classifier
+                                            // file.
+  IMAQ_WRITE_CLASSIFIER_FILE_MODES_SIZE_GUARD = 0xFFFFFFFF
+} WriteClassifierFileMode;
+
+typedef enum Barcode2DShape_enum {
+  IMAQ_SQUARE_BARCODE_2D = 0,  // The function searches for square 2D barcodes.
+  IMAQ_RECTANGULAR_BARCODE_2D =
+      1,  // The function searches for rectangular 2D barcodes.
+  IMAQ_BARCODE_2D_SHAPE_SIZE_GUARD = 0xFFFFFFFF
+} Barcode2DShape;
+
+typedef enum DataMatrixRotationMode_enum {
+  IMAQ_UNLIMITED_ROTATION = 0,  // The function allows for unlimited rotation.
+  IMAQ_0_DEGREES =
+      1,  // The function allows for between -5 and 5 degrees of rotation.
+  IMAQ_90_DEGREES =
+      2,  // The function allows for between 85 and 95 degrees of rotation.
+  IMAQ_180_DEGREES =
+      3,  // The function allows for between 175 and 185 degrees of rotation.
+  IMAQ_270_DEGREES =
+      4,  // The function allows for between 265 and 275 degrees of rotation.
+  IMAQ_DATA_MATRIX_ROTATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixRotationMode;
+
+typedef enum AIMGrade_enum {
+  IMAQ_AIM_GRADE_F = 0,  // The Data Matrix barcode received a grade of F.
+  IMAQ_AIM_GRADE_D = 1,  // The Data Matrix barcode received a grade of D.
+  IMAQ_AIM_GRADE_C = 2,  // The Data Matrix barcode received a grade of C.
+  IMAQ_AIM_GRADE_B = 3,  // The Data Matrix barcode received a grade of B.
+  IMAQ_AIM_GRADE_A = 4,  // The Data Matrix barcode received a grade of A.
+  IMAQ_DATA_MATRIX_AIM_GRADE_SIZE_GUARD = 0xFFFFFFFF
+} AIMGrade;
+
+typedef enum DataMatrixCellFillMode_enum {
+  IMAQ_AUTO_DETECT_CELL_FILL_MODE = -2,  // Sets the function to determine the
+                                         // Data Matrix barcode cell fill
+                                         // percentage automatically.
+  IMAQ_LOW_FILL = 0,  // Sets the function to read Data Matrix barcodes with a
+                      // cell fill percentage of less than 30 percent.
+  IMAQ_NORMAL_FILL = 1,  // Sets the function to read Data Matrix barcodes with
+                         // a cell fill percentage greater than or equal to 30
+                         // percent.
+  IMAQ_DATA_MATRIX_CELL_FILL_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixCellFillMode;
+
+typedef enum DataMatrixDemodulationMode_enum {
+  IMAQ_AUTO_DETECT_DEMODULATION_MODE =
+      -2,  // The function will try each demodulation mode and use the one which
+           // decodes the Data Matrix barcode within the fewest iterations and
+           // utilizing the least amount of error correction.
+  IMAQ_HISTOGRAM = 0,  // The function uses a histogram of all of the Data
+                       // Matrix cells to calculate a threshold.
+  IMAQ_LOCAL_CONTRAST = 1,  // The function examines each of the cell's
+                            // neighbors to determine if the cell is on or off.
+  IMAQ_COMBINED = 2,  // The function uses the histogram of the Data Matrix
+                      // barcode to calculate a threshold.
+  IMAQ_ALL_DEMODULATION_MODES =
+      3,  // The function tries IMAQ_HISTOGRAM, then IMAQ_LOCAL_CONTRAST and
+          // then IMAQ_COMBINATION, stopping once one mode is successful.
+  IMAQ_DATA_MATRIX_DEMODULATION_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixDemodulationMode;
+
+typedef enum DataMatrixECC_enum {
+  IMAQ_AUTO_DETECT_ECC = -2,  // Sets the function to determine the Data Matrix
+                              // barcode ECC automatically.
+  IMAQ_ECC_000 =
+      0,  // Sets the function to read Data Matrix barcodes of ECC 000 only.
+  IMAQ_ECC_050 =
+      50,  // Sets the function to read Data Matrix barcodes of ECC 050 only.
+  IMAQ_ECC_080 =
+      80,  // Sets the function to read Data Matrix barcodes of ECC 080 only.
+  IMAQ_ECC_100 =
+      100,  // Sets the function to read Data Matrix barcodes of ECC 100 only.
+  IMAQ_ECC_140 =
+      140,  // Sets the function to read Data Matrix barcodes of ECC 140 only.
+  IMAQ_ECC_000_140 = 190,  // Sets the function to read Data Matrix barcodes of
+                           // ECC 000, ECC 050, ECC 080, ECC 100, and ECC 140
+                           // only.
+  IMAQ_ECC_200 =
+      200,  // Sets the function to read Data Matrix barcodes of ECC 200 only.
+  IMAQ_DATA_MATRIX_ECC_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixECC;
+
+typedef enum DataMatrixPolarity_enum {
+  IMAQ_AUTO_DETECT_POLARITY = -2,  // Sets the function to determine the Data
+                                   // Matrix barcode polarity automatically.
+  IMAQ_BLACK_DATA_ON_WHITE_BACKGROUND = 0,  // Sets the function to read Data
+                                            // Matrix barcodes with dark data on
+                                            // a bright background.
+  IMAQ_WHITE_DATA_ON_BLACK_BACKGROUND = 1,  // Sets the function to read Data
+                                            // Matrix barcodes with bright data
+                                            // on a dark background.
+  IMAQ_DATA_MATRIX_POLARITY_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixPolarity;
+
+typedef enum DataMatrixCellFilterMode_enum {
+  IMAQ_AUTO_DETECT_CELL_FILTER_MODE =
+      -2,  // The function will try all filter modes and uses the one that
+           // decodes the Data Matrix barcode within the fewest iterations and
+           // utilizing the least amount of error correction.
+  IMAQ_AVERAGE_FILTER = 0,  // The function sets the pixel value for the cell to
+                            // the average of the sampled pixels.
+  IMAQ_MEDIAN_FILTER = 1,  // The function sets the pixel value for the cell to
+                           // the median of the sampled pixels.
+  IMAQ_CENTRAL_AVERAGE_FILTER = 2,  // The function sets the pixel value for the
+                                    // cell to the average of the pixels in the
+                                    // center of the cell sample.
+  IMAQ_HIGH_AVERAGE_FILTER =
+      3,  // The function sets the pixel value for the cell to the average value
+          // of the half of the sampled pixels with the highest pixel values.
+  IMAQ_LOW_AVERAGE_FILTER = 4,  // The function sets the pixel value for the
+                                // cell to the average value of the half of the
+                                // sampled pixels with the lowest pixel values.
+  IMAQ_VERY_HIGH_AVERAGE_FILTER =
+      5,  // The function sets the pixel value for the cell to the average value
+          // of the ninth of the sampled pixels with the highest pixel values.
+  IMAQ_VERY_LOW_AVERAGE_FILTER =
+      6,  // The function sets the pixel value for the cell to the average value
+          // of the ninth of the sampled pixels with the lowest pixel values.
+  IMAQ_ALL_CELL_FILTERS = 8,  // The function tries each filter mode, starting
+                              // with IMAQ_AVERAGE_FILTER and ending with
+                              // IMAQ_VERY_LOW_AVERAGE_FILTER, stopping once a
+                              // filter mode decodes correctly.
+  IMAQ_DATA_MATRIX_CELL_FILTER_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixCellFilterMode;
+
+typedef enum WindowBackgroundHatchStyle_enum {
+  IMAQ_HATCH_STYLE_HORIZONTAL =
+      0,  // The background of the display window will be horizontal bars.
+  IMAQ_HATCH_STYLE_VERTICAL =
+      1,  // The background of the display window will be vertical bars.
+  IMAQ_HATCH_STYLE_FORWARD_DIAGONAL =
+      2,  // The background of the display window will be diagonal bars.
+  IMAQ_HATCH_STYLE_BACKWARD_DIAGONAL =
+      3,  // The background of the display window will be diagonal bars.
+  IMAQ_HATCH_STYLE_CROSS = 4,  // The background of the display window will be
+                               // intersecting horizontal and vertical bars.
+  IMAQ_HATCH_STYLE_CROSS_HATCH = 5,  // The background of the display window
+                                     // will be intersecting forward and
+                                     // backward diagonal bars.
+  IMAQ_HATCH_STYLE_SIZE_GUARD = 0xFFFFFFFF
+} WindowBackgroundHatchStyle;
+
+typedef enum DataMatrixMirrorMode_enum {
+  IMAQ_AUTO_DETECT_MIRROR = -2,  // Specifies that the function should determine
+                                 // if the Data Matrix barcode is mirrored.
+  IMAQ_APPEARS_NORMAL = 0,  // Specifies that the function should expect the
+                            // Data Matrix barcode to appear normal.
+  IMAQ_APPEARS_MIRRORED = 1,  // Specifies that the function should expect the
+                              // Data Matrix barcode to appear mirrored.
+  IMAQ_DATA_MATRIX_MIRROR_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixMirrorMode;
+
+typedef enum CalibrationMode2_enum {
+  IMAQ_PERSPECTIVE_MODE = 0,  // Functions correct for distortion caused by the
+                              // camera's perspective.
+  IMAQ_MICROPLANE_MODE =
+      1,  // Functions correct for distortion caused by the camera's lens.
+  IMAQ_SIMPLE_CALIBRATION_MODE = 2,  // Functions do not correct for distortion.
+  IMAQ_CORRECTED_IMAGE_MODE = 3,  // The image is already corrected.
+  IMAQ_NO_CALIBRATION_MODE = 4,  // Image with No calibration.
+  IMAQ_CALIBRATION_MODE2_SIZE_GUARD = 0xFFFFFFFF
+} CalibrationMode2;
+
+typedef enum DataMatrixGradingMode_enum {
+  IMAQ_NO_GRADING =
+      0,  // The function does not make any preparatory calculations.
+  IMAQ_PREPARE_FOR_AIM = 1,  // The function prepares the image for grading
+                             // using the AIM Print Quality metrics.
+  IMAQ_DATA_MATRIX_GRADING_MODE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixGradingMode;
+
+typedef enum WaveletTransformMode_enum {
+  IMAQ_WAVELET_TRANSFORM_INTEGER =
+      0,  // Uses a 5-3 reversible integer transform.
+  IMAQ_WAVELET_TRANSFORM_FLOATING_POINT =
+      1,  // Performs a 9-7 irreversible floating-point transform.
+  IMAQ_WAVELET_TRANSFORM_MODE_SIZE_GUARD = 0xFFFFFFFF
+} WaveletTransformMode;
+
+typedef enum NormalizationMethod_enum {
+  IMAQ_NORMALIZATION_NONE = 0,  // No normalization.
+  IMAQ_NORMALIZATION_HISTOGRAM_MATCHING = 1,  // Adjust image so its histogram
+                                              // is similar to the golden
+                                              // template's histogram.
+  IMAQ_NORMALIZATION_AVERAGE_MATCHING = 2,  // Adjust image so its mean pixel
+                                            // value equals the golden
+                                            // template's mean pixel value.
+  IMAQ_NORMALIZATION_SIZE_GUARD = 0xFFFFFFFF
+} NormalizationMethod;
+
+typedef enum RegistrationMethod_enum {
+  IMAQ_REGISTRATION_NONE = 0,  // No registration.
+  IMAQ_REGISTRATION_PERSPECTIVE = 1,  // Adjust image to correct for minor
+                                      // variations in alignment or perspective.
+  IMAQ_REGISTRATION_SIZE_GUARD = 0xFFFFFFFF
+} RegistrationMethod;
+
+typedef enum LinearAveragesMode_enum {
+  IMAQ_COLUMN_AVERAGES = 1,  // Specifies that the function calculates the mean
+                             // pixel value of each column.
+  IMAQ_ROW_AVERAGES = 2,  // Specifies that the function calculates the mean
+                          // pixel value of each row.
+  IMAQ_RISING_DIAGONAL_AVERAGES =
+      4,  // Specifies that the function calculates the mean pixel value of each
+          // diagonal running from the lower left to the upper right of the
+          // inspected area of the image.
+  IMAQ_FALLING_DIAGONAL_AVERAGES =
+      8,  // Specifies that the function calculates the mean pixel value of each
+          // diagonal running from the upper left to the lower right of the
+          // inspected area of the image.
+  IMAQ_ALL_LINEAR_AVERAGES = 15,  // Specifies that the function calculates all
+                                  // four linear mean pixel values.
+  IMAQ_LINEAR_AVERAGES_MODE_SIZE_GUARD = 0xFFFFFFFF
+} LinearAveragesMode;
+
+typedef enum CompressionType_enum {
+  IMAQ_COMPRESSION_NONE =
+      0,  // Specifies that the function should not compress the image.
+  IMAQ_COMPRESSION_JPEG = 1,  // Specifies that the function should use lossy
+                              // JPEG compression on the image.
+  IMAQ_COMPRESSION_PACKED_BINARY = 2,  // Specifies that the function should use
+                                       // lossless binary packing on the image.
+  IMAQ_COMPRESSION_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} CompressionType;
+
+typedef enum FlattenType_enum {
+  IMAQ_FLATTEN_IMAGE = 0,  // Flattens just the image data.
+  IMAQ_FLATTEN_IMAGE_AND_VISION_INFO = 1,  // Flattens the image data and any
+                                           // Vision information associated with
+                                           // the image.
+  IMAQ_FLATTEN_TYPE_SIZE_GUARD = 0xFFFFFFFF
+} FlattenType;
+
+typedef enum DataMatrixCellSampleSize_enum {
+  IMAQ_AUTO_DETECT_CELL_SAMPLE_SIZE =
+      -2,  // The function will try each sample size and use the one which
+           // decodes the Data Matrix barcode within the fewest iterations and
+           // utilizing the least amount of error correction.
+  IMAQ_1x1 = 1,  // The function will use a 1x1 sized sample from each cell.
+  IMAQ_2x2 = 2,  // The function will use a 2x2 sized sample from each cell.
+  IMAQ_3x3 = 3,  // The function will use a 3x3 sized sample from each cell.
+  IMAQ_4x4 = 4,  // The function will use a 4x4 sized sample from each cell.
+  IMAQ_5x5 = 5,  // The function will use a 5x5 sized sample from each cell.
+  IMAQ_6x6 = 6,  // The function will use a 6x6 sized sample from each cell.
+  IMAQ_7x7 = 7,  // The function will use a 7x7 sized sample from each cell.
+  IMAQ_DATA_MATRIX_CELL_SAMPLE_SIZE_SIZE_GUARD = 0xFFFFFFFF
+} DataMatrixCellSampleSize;
+
+//============================================================================
+//  Forward Declare Data Structures
+//============================================================================
+typedef struct Image_struct Image;
+typedef struct ROI_struct ROI;
+typedef struct Overlay_struct Overlay;
+typedef struct ClassifierSession_struct ClassifierSession;
+typedef struct MultipleGeometricPattern_struct MultipleGeometricPattern;
+typedef int ContourID;
+typedef unsigned long SESSION_ID;
+typedef int AVISession;
+typedef char* FilterName;
+typedef char String255[256];
+typedef struct CharSet_struct CharSet;
+typedef struct OCRSpacingOptions_struct OCRSpacingOptions;
+typedef struct OCRProcessingOptions_struct OCRProcessingOptions;
+typedef struct ReadTextOptions_struct ReadTextOptions;
+typedef struct CharInfo_struct CharInfo;
+typedef struct CharReport_struct CharReport;
+typedef struct ReadTextReport_struct ReadTextReport;
+typedef struct DivisionModel_struct DivisionModel;
+typedef struct FocalLength_struct FocalLength;
+typedef struct PolyModel_struct PolyModel;
+typedef struct DistortionModelParams_struct DistortionModelParams;
+typedef struct PointFloat_struct PointFloat;
+typedef struct InternalParameters_struct InternalParameters;
+typedef struct MaxGridSize_struct MaxGridSize;
+typedef struct ImageSize_struct ImageSize;
+typedef struct CalibrationReferencePoints_struct CalibrationReferencePoints;
+typedef struct GetCameraParametersReport_struct GetCameraParametersReport;
+typedef struct CalibrationAxisInfo_struct CalibrationAxisInfo;
+typedef struct CalibrationLearnSetupInfo_struct CalibrationLearnSetupInfo;
+typedef struct GridDescriptor_struct GridDescriptor;
+typedef struct ErrorStatistics_struct ErrorStatistics;
+typedef struct GetCalibrationInfoReport_struct GetCalibrationInfoReport;
+typedef struct EdgePolarity_struct EdgePolarity;
+typedef struct ClampSettings_struct ClampSettings;
+typedef struct PointDouble_struct PointDouble;
+typedef struct PointDoublePair_struct PointDoublePair;
+typedef struct ClampResults_struct ClampResults;
+typedef struct ClampPoints_struct ClampPoints;
+typedef struct RGBValue_struct RGBValue;
+typedef struct ClampOverlaySettings_struct ClampOverlaySettings;
+typedef struct ClampMax2Report_struct ClampMax2Report;
+typedef struct ContourFitSplineReport_struct ContourFitSplineReport;
+typedef struct LineFloat_struct LineFloat;
+typedef struct LineEquation_struct LineEquation;
+typedef struct ContourFitLineReport_struct ContourFitLineReport;
+typedef struct ContourFitPolynomialReport_struct ContourFitPolynomialReport;
+typedef struct PartialCircle_struct PartialCircle;
+typedef struct PartialEllipse_struct PartialEllipse;
+typedef struct SetupMatchPatternData_struct SetupMatchPatternData;
+typedef struct RangeSettingDouble_struct RangeSettingDouble;
+typedef struct GeometricAdvancedSetupDataOption_struct
+    GeometricAdvancedSetupDataOption;
+typedef struct ContourInfoReport_struct ContourInfoReport;
+typedef struct ROILabel_struct ROILabel;
+typedef struct SupervisedColorSegmentationReport_struct
+    SupervisedColorSegmentationReport;
+typedef struct LabelToROIReport_struct LabelToROIReport;
+typedef struct ColorSegmenationOptions_struct ColorSegmenationOptions;
+typedef struct ClassifiedCurve_struct ClassifiedCurve;
+typedef struct RangeDouble_struct RangeDouble;
+typedef struct RangeLabel_struct RangeLabel;
+typedef struct CurvatureAnalysisReport_struct CurvatureAnalysisReport;
+typedef struct Disparity_struct Disparity;
+typedef struct ComputeDistancesReport_struct ComputeDistancesReport;
+typedef struct MatchMode_struct MatchMode;
+typedef struct ClassifiedDisparity_struct ClassifiedDisparity;
+typedef struct ClassifyDistancesReport_struct ClassifyDistancesReport;
+typedef struct ContourComputeCurvatureReport_struct
+    ContourComputeCurvatureReport;
+typedef struct ContourOverlaySettings_struct ContourOverlaySettings;
+typedef struct CurveParameters_struct CurveParameters;
+typedef struct ExtractContourReport_struct ExtractContourReport;
+typedef struct ConnectionConstraint_struct ConnectionConstraint;
+typedef struct ExtractTextureFeaturesReport_struct ExtractTextureFeaturesReport;
+typedef struct WaveletBandsReport_struct WaveletBandsReport;
+typedef struct CircleFitOptions_struct CircleFitOptions;
+typedef struct EdgeOptions2_struct EdgeOptions2;
+typedef struct FindCircularEdgeOptions_struct FindCircularEdgeOptions;
+typedef struct FindConcentricEdgeOptions_struct FindConcentricEdgeOptions;
+typedef struct ConcentricEdgeFitOptions_struct ConcentricEdgeFitOptions;
+typedef struct FindConcentricEdgeReport_struct FindConcentricEdgeReport;
+typedef struct FindCircularEdgeReport_struct FindCircularEdgeReport;
+typedef struct WindowSize_struct WindowSize;
+typedef struct DisplacementVector_struct DisplacementVector;
+typedef struct WaveletOptions_struct WaveletOptions;
+typedef struct CooccurrenceOptions_struct CooccurrenceOptions;
+typedef struct ParticleClassifierLocalThresholdOptions_struct
+    ParticleClassifierLocalThresholdOptions;
+typedef struct RangeFloat_struct RangeFloat;
+typedef struct ParticleClassifierAutoThresholdOptions_struct
+    ParticleClassifierAutoThresholdOptions;
+typedef struct ParticleClassifierPreprocessingOptions2_struct
+    ParticleClassifierPreprocessingOptions2;
+typedef struct MeasureParticlesReport_struct MeasureParticlesReport;
+typedef struct GeometricPatternMatch3_struct GeometricPatternMatch3;
+typedef struct MatchGeometricPatternAdvancedOptions3_struct
+    MatchGeometricPatternAdvancedOptions3;
+typedef struct ColorOptions_struct ColorOptions;
+typedef struct SampleScore_struct SampleScore;
+typedef struct ClassifierReportAdvanced_struct ClassifierReportAdvanced;
+typedef struct LearnGeometricPatternAdvancedOptions2_struct
+    LearnGeometricPatternAdvancedOptions2;
+typedef struct ParticleFilterOptions2_struct ParticleFilterOptions2;
+typedef struct FindEdgeOptions2_struct FindEdgeOptions2;
+typedef struct FindEdgeReport_struct FindEdgeReport;
+typedef struct FindTransformRectOptions2_struct FindTransformRectOptions2;
+typedef struct FindTransformRectsOptions2_struct FindTransformRectsOptions2;
+typedef struct ReadTextReport3_struct ReadTextReport3;
+typedef struct CharacterStatistics_struct CharacterStatistics;
+typedef struct CharReport3_struct CharReport3;
+typedef struct ArcInfo2_struct ArcInfo2;
+typedef struct EdgeReport2_struct EdgeReport2;
+typedef struct SearchArcInfo_struct SearchArcInfo;
+typedef struct ConcentricRakeReport2_struct ConcentricRakeReport2;
+typedef struct SpokeReport2_struct SpokeReport2;
+typedef struct EdgeInfo_struct EdgeInfo;
+typedef struct SearchLineInfo_struct SearchLineInfo;
+typedef struct RakeReport2_struct RakeReport2;
+typedef struct TransformBehaviors_struct TransformBehaviors;
+typedef struct QRCodeDataToken_struct QRCodeDataToken;
+typedef struct ParticleFilterOptions_struct ParticleFilterOptions;
+typedef struct StraightEdgeReport2_struct StraightEdgeReport2;
+typedef struct StraightEdgeOptions_struct StraightEdgeOptions;
+typedef struct StraightEdge_struct StraightEdge;
+typedef struct QRCodeSearchOptions_struct QRCodeSearchOptions;
+typedef struct QRCodeSizeOptions_struct QRCodeSizeOptions;
+typedef struct QRCodeDescriptionOptions_struct QRCodeDescriptionOptions;
+typedef struct QRCodeReport_struct QRCodeReport;
+typedef struct AIMGradeReport_struct AIMGradeReport;
+typedef struct DataMatrixSizeOptions_struct DataMatrixSizeOptions;
+typedef struct DataMatrixDescriptionOptions_struct DataMatrixDescriptionOptions;
+typedef struct DataMatrixSearchOptions_struct DataMatrixSearchOptions;
+typedef struct DataMatrixReport_struct DataMatrixReport;
+typedef struct JPEG2000FileAdvancedOptions_struct JPEG2000FileAdvancedOptions;
+typedef struct MatchGeometricPatternAdvancedOptions2_struct
+    MatchGeometricPatternAdvancedOptions2;
+typedef struct InspectionAlignment_struct InspectionAlignment;
+typedef struct InspectionOptions_struct InspectionOptions;
+typedef struct CharReport2_struct CharReport2;
+typedef struct CharInfo2_struct CharInfo2;
+typedef struct ReadTextReport2_struct ReadTextReport2;
+typedef struct EllipseFeature_struct EllipseFeature;
+typedef struct CircleFeature_struct CircleFeature;
+typedef struct ConstCurveFeature_struct ConstCurveFeature;
+typedef struct RectangleFeature_struct RectangleFeature;
+typedef struct LegFeature_struct LegFeature;
+typedef struct CornerFeature_struct CornerFeature;
+typedef struct LineFeature_struct LineFeature;
+typedef struct ParallelLinePairFeature_struct ParallelLinePairFeature;
+typedef struct PairOfParallelLinePairsFeature_struct
+    PairOfParallelLinePairsFeature;
+typedef union GeometricFeature_union GeometricFeature;
+typedef struct FeatureData_struct FeatureData;
+typedef struct GeometricPatternMatch2_struct GeometricPatternMatch2;
+typedef struct ClosedCurveFeature_struct ClosedCurveFeature;
+typedef struct LineMatch_struct LineMatch;
+typedef struct LineDescriptor_struct LineDescriptor;
+typedef struct RectangleDescriptor_struct RectangleDescriptor;
+typedef struct RectangleMatch_struct RectangleMatch;
+typedef struct EllipseDescriptor_struct EllipseDescriptor;
+typedef struct EllipseMatch_struct EllipseMatch;
+typedef struct CircleMatch_struct CircleMatch;
+typedef struct CircleDescriptor_struct CircleDescriptor;
+typedef struct ShapeDetectionOptions_struct ShapeDetectionOptions;
+typedef struct Curve_struct Curve;
+typedef struct CurveOptions_struct CurveOptions;
+typedef struct Barcode2DInfo_struct Barcode2DInfo;
+typedef struct DataMatrixOptions_struct DataMatrixOptions;
+typedef struct ClassifierAccuracyReport_struct ClassifierAccuracyReport;
+typedef struct NearestNeighborClassResult_struct NearestNeighborClassResult;
+typedef struct NearestNeighborTrainingReport_struct
+    NearestNeighborTrainingReport;
+typedef struct ParticleClassifierPreprocessingOptions_struct
+    ParticleClassifierPreprocessingOptions;
+typedef struct ClassifierSampleInfo_struct ClassifierSampleInfo;
+typedef struct ClassScore_struct ClassScore;
+typedef struct ClassifierReport_struct ClassifierReport;
+typedef struct NearestNeighborOptions_struct NearestNeighborOptions;
+typedef struct ParticleClassifierOptions_struct ParticleClassifierOptions;
+typedef struct RGBU64Value_struct RGBU64Value;
+typedef struct GeometricPatternMatch_struct GeometricPatternMatch;
+typedef struct MatchGeometricPatternAdvancedOptions_struct
+    MatchGeometricPatternAdvancedOptions;
+typedef struct MatchGeometricPatternOptions_struct MatchGeometricPatternOptions;
+typedef struct LearnGeometricPatternAdvancedOptions_struct
+    LearnGeometricPatternAdvancedOptions;
+typedef struct FitEllipseOptions_struct FitEllipseOptions;
+typedef struct FitCircleOptions_struct FitCircleOptions;
+typedef struct ConstructROIOptions2_struct ConstructROIOptions2;
+typedef struct HSLValue_struct HSLValue;
+typedef struct HSVValue_struct HSVValue;
+typedef struct HSIValue_struct HSIValue;
+typedef struct CIELabValue_struct CIELabValue;
+typedef struct CIEXYZValue_struct CIEXYZValue;
+typedef union Color2_union Color2;
+typedef struct BestEllipse2_struct BestEllipse2;
+typedef struct LearnPatternAdvancedOptions_struct LearnPatternAdvancedOptions;
+typedef struct AVIInfo_struct AVIInfo;
+typedef struct LearnPatternAdvancedShiftOptions_struct
+    LearnPatternAdvancedShiftOptions;
+typedef struct LearnPatternAdvancedRotationOptions_struct
+    LearnPatternAdvancedRotationOptions;
+typedef struct MatchPatternAdvancedOptions_struct MatchPatternAdvancedOptions;
+typedef struct ParticleFilterCriteria2_struct ParticleFilterCriteria2;
+typedef struct BestCircle2_struct BestCircle2;
+typedef struct OCRSpacingOptions_struct OCRSpacingOptions;
+typedef struct OCRProcessingOptions_struct OCRProcessingOptions;
+typedef struct ReadTextOptions_struct ReadTextOptions;
+typedef struct CharInfo_struct CharInfo;
+#if !defined(USERINT_HEADER) && !defined(_CVI_RECT_DEFINED)
+typedef struct Rect_struct Rect;
+#endif
+typedef struct CharReport_struct CharReport;
+typedef struct ReadTextReport_struct ReadTextReport;
+#if !defined(USERINT_HEADER) && !defined(_CVI_POINT_DEFINED)
+typedef struct Point_struct Point;
+#endif
+typedef struct Annulus_struct Annulus;
+typedef struct EdgeLocationReport_struct EdgeLocationReport;
+typedef struct EdgeOptions_struct EdgeOptions;
+typedef struct EdgeReport_struct EdgeReport;
+typedef struct ExtremeReport_struct ExtremeReport;
+typedef struct FitLineOptions_struct FitLineOptions;
+typedef struct DisplayMapping_struct DisplayMapping;
+typedef struct DetectExtremesOptions_struct DetectExtremesOptions;
+typedef struct ImageInfo_struct ImageInfo;
+typedef struct LCDOptions_struct LCDOptions;
+typedef struct LCDReport_struct LCDReport;
+typedef struct LCDSegments_struct LCDSegments;
+typedef struct LearnCalibrationOptions_struct LearnCalibrationOptions;
+typedef struct LearnColorPatternOptions_struct LearnColorPatternOptions;
+typedef struct Line_struct Line;
+typedef struct LinearAverages_struct LinearAverages;
+typedef struct LineProfile_struct LineProfile;
+typedef struct MatchColorPatternOptions_struct MatchColorPatternOptions;
+typedef struct HistogramReport_struct HistogramReport;
+typedef struct ArcInfo_struct ArcInfo;
+typedef struct AxisReport_struct AxisReport;
+typedef struct BarcodeInfo_struct BarcodeInfo;
+typedef struct BCGOptions_struct BCGOptions;
+typedef struct BestCircle_struct BestCircle;
+typedef struct BestEllipse_struct BestEllipse;
+typedef struct BestLine_struct BestLine;
+typedef struct BrowserOptions_struct BrowserOptions;
+typedef struct CoordinateSystem_struct CoordinateSystem;
+typedef struct CalibrationInfo_struct CalibrationInfo;
+typedef struct CalibrationPoints_struct CalibrationPoints;
+typedef struct CaliperOptions_struct CaliperOptions;
+typedef struct CaliperReport_struct CaliperReport;
+typedef struct DrawTextOptions_struct DrawTextOptions;
+typedef struct CircleReport_struct CircleReport;
+typedef struct ClosedContour_struct ClosedContour;
+typedef struct ColorHistogramReport_struct ColorHistogramReport;
+typedef struct ColorInformation_struct ColorInformation;
+typedef struct Complex_struct Complex;
+typedef struct ConcentricRakeReport_struct ConcentricRakeReport;
+typedef struct ConstructROIOptions_struct ConstructROIOptions;
+typedef struct ContourInfo_struct ContourInfo;
+typedef union ContourUnion_union ContourUnion;
+typedef struct ContourInfo2_struct ContourInfo2;
+typedef struct ContourPoint_struct ContourPoint;
+typedef struct CoordinateTransform_struct CoordinateTransform;
+typedef struct CoordinateTransform2_struct CoordinateTransform2;
+typedef struct CannyOptions_struct CannyOptions;
+typedef struct Range_struct Range;
+typedef struct UserPointSymbol_struct UserPointSymbol;
+typedef struct View3DOptions_struct View3DOptions;
+typedef struct MatchPatternOptions_struct MatchPatternOptions;
+typedef struct TIFFFileOptions_struct TIFFFileOptions;
+typedef union Color_union Color;
+typedef union PixelValue_union PixelValue;
+typedef struct OpenContour_struct OpenContour;
+typedef struct OverlayTextOptions_struct OverlayTextOptions;
+typedef struct ParticleFilterCriteria_struct ParticleFilterCriteria;
+typedef struct ParticleReport_struct ParticleReport;
+typedef struct PatternMatch_struct PatternMatch;
+typedef struct QuantifyData_struct QuantifyData;
+typedef struct QuantifyReport_struct QuantifyReport;
+typedef struct RakeOptions_struct RakeOptions;
+typedef struct RakeReport_struct RakeReport;
+typedef struct TransformReport_struct TransformReport;
+typedef struct ShapeReport_struct ShapeReport;
+typedef struct MeterArc_struct MeterArc;
+typedef struct ThresholdData_struct ThresholdData;
+typedef struct StructuringElement_struct StructuringElement;
+typedef struct SpokeReport_struct SpokeReport;
+typedef struct SimpleEdgeOptions_struct SimpleEdgeOptions;
+typedef struct SelectParticleCriteria_struct SelectParticleCriteria;
+typedef struct SegmentInfo_struct SegmentInfo;
+typedef struct RotationAngleRange_struct RotationAngleRange;
+typedef struct RotatedRect_struct RotatedRect;
+typedef struct ROIProfile_struct ROIProfile;
+typedef struct ToolWindowOptions_struct ToolWindowOptions;
+typedef struct SpokeOptions_struct SpokeOptions;
+
+//============================================================================
+// Data Structures
+//============================================================================
+#if !defined __GNUC__ && !defined _M_X64
+#pragma pack(push, 1)
+#endif
+typedef struct DivisionModel_struct {
+  float kappa;  // The learned kappa coefficient of division model.
+} DivisionModel;
+
+typedef struct FocalLength_struct {
+  float fx;  // Focal length in X direction.
+  float fy;  // Focal length in Y direction.
+} FocalLength;
+
+typedef struct PolyModel_struct {
+  float* kCoeffs;  // The learned radial coefficients of polynomial model.
+  unsigned int numKCoeffs;  // Number of K coefficients.
+  float p1;  // The P1(learned tangential coefficients of polynomial model).
+  float p2;  // The P2(learned tangential coefficients of polynomial model).
+} PolyModel;
+
+typedef struct DistortionModelParams_struct {
+  DistortionModel distortionModel;  // Type of learned distortion model.
+  PolyModel polyModel;  // The learned coefficients of polynomial model.
+  DivisionModel divisionModel;  // The learned coefficient of division model.
+} DistortionModelParams;
+
+typedef struct PointFloat_struct {
+  float x;  // The x-coordinate of the point.
+  float y;  // The y-coordinate of the point.
+} PointFloat;
+
+typedef struct InternalParameters_struct {
+  char isInsufficientData;
+  FocalLength focalLength;
+  PointFloat opticalCenter;
+} InternalParameters;
+
+typedef struct MaxGridSize_struct {
+  unsigned int xMax;  // Maximum x limit for the grid size.
+  unsigned int yMax;  // Maximum y limit for the grid size.
+} MaxGridSize;
+
+typedef struct ImageSize_struct {
+  unsigned int xRes;  // X resolution of the image.
+  unsigned int yRes;  // Y resolution of the image.
+} ImageSize;
+
+typedef struct CalibrationReferencePoints_struct {
+  PointDouble*
+      pixelCoords;  // Specifies the coordinates of the pixel reference points.
+  unsigned int numPixelCoords;  // Number of pixel coordinates.
+  PointDouble*
+      realCoords;  // Specifies the measuring unit associated with the image.
+  unsigned int numRealCoords;  // Number of real coordinates.
+  CalibrationUnit units;  // Specifies the units of X Step and Y Step.
+  ImageSize imageSize;  // Specifies the size of calibration template image.
+} CalibrationReferencePoints;
+
+typedef struct GetCameraParametersReport_struct {
+  double*
+      projectionMatrix;  // The projection(homography) matrix of working plane.
+  unsigned int projectionMatrixRows;  // Number of rows in projection matrix.
+  unsigned int projectionMatrixCols;  // Number of columns in projection matrix.
+  DistortionModelParams distortion;  // Distortion model Coefficients.
+  InternalParameters internalParams;  // The learned internal paramters of
+                                      // camera model such as focal length and
+                                      // optical center.
+} GetCameraParametersReport;
+
+typedef struct CalibrationAxisInfo_struct {
+  PointFloat center;  // The origin of the reference coordinate system,
+                      // expressed in pixel units.
+  float rotationAngle;  // The angle of the x-axis of the real-world coordinate
+                        // system, in relation to the horizontal.
+  AxisOrientation axisDirection;  // Specifies the direction of the calibraiton
+                                  // axis which is either Direct or Indirect.
+} CalibrationAxisInfo;
+
+typedef struct CalibrationLearnSetupInfo_struct {
+  CalibrationMode2 calibrationMethod;  // Type of calibration method used.
+  DistortionModel distortionModel;  // Type of learned distortion model.
+  ScalingMethod
+      scaleMode;  // The aspect scaling to use when correcting an image.
+  CalibrationROI roiMode;  // The ROI to use when correcting an image.
+  char learnCorrectionTable;  // Set this input to true value if you want the
+                              // correction table to be determined and stored.
+} CalibrationLearnSetupInfo;
+
+typedef struct GridDescriptor_struct {
+  float xStep;  // The distance in the x direction between two adjacent pixels
+                // in units specified by unit.
+  float yStep;  // The distance in the y direction between two adjacent pixels
+                // in units specified by unit.
+  CalibrationUnit unit;  // The unit of measure for the image.
+} GridDescriptor;
+
+typedef struct ErrorStatistics_struct {
+  double mean;  // Mean error statistics value.
+  double maximum;  // Maximum value of error.
+  double standardDeviation;  // The standard deviation error statistiscs value.
+  double distortion;  // The distortion error statistics value.
+} ErrorStatistics;
+
+typedef struct GetCalibrationInfoReport_struct {
+  ROI* userRoi;  // Specifies the ROI the user provided when learning the
+                 // calibration.
+  ROI* calibrationRoi;  // Specifies the ROI that corresponds to the region of
+                        // the image where the calibration information is
+                        // accurate.
+  CalibrationAxisInfo
+      axisInfo;  // Reference Coordinate System for the real-world coordinates.
+  CalibrationLearnSetupInfo
+      learnSetupInfo;  // Calibration learn setup information.
+  GridDescriptor gridDescriptor;  // Specifies scaling constants used to
+                                  // calibrate the image.
+  float* errorMap;  // The the error map of calibration template image.
+  unsigned int errorMapRows;  // Number of rows in error map.
+  unsigned int errorMapCols;  // Number of Columns in error map.
+  ErrorStatistics errorStatistics;  // Error statistics of the calibration.
+} GetCalibrationInfoReport;
+
+typedef struct EdgePolarity_struct {
+  EdgePolaritySearchMode start;
+  EdgePolaritySearchMode end;
+} EdgePolarity;
+
+typedef struct ClampSettings_struct {
+  double angleRange;  // Specifies the angle range.
+  EdgePolarity edgePolarity;  // Specifies the edge polarity.
+} ClampSettings;
+
+typedef struct PointDouble_struct {
+  double x;  // The x-coordinate of the point.
+  double y;  // The y-coordinate of the point.
+} PointDouble;
+
+typedef struct PointDoublePair_struct {
+  PointDouble start;  // The Start co-ordinate of the pair.
+  PointDouble end;  // The End co-ordinate of the pair.
+} PointDoublePair;
+
+typedef struct ClampResults_struct {
+  double distancePix;  // Defines the Pixel world distance.
+  double distanceRealWorld;  // Defines the real world distance.
+  double angleAbs;  // Defines the absolute angle.
+  double angleRelative;  // Defines the relative angle.
+} ClampResults;
+
+typedef struct ClampPoints_struct {
+  PointDoublePair pixel;  // Specifies the pixel world point pair for clamp.
+  PointDoublePair realWorld;  // Specifies the real world point pair for clamp.
+} ClampPoints;
+
+typedef struct RGBValue_struct {
+  unsigned char B;  // The blue value of the color.
+  unsigned char G;  // The green value of the color.
+  unsigned char R;  // The red value of the color.
+  unsigned char alpha;  // The alpha value of the color, which represents extra
+                        // information about a color image, such as gamma
+                        // correction.
+} RGBValue;
+
+typedef struct ClampOverlaySettings_struct {
+  int showSearchArea;  // If TRUE, the function overlays the search area on the
+                       // image.
+  int showCurves;  // If TRUE, the function overlays the curves on the image.
+  int showClampLocation;  // If TRUE, the function overlays the clamp location
+                          // on the image.
+  int showResult;  // If TRUE, the function overlays the hit lines to the object
+                   // and the edge used to generate the hit line on the result
+                   // image.
+  RGBValue searchAreaColor;  // Specifies the RGB color value to use to overlay
+                             // the search area.
+  RGBValue curvesColor;  // Specifies the RGB color value to use to overlay the
+                         // curves.
+  RGBValue clampLocationsColor;  // Specifies the RGB color value to use to
+                                 // overlay the clamp locations.
+  RGBValue resultColor;  // Specifies the RGB color value to use to overlay the
+                         // results.
+  char* overlayGroupName;  // Specifies the group overlay name for the step
+                           // overlays.
+} ClampOverlaySettings;
+
+typedef struct ClampMax2Report_struct {
+  ClampResults clampResults;  // Specifies the Clamp results information
+                              // returned by the function.
+  ClampPoints clampPoints;  // Specifies the clamp points information returned
+                            // by the function.
+  unsigned int calibrationValid;  // Specifies if the calibration information is
+                                  // valid or not.
+} ClampMax2Report;
+
+typedef struct ContourFitSplineReport_struct {
+  PointDouble* points;  // It returns the points of the best-fit B-spline curve.
+  int numberOfPoints;  // Number of Best fit points returned.
+} ContourFitSplineReport;
+
+typedef struct LineFloat_struct {
+  PointFloat start;  // The coordinate location of the start of the line.
+  PointFloat end;  // The coordinate location of the end of the line.
+} LineFloat;
+
+typedef struct LineEquation_struct {
+  double a;  // The a coefficient of the line equation.
+  double b;  // The b coefficient of the line equation.
+  double c;  // The c coefficient of the line equation.
+} LineEquation;
+
+typedef struct ContourFitLineReport_struct {
+  LineFloat lineSegment;  // Line Segment represents the intersection of the
+                          // line equation and the contour.
+  LineEquation lineEquation;  // Line Equation is a structure of three
+                              // coefficients A, B, and C of the equation in the
+                              // normal form (Ax + By + C=0) of the best fit
+                              // line.
+} ContourFitLineReport;
+
+typedef struct ContourFitPolynomialReport_struct {
+  PointDouble* bestFit;  // It returns the points of the best-fit polynomial.
+  int numberOfPoints;  // Number of Best fit points returned.
+  double* polynomialCoefficients;  // Polynomial Coefficients returns the
+                                   // coefficients of the polynomial equation.
+  int numberOfCoefficients;  // Number of Coefficients returned in the
+                             // polynomial coefficients array.
+} ContourFitPolynomialReport;
+
+typedef struct PartialCircle_struct {
+  PointFloat center;  // Center of the circle.
+  double radius;  // Radius of the circle.
+  double startAngle;  // Start angle of the fitted structure.
+  double endAngle;  // End angle of the fitted structure.
+} PartialCircle;
+
+typedef struct PartialEllipse_struct {
+  PointFloat center;  // Center of the Ellipse.
+  double angle;  // Angle of the ellipse.
+  double majorRadius;  // The length of the semi-major axis of the ellipse.
+  double minorRadius;  // The length of the semi-minor axis of the ellipse.
+  double startAngle;  // Start angle of the fitted structure.
+  double endAngle;  // End angle of the fitted structure.
+} PartialEllipse;
+
+typedef struct SetupMatchPatternData_struct {
+  unsigned char* matchSetupData;  // String containing the match setup data.
+  int numMatchSetupData;  // Number of match setup data.
+} SetupMatchPatternData;
+
+typedef struct RangeSettingDouble_struct {
+  SettingType settingType;  // Match Constraints specifies the match option
+                            // whose values you want to constrain by the given
+                            // range.
+  double min;  // Min is the minimum value of the range for a given Match
+               // Constraint.
+  double max;  // Max is the maximum value of the range for a given Match
+               // Constraint.
+} RangeSettingDouble;
+
+typedef struct GeometricAdvancedSetupDataOption_struct {
+  GeometricSetupDataItem type;  // It determines the option you want to use
+                                // during the matching phase.
+  double value;  // Value is the value for the option you want to use during the
+                 // matching phase.
+} GeometricAdvancedSetupDataOption;
+
+typedef struct ContourInfoReport_struct {
+  PointDouble* pointsPixel;  // Points (pixel) specifies the location of every
+                             // point detected on the curve, in pixels.
+  unsigned int numPointsPixel;  // Number of points pixel elements.
+  PointDouble* pointsReal;  // Points (real) specifies the location of every
+                            // point detected on the curve, in calibrated units.
+  unsigned int numPointsReal;  // Number of points real elements.
+  double* curvaturePixel;  // Curvature Pixel displays the curvature profile for
+                           // the selected contour, in pixels.
+  unsigned int numCurvaturePixel;  // Number of curvature pixels.
+  double* curvatureReal;  // Curvature Real displays the curvature profile for
+                          // the selected contour, in calibrated units.
+  unsigned int numCurvatureReal;  // Number of curvature Real elements.
+  double length;  // Length (pixel) specifies the length, in pixels, of the
+                  // curves in the image.
+  double lengthReal;  // Length (real) specifies the length, in calibrated
+                      // units, of the curves within the curvature range.
+  unsigned int hasEquation;  // Has Equation specifies whether the contour has a
+                             // fitted equation.
+} ContourInfoReport;
+
+typedef struct ROILabel_struct {
+  char* className;  // Specifies the classname you want to segment.
+  unsigned int
+      label;  // Label is the label number associated with the Class Name.
+} ROILabel;
+
+typedef struct SupervisedColorSegmentationReport_struct {
+  ROILabel* labelOut;  // The Roi labels array.
+  unsigned int numLabelOut;  // The number of elements in labelOut array.
+} SupervisedColorSegmentationReport;
+
+typedef struct LabelToROIReport_struct {
+  ROI** roiArray;  // Array of ROIs.
+  unsigned int numOfROIs;  // Number of ROIs in the roiArray.
+  unsigned int* labelsOutArray;  // Array of labels.
+  unsigned int numOfLabels;  // Number of labels.
+  int* isTooManyVectorsArray;  // isTooManyVectorsArray array.
+  unsigned int isTooManyVectorsArraySize;  // Number of elements in
+                                           // isTooManyVectorsArray.
+} LabelToROIReport;
+
+typedef struct ColorSegmenationOptions_struct {
+  unsigned int windowX;  // X is the window size in x direction.
+  unsigned int windowY;  // Y is the window size in y direction.
+  unsigned int stepSize;  // Step Size is the distance between two windows.
+  unsigned int minParticleArea;  // Min Particle Area is the minimum number of
+                                 // allowed pixels.
+  unsigned int maxParticleArea;  // Max Particle Area is the maximum number of
+                                 // allowed pixels.
+  short isFineSegment;  // When enabled, the step processes the boundary pixels
+                        // of each segmentation cluster using a step size of 1.
+} ColorSegmenationOptions;
+
+typedef struct ClassifiedCurve_struct {
+  double length;  // Specifies the length, in pixels, of the curves within the
+                  // curvature range.
+  double lengthReal;  // specifies the length, in calibrated units, of the
+                      // curves within the curvature range.
+  double maxCurvature;  // specifies the maximum curvature, in pixels, for the
+                        // selected curvature range.
+  double maxCurvatureReal;  // specifies the maximum curvature, in calibrated
+                            // units, for the selected curvature range.
+  unsigned int label;  // specifies the class to which the the sample belongs.
+  PointDouble* curvePoints;  // Curve Points is a point-coordinate cluster that
+                             // defines the points of the curve.
+  unsigned int numCurvePoints;  // Number of curve points.
+} ClassifiedCurve;
+
+typedef struct RangeDouble_struct {
+  double minValue;  // The minimum value of the range.
+  double maxValue;  // The maximum value of the range.
+} RangeDouble;
+
+typedef struct RangeLabel_struct {
+  RangeDouble range;  // Specifies the range of curvature values.
+  unsigned int label;  // Class Label specifies the class to which the the
+                       // sample belongs.
+} RangeLabel;
+
+typedef struct CurvatureAnalysisReport_struct {
+  ClassifiedCurve* curves;
+  unsigned int numCurves;
+} CurvatureAnalysisReport;
+
+typedef struct Disparity_struct {
+  PointDouble
+      current;  // Current is a array of points that defines the target contour.
+  PointDouble reference;  // reference is a array of points that defines the
+                          // template contour.
+  double distance;  // Specifies the distance, in pixels, between the template
+                    // contour point and the target contour point.
+} Disparity;
+
+typedef struct ComputeDistancesReport_struct {
+  Disparity*
+      distances;  // Distances is an array containing the computed distances.
+  unsigned int numDistances;  // Number elements in the distances array.
+  Disparity* distancesReal;  // Distances Real is an array containing the
+                             // computed distances in calibrated units.
+  unsigned int numDistancesReal;  // Number of elements in real distances array.
+} ComputeDistancesReport;
+
+typedef struct MatchMode_struct {
+  unsigned int rotation;  // Rotation When enabled, the Function searches for
+                          // occurrences of the template in the inspection
+                          // image, allowing for template matches to be rotated.
+  unsigned int scale;  // Rotation When enabled, the Function searches for
+                       // occurrences of the template in the inspection image,
+                       // allowing for template matches to be rotated.
+  unsigned int occlusion;  // Occlusion specifies whether or not to search for
+                           // occluded versions of the shape.
+} MatchMode;
+
+typedef struct ClassifiedDisparity_struct {
+  double length;  // Length (pixel) specifies the length, in pixels, of the
+                  // curves within the curvature range.
+  double lengthReal;  // Length (real) specifies the length, in calibrated
+                      // units, of the curves within the curvature range.
+  double maxDistance;  // Maximum Distance (pixel) specifies the maximum
+                       // distance, in pixels, between points along the selected
+                       // contour and the template contour.
+  double maxDistanceReal;  // Maximum Distance (real) specifies the maximum
+                           // distance, in calibrated units, between points
+                           // along the selected contour and the template
+                           // contour.
+  unsigned int label;  // Class Label specifies the class to which the the
+                       // sample belongs.
+  PointDouble* templateSubsection;  // Template subsection points is an array of
+                                    // points that defines the boundary of the
+                                    // template.
+  unsigned int numTemplateSubsection;  // Number of reference points.
+  PointDouble* targetSubsection;  // Current Points(Target subsection points) is
+                                  // an array of points that defines the
+                                  // boundary of the target.
+  unsigned int numTargetSubsection;  // Number of current points.
+} ClassifiedDisparity;
+
+typedef struct ClassifyDistancesReport_struct {
+  ClassifiedDisparity* classifiedDistances;  // Disparity array containing the
+                                             // classified distances.
+  unsigned int
+      numClassifiedDistances;  // Number of elements in the disparity array.
+} ClassifyDistancesReport;
+
+typedef struct ContourComputeCurvatureReport_struct {
+  double* curvaturePixel;  // Curvature Pixel displays the curvature profile for
+                           // the selected contour, in pixels.
+  unsigned int numCurvaturePixel;  // Number of curvature pixels.
+  double* curvatureReal;  // Curvature Real displays the curvature profile for
+                          // the selected contour, in calibrated units.
+  unsigned int numCurvatureReal;  // Number of curvature Real elements.
+} ContourComputeCurvatureReport;
+
+typedef struct ContourOverlaySettings_struct {
+  unsigned int overlay;  // Overlay specifies whether to display the overlay on
+                         // the image.
+  RGBValue color;  // Color is the color of the overlay.
+  unsigned int width;  // Width specifies the width of the overlay in pixels.
+  unsigned int maintainWidth;  // Maintain Width? specifies whether you want the
+                               // overlay measured in screen pixels or image
+                               // pixels.
+} ContourOverlaySettings;
+
+typedef struct CurveParameters_struct {
+  ExtractionMode extractionMode;  // Specifies the method the function uses to
+                                  // identify curves in the image.
+  int threshold;  // Specifies the minimum contrast a seed point must have in
+                  // order to begin a curve.
+  EdgeFilterSize filterSize;  // Specifies the width of the edge filter the
+                              // function uses to identify curves in the image.
+  int minLength;  // Specifies the length, in pixels, of the smallest curve the
+                  // function will extract.
+  int searchStep;  // Search Step Size specifies the distance, in the y
+                   // direction, between the image rows that the algorithm
+                   // inspects for curve seed points.
+  int maxEndPointGap;  // Specifies the maximum gap, in pixels, between the
+                       // endpoints of a curve that the function identifies as a
+                       // closed curve.
+  int subpixel;  // Subpixel specifies whether to detect curve points with
+                 // subpixel accuracy.
+} CurveParameters;
+
+typedef struct ExtractContourReport_struct {
+  PointDouble* contourPoints;  // Contour Points specifies every point found on
+                               // the contour.
+  int numContourPoints;  // Number of contour points.
+  PointDouble* sourcePoints;  // Source Image Points specifies every point found
+                              // on the contour in the source image.
+  int numSourcePoints;  // Number of source points.
+} ExtractContourReport;
+
+typedef struct ConnectionConstraint_struct {
+  ConnectionConstraintType constraintType;  // Constraint Type specifies what
+                                            // criteria to use to consider two
+                                            // curves part of a contour.
+  RangeDouble range;  // Specifies range for a given Match Constraint.
+} ConnectionConstraint;
+
+typedef struct ExtractTextureFeaturesReport_struct {
+  int* waveletBands;  // The array having all the Wavelet Banks used for
+                      // extraction.
+  int numWaveletBands;  // Number of wavelet banks in the Array.
+  double** textureFeatures;  // 2-D array to store all the Texture features
+                             // extracted.
+  int textureFeaturesRows;  // Number of Rows in the Texture Features array.
+  int textureFeaturesCols;  // Number of Cols in Texture Features array.
+} ExtractTextureFeaturesReport;
+
+typedef struct WaveletBandsReport_struct {
+  float** LLBand;  // 2-D array for LL Band.
+  float** LHBand;  // 2-D array for LH Band.
+  float** HLBand;  // 2-D array for HL Band.
+  float** HHBand;  // 2-D array for HH Band.
+  float** LLLBand;  // 2-D array for LLL Band.
+  float** LLHBand;  // 2-D array for LLH Band.
+  float LHLBand;  // 2-D array for LHL Band.
+  float** LHHBand;  // 2-D array for LHH Band.
+  int rows;  // Number of Rows for each of the 2-D arrays.
+  int cols;  // Number of Columns for each of the 2-D arrays.
+} WaveletBandsReport;
+
+typedef struct CircleFitOptions_struct {
+  int maxRadius;  // Specifies the acceptable distance, in pixels, that a point
+                  // determined to belong to the circle can be from the
+                  // perimeter of the circle.
+  double stepSize;  // Step Size is the angle, in degrees, between each radial
+                    // line in the annular region.
+  RakeProcessType processType;  // Method used to process the data extracted for
+                                // edge detection.
+} CircleFitOptions;
+
+typedef struct EdgeOptions2_struct {
+  EdgePolaritySearchMode
+      polarity;  // Specifies the polarity of the edges to be found.
+  unsigned int kernelSize;  // Specifies the size of the edge detection kernel.
+  unsigned int width;  // Specifies the number of pixels averaged perpendicular
+                       // to the search direction to compute the edge profile
+                       // strength at each point along the search ROI.
+  float minThreshold;  // Specifies the minimum edge strength (gradient
+                       // magnitude) required for a detected edge.
+  InterpolationMethod interpolationType;  // Specifies the interpolation method
+                                          // used to locate the edge position.
+  ColumnProcessingMode columnProcessingMode;  // Specifies the method used to
+                                              // find the straight edge.
+} EdgeOptions2;
+
+typedef struct FindCircularEdgeOptions_struct {
+  SpokeDirection
+      direction;  // Specifies the Spoke direction to search in the ROI.
+  int showSearchArea;  // If TRUE, the function overlays the search area on the
+                       // image.
+  int showSearchLines;  // If TRUE, the function overlays the search lines used
+                        // to locate the edges on the image.
+  int showEdgesFound;  // If TRUE, the function overlays the locations of the
+                       // edges found on the image.
+  int showResult;  // If TRUE, the function overlays the hit lines to the object
+                   // and the edge used to generate the hit line on the result
+                   // image.
+  RGBValue searchAreaColor;  // Specifies the RGB color value to use to overlay
+                             // the search area.
+  RGBValue searchLinesColor;  // Specifies the RGB color value to use to overlay
+                              // the search lines.
+  RGBValue searchEdgesColor;  // Specifies the RGB color value to use to overlay
+                              // the search edges.
+  RGBValue resultColor;  // Specifies the RGB color value to use to overlay the
+                         // results.
+  char* overlayGroupName;  // Specifies the overlay group name to assign to the
+                           // overlays.
+  EdgeOptions2 edgeOptions;  // Specifies the edge detection options along a
+                             // single search line.
+} FindCircularEdgeOptions;
+
+typedef struct FindConcentricEdgeOptions_struct {
+  ConcentricRakeDirection direction;  // Specifies the Concentric Rake
+                                      // direction.
+  int showSearchArea;  // If TRUE, the function overlays the search area on the
+                       // image.
+  int showSearchLines;  // If TRUE, the function overlays the search lines used
+                        // to locate the edges on the image.
+  int showEdgesFound;  // If TRUE, the function overlays the locations of the
+                       // edges found on the image.
+  int showResult;  // If TRUE, the function overlays the hit lines to the object
+                   // and the edge used to generate the hit line on the result
+                   // image.
+  RGBValue searchAreaColor;  // Specifies the RGB color value to use to overlay
+                             // the search area.
+  RGBValue searchLinesColor;  // Specifies the RGB color value to use to overlay
+                              // the search lines.
+  RGBValue searchEdgesColor;  // Specifies the RGB color value to use to overlay
+                              // the search edges.
+  RGBValue resultColor;  // Specifies the RGB color value to use to overlay the
+                         // results.
+  char* overlayGroupName;  // Specifies the overlay group name to assign to the
+                           // overlays.
+  EdgeOptions2 edgeOptions;  // Specifies the edge detection options along a
+                             // single search line.
+} FindConcentricEdgeOptions;
+
+typedef struct ConcentricEdgeFitOptions_struct {
+  int maxRadius;  // Specifies the acceptable distance, in pixels, that a point
+                  // determined to belong to the circle can be from the
+                  // perimeter of the circle.
+  double stepSize;  // The sampling factor that determines the gap between the
+                    // rake lines.
+  RakeProcessType processType;  // Method used to process the data extracted for
+                                // edge detection.
+} ConcentricEdgeFitOptions;
+
+typedef struct FindConcentricEdgeReport_struct {
+  PointFloat startPt;  // Pixel Coordinates for starting point of the edge.
+  PointFloat endPt;  // Pixel Coordinates for end point of the edge.
+  PointFloat startPtCalibrated;  // Real world Coordinates for starting point of
+                                 // the edge.
+  PointFloat
+      endPtCalibrated;  // Real world Coordinates for end point of the edge.
+  double angle;  // Angle of the edge found.
+  double angleCalibrated;  // Calibrated angle of the edge found.
+  double straightness;  // The straightness value of the detected straight edge.
+  double avgStrength;  // Average strength of the egde found.
+  double avgSNR;  // Average SNR(Signal to Noise Ratio) for the edge found.
+  int lineFound;  // If the edge is found or not.
+} FindConcentricEdgeReport;
+
+typedef struct FindCircularEdgeReport_struct {
+  PointFloat centerCalibrated;  // Real world Coordinates of the Center.
+  double radiusCalibrated;  // Real world radius of the Circular Edge found.
+  PointFloat center;  // Pixel Coordinates of the Center.
+  double radius;  // Radius in pixels of the Circular Edge found.
+  double roundness;  // The roundness of the calculated circular edge.
+  double avgStrength;  // Average strength of the egde found.
+  double avgSNR;  // Average SNR(Signal to Noise Ratio) for the edge found.
+  int circleFound;  // If the circlular edge is found or not.
+} FindCircularEdgeReport;
+
+typedef struct WindowSize_struct {
+  int x;  // Window lenght on X direction.
+  int y;  // Window lenght on Y direction.
+  int stepSize;  // Distance between windows.
+} WindowSize;
+
+typedef struct DisplacementVector_struct {
+  int x;  // length on X direction.
+  int y;  // length on Y direction.
+} DisplacementVector;
+
+typedef struct WaveletOptions_struct {
+  WaveletType typeOfWavelet;  // Type of wavelet(db, bior.
+  float minEnergy;  // Minimum Energy in the bands to consider for texture
+                    // defect detection.
+} WaveletOptions;
+
+typedef struct CooccurrenceOptions_struct {
+  int level;  // Level/size of matrix.
+  DisplacementVector
+      displacement;  // Displacemnet between pixels to accumulate the matrix.
+} CooccurrenceOptions;
+
+typedef struct ParticleClassifierLocalThresholdOptions_struct {
+  LocalThresholdMethod
+      method;  // Specifies the local thresholding method the function uses.
+  ParticleType particleType;  // Specifies what kind of particles to look for.
+  unsigned int windowWidth;  // The width of the rectangular window around the
+                             // pixel on which the function performs the local
+                             // threshold.
+  unsigned int windowHeight;  // The height of the rectangular window around the
+                              // pixel on which the function performs the local
+                              // threshold.
+  double deviationWeight;  // Specifies the k constant used in the Niblack local
+                           // thresholding algorithm, which determines the
+                           // weight applied to the variance calculation.
+} ParticleClassifierLocalThresholdOptions;
+
+typedef struct RangeFloat_struct {
+  float minValue;  // The minimum value of the range.
+  float maxValue;  // The maximum value of the range.
+} RangeFloat;
+
+typedef struct ParticleClassifierAutoThresholdOptions_struct {
+  ThresholdMethod method;  // The method for binary thresholding, which
+                           // specifies how to calculate the classes.
+  ParticleType particleType;  // Specifies what kind of particles to look for.
+  RangeFloat limits;  // The limits on the automatic threshold range.
+} ParticleClassifierAutoThresholdOptions;
+
+typedef struct ParticleClassifierPreprocessingOptions2_struct {
+  ParticleClassifierThresholdType
+      thresholdType;  // The type of threshold to perform on the image.
+  RangeFloat manualThresholdRange;  // The range of pixels to keep if manually
+                                    // thresholding the image.
+  ParticleClassifierAutoThresholdOptions
+      autoThresholdOptions;  // The options used to auto threshold the image.
+  ParticleClassifierLocalThresholdOptions
+      localThresholdOptions;  // The options used to local threshold the image.
+  int rejectBorder;  // Set this element to TRUE to reject border particles.
+  int numErosions;  // The number of erosions to perform.
+} ParticleClassifierPreprocessingOptions2;
+
+typedef struct MeasureParticlesReport_struct {
+  double** pixelMeasurements;  // The measurements on the particles in the
+                               // image, in pixel coordinates.
+  double** calibratedMeasurements;  // The measurements on the particles in the
+                                    // image, in real-world coordinates.
+  size_t numParticles;  // The number of particles on which measurements were
+                        // taken.
+  size_t numMeasurements;  // The number of measurements taken.
+} MeasureParticlesReport;
+
+typedef struct GeometricPatternMatch3_struct {
+  PointFloat
+      position;  // The location of the origin of the template in the match.
+  float rotation;  // The rotation of the match relative to the template image,
+                   // in degrees.
+  float scale;  // The size of the match relative to the size of the template
+                // image, expressed as a percentage.
+  float score;  // The accuracy of the match.
+  PointFloat corner[4];  // An array of four points describing the rectangle
+                         // surrounding the template image.
+  int inverse;  // This element is TRUE if the match is an inverse of the
+                // template image.
+  float occlusion;  // The percentage of the match that is occluded.
+  float templateMatchCurveScore;  // The accuracy of the match obtained by
+                                  // comparing the template curves to the curves
+                                  // in the match region.
+  float matchTemplateCurveScore;  // The accuracy of the match obtained by
+                                  // comparing the curves in the match region to
+                                  // the template curves.
+  float correlationScore;  // The accuracy of the match obtained by comparing
+                           // the template image to the match region using a
+                           // correlation metric that compares the two regions
+                           // as a function of their pixel values.
+  PointFloat calibratedPosition;  // The location of the origin of the template
+                                  // in the match.
+  float calibratedRotation;  // The rotation of the match relative to the
+                             // template image, in degrees.
+  PointFloat calibratedCorner[4];  // An array of four points describing the
+                                   // rectangle surrounding the template image.
+} GeometricPatternMatch3;
+
+typedef struct MatchGeometricPatternAdvancedOptions3_struct {
+  unsigned int subpixelIterations;  // Specifies the maximum number of
+                                    // incremental improvements used to refine
+                                    // matches with subpixel information.
+  double subpixelTolerance;  // Specifies the maximum amount of change, in
+                             // pixels, between consecutive incremental
+                             // improvements in the match position before the
+                             // function stops refining the match position.
+  unsigned int
+      initialMatchListLength;  // Specifies the maximum size of the match list.
+  int targetTemplateCurveScore;  // Set this element to TRUE to specify that the
+                                 // function should calculate the match curve to
+                                 // template curve score and return it for each
+                                 // match result.
+  int correlationScore;  // Set this element to TRUE to specify that the
+                         // function should calculate the correlation score and
+                         // return it for each match result.
+  double minMatchSeparationDistance;  // Specifies the minimum separation
+                                      // distance, in pixels, between the
+                                      // origins of two matches that have unique
+                                      // positions.
+  double minMatchSeparationAngle;  // Specifies the minimum angular difference,
+                                   // in degrees, between two matches that have
+                                   // unique angles.
+  double minMatchSeparationScale;  // Specifies the minimum difference in scale,
+                                   // expressed as a percentage, between two
+                                   // matches that have unique scales.
+  double maxMatchOverlap;  // Specifies the maximum amount of overlap, expressed
+                           // as a percentage, allowed between the bounding
+                           // rectangles of two unique matches.
+  int coarseResult;  // Specifies whether you want the function to spend less
+                     // time accurately estimating the location of a match.
+  int enableCalibrationSupport;  // Set this element to TRUE to specify the
+                                 // algorithm treat the inspection image as a
+                                 // calibrated image.
+  ContrastMode enableContrastReversal;  // Use this element to specify the
+                                        // contrast of the matches to search for
+                                        // in the image.
+  GeometricMatchingSearchStrategy
+      matchStrategy;  // Specifies the aggressiveness of the search strategy.
+  unsigned int refineMatchFactor;  // Specifies the factor that is applied to
+                                   // the number of matches requested by the
+                                   // user to determine the number of matches
+                                   // that are refined at the initial matching
+                                   // stage.
+  unsigned int subpixelMatchFactor;  // Specifies the factor that is applied to
+                                     // the number of matches requested by the
+                                     // user to determine the number of matches
+                                     // that are evaluated at the final subpixel
+                                     // matching stage.
+} MatchGeometricPatternAdvancedOptions3;
+
+typedef struct ColorOptions_struct {
+  ColorClassificationResolution colorClassificationResolution;  // Specifies the
+                                                                // color
+                                                                // resolution of
+                                                                // the
+                                                                // classifier.
+  unsigned int useLuminance;  // Specifies if the luminance band is going to be
+                              // used in the feature vector.
+  ColorMode colorMode;  // Specifies the color mode of the classifier.
+} ColorOptions;
+
+typedef struct SampleScore_struct {
+  char* className;  // The name of the class.
+  float distance;  // The distance from the item to this class.
+  unsigned int index;  // index of this sample.
+} SampleScore;
+
+typedef struct ClassifierReportAdvanced_struct {
+  char* bestClassName;  // The name of the best class for the sample.
+  float classificationScore;  // The similarity of the sample and the two
+                              // closest classes in the classifier.
+  float identificationScore;  // The similarity of the sample and the assigned
+                              // class.
+  ClassScore* allScores;  // All classes and their scores.
+  int allScoresSize;  // The number of entries in allScores.
+  SampleScore* sampleScores;  // All samples and their scores.
+  int sampleScoresSize;  // The number of entries in sampleScores.
+} ClassifierReportAdvanced;
+
+typedef struct LearnGeometricPatternAdvancedOptions2_struct {
+  double minScaleFactor;  // Specifies the minimum scale factor that the
+                          // template is learned for.
+  double maxScaleFactor;  // Specifies the maximum scale factor the template is
+                          // learned for.
+  double minRotationAngleValue;  // Specifies the minimum rotation angle the
+                                 // template is learned for.
+  double maxRotationAngleValue;  // Specifies the maximum rotation angle the
+                                 // template is learned for.
+  unsigned int imageSamplingFactor;  // Specifies the factor that is used to
+                                     // subsample the template and the image for
+                                     // the initial matching phase.
+} LearnGeometricPatternAdvancedOptions2;
+
+typedef struct ParticleFilterOptions2_struct {
+  int rejectMatches;  // Set this parameter to TRUE to transfer only those
+                      // particles that do not meet all the criteria.
+  int rejectBorder;  // Set this element to TRUE to reject border particles.
+  int fillHoles;  // Set this element to TRUE to fill holes in particles.
+  int connectivity8;  // Set this parameter to TRUE to use connectivity-8 to
+                      // determine whether particles are touching.
+} ParticleFilterOptions2;
+
+typedef struct FindEdgeOptions2_struct {
+  RakeDirection direction;  // The direction to search in the ROI.
+  int showSearchArea;  // If TRUE, the function overlays the search area on the
+                       // image.
+  int showSearchLines;  // If TRUE, the function overlays the search lines used
+                        // to locate the edges on the image.
+  int showEdgesFound;  // If TRUE, the function overlays the locations of the
+                       // edges found on the image.
+  int showResult;  // If TRUE, the function overlays the hit lines to the object
+                   // and the edge used to generate the hit line on the result
+                   // image.
+  RGBValue searchAreaColor;  // Specifies the RGB color value to use to overlay
+                             // the search area.
+  RGBValue searchLinesColor;  // Specifies the RGB color value to use to overlay
+                              // the search lines.
+  RGBValue searchEdgesColor;  // Specifies the RGB color value to use to overlay
+                              // the search edges.
+  RGBValue resultColor;  // Specifies the RGB color value to use to overlay the
+                         // results.
+  char* overlayGroupName;  // Specifies the overlay group name to assign to the
+                           // overlays.
+  EdgeOptions2 edgeOptions;  // Specifies the edge detection options along a
+                             // single search line.
+} FindEdgeOptions2;
+
+typedef struct FindEdgeReport_struct {
+  StraightEdge* straightEdges;  // An array of straight edges detected.
+  unsigned int
+      numStraightEdges;  // Indicates the number of straight edges found.
+} FindEdgeReport;
+
+typedef struct FindTransformRectOptions2_struct {
+  FindReferenceDirection direction;  // Specifies the direction and orientation
+                                     // in which the function searches for the
+                                     // primary axis.
+  int showSearchArea;  // If TRUE, the function overlays the search area on the
+                       // image.
+  int showSearchLines;  // If TRUE, the function overlays the search lines used
+                        // to locate the edges on the image.
+  int showEdgesFound;  // If TRUE, the function overlays the locations of the
+                       // edges found on the image.
+  int showResult;  // If TRUE, the function overlays the hit lines to the object
+                   // and the edge used to generate the hit line on the result
+                   // image.
+  RGBValue searchAreaColor;  // Specifies the RGB color value to use to overlay
+                             // the search area.
+  RGBValue searchLinesColor;  // Specifies the RGB color value to use to overlay
+                              // the search lines.
+  RGBValue searchEdgesColor;  // Specifies the RGB color value to use to overlay
+                              // the search edges.
+  RGBValue resultColor;  // Specifies the RGB color value to use to overlay the
+                         // results.
+  char* overlayGroupName;  // Specifies the overlay group name to assign to the
+                           // overlays.
+  EdgeOptions2 edgeOptions;  // Specifies the edge detection options along a
+                             // single search line.
+} FindTransformRectOptions2;
+
+typedef struct FindTransformRectsOptions2_struct {
+  FindReferenceDirection direction;  // Specifies the direction and orientation
+                                     // in which the function searches for the
+                                     // primary axis.
+  int showSearchArea;  // If TRUE, the function overlays the search area on the
+                       // image.
+  int showSearchLines;  // If TRUE, the function overlays the search lines used
+                        // to locate the edges on the image.
+  int showEdgesFound;  // If TRUE, the function overlays the locations of the
+                       // edges found on the image.
+  int showResult;  // If TRUE, the function overlays the hit lines to the object
+                   // and the edge used to generate the hit line on the result
+                   // image.
+  RGBValue searchAreaColor;  // Specifies the RGB color value to use to overlay
+                             // the search area.
+  RGBValue searchLinesColor;  // Specifies the RGB color value to use to overlay
+                              // the search lines.
+  RGBValue searchEdgesColor;  // Specifies the RGB color value to use to overlay
+                              // the search edges.
+  RGBValue resultColor;  // Specifies the RGB color value to use to overlay the
+                         // results.
+  char* overlayGroupName;  // Specifies the overlay group name to assign to the
+                           // overlays.
+  EdgeOptions2 primaryEdgeOptions;  // Specifies the parameters used to compute
+                                    // the edge gradient information and detect
+                                    // the edges for the primary ROI.
+  EdgeOptions2 secondaryEdgeOptions;  // Specifies the parameters used to
+                                      // compute the edge gradient information
+                                      // and detect the edges for the secondary
+                                      // ROI.
+} FindTransformRectsOptions2;
+
+typedef struct ReadTextReport3_struct {
+  const char* readString;  // The read string.
+  CharReport3* characterReport;  // An array of reports describing the
+                                 // properties of each identified character.
+  int numCharacterReports;  // The number of identified characters.
+  ROI* roiBoundingCharacters;  // An array specifying the coordinates of the
+                               // character bounding ROI.
+} ReadTextReport3;
+
+typedef struct CharacterStatistics_struct {
+  int left;  // The left offset of the character bounding rectangles in the
+             // current ROI.
+  int top;  // The top offset of the character bounding rectangles in the
+            // current ROI.
+  int width;  // The width of each of the characters you trained in the current
+              // ROI.
+  int height;  // The height of each trained character in the current ROI.
+  int characterSize;  // The size of the character in pixels.
+} CharacterStatistics;
+
+typedef struct CharReport3_struct {
+  const char* character;  // The character value.
+  int classificationScore;  // The degree to which the assigned character class
+                            // represents the object better than the other
+                            // character classes in the character set.
+  int verificationScore;  // The similarity of the character and the reference
+                          // character for the character class.
+  int verified;  // This element is TRUE if a reference character was found for
+                 // the character class and FALSE if a reference character was
+                 // not found.
+  int lowThreshold;  // The minimum value of the threshold range used for this
+                     // character.
+  int highThreshold;  // The maximum value of the threshold range used for this
+                      // character.
+  CharacterStatistics
+      characterStats;  // Describes the characters segmented in the ROI.
+} CharReport3;
+
+typedef struct ArcInfo2_struct {
+  PointFloat center;  // The center point of the arc.
+  double radius;  // The radius of the arc.
+  double startAngle;  // The starting angle of the arc, specified
+                      // counter-clockwise from the x-axis.
+  double endAngle;  // The ending angle of the arc, specified counter-clockwise
+                    // from the x-axis.
+} ArcInfo2;
+
+typedef struct EdgeReport2_struct {
+  EdgeInfo* edges;  // An array of edges detected.
+  unsigned int numEdges;  // Indicates the number of edges detected.
+  double* gradientInfo;  // An array that contains the calculated edge strengths
+                         // along the user-defined search area.
+  unsigned int numGradientInfo;  // Indicates the number of elements contained
+                                 // in gradientInfo.
+  int calibrationValid;  // Indicates if the calibration data corresponding to
+                         // the location of the edges is correct.
+} EdgeReport2;
+
+typedef struct SearchArcInfo_struct {
+  ArcInfo2 arcCoordinates;  // Describes the arc used for edge detection.
+  EdgeReport2 edgeReport;  // Describes the edges found in this search line.
+} SearchArcInfo;
+
+typedef struct ConcentricRakeReport2_struct {
+  EdgeInfo* firstEdges;  // The first edge point detected along each search line
+                         // in the ROI.
+  unsigned int numFirstEdges;  // The number of points in the firstEdges array.
+  EdgeInfo* lastEdges;  // The last edge point detected along each search line
+                        // in the ROI.
+  unsigned int numLastEdges;  // The number of points in the lastEdges array.
+  SearchArcInfo* searchArcs;  // Contains the arcs used for edge detection and
+                              // the edge information for each arc.
+  unsigned int numSearchArcs;  // The number of arcs in the searchArcs array.
+} ConcentricRakeReport2;
+
+typedef struct SpokeReport2_struct {
+  EdgeInfo* firstEdges;  // The first edge point detected along each search line
+                         // in the ROI.
+  unsigned int numFirstEdges;  // The number of points in the firstEdges array.
+  EdgeInfo* lastEdges;  // The last edge point detected along each search line
+                        // in the ROI.
+  unsigned int numLastEdges;  // The number of points in the lastEdges array.
+  SearchLineInfo* searchLines;  // The search lines used for edge detection.
+  unsigned int
+      numSearchLines;  // The number of search lines used in the edge detection.
+} SpokeReport2;
+
+typedef struct EdgeInfo_struct {
+  PointFloat position;  // The location of the edge in the image.
+  PointFloat calibratedPosition;  // The position of the edge in the image in
+                                  // real-world coordinates.
+  double distance;  // The location of the edge from the first point along the
+                    // boundary of the input ROI.
+  double calibratedDistance;  // The location of the edge from the first point
+                              // along the boundary of the input ROI in
+                              // real-world coordinates.
+  double magnitude;  // The intensity contrast at the edge.
+  double
+      noisePeak;  // The strength of the noise associated with the current edge.
+  int rising;  // Indicates the polarity of the edge.
+} EdgeInfo;
+
+typedef struct SearchLineInfo_struct {
+  LineFloat lineCoordinates;  // The endpoints of the search line.
+  EdgeReport2 edgeReport;  // Describes the edges found in this search line.
+} SearchLineInfo;
+
+typedef struct RakeReport2_struct {
+  EdgeInfo* firstEdges;  // The first edge point detected along each search line
+                         // in the ROI.
+  unsigned int numFirstEdges;  // The number of points in the firstEdges array.
+  EdgeInfo* lastEdges;  // The last edge point detected along each search line
+                        // in the ROI.
+  unsigned int numLastEdges;  // The number of points in the lastEdges array.
+  SearchLineInfo* searchLines;  // The search lines used for edge detection.
+  unsigned int
+      numSearchLines;  // The number of search lines used in the edge detection.
+} RakeReport2;
+
+typedef struct TransformBehaviors_struct {
+  GroupBehavior ShiftBehavior;  // Specifies the behavior of an overlay group
+                                // when a shift operation is applied to an
+                                // image.
+  GroupBehavior ScaleBehavior;  // Specifies the behavior of an overlay group
+                                // when a scale operation is applied to an
+                                // image.
+  GroupBehavior RotateBehavior;  // Specifies the behavior of an overlay group
+                                 // when a rotate operation is applied to an
+                                 // image.
+  GroupBehavior SymmetryBehavior;  // Specifies the behavior of an overlay group
+                                   // when a symmetry operation is applied to an
+                                   // image.
+} TransformBehaviors;
+
+typedef struct QRCodeDataToken_struct {
+  QRStreamMode mode;  // Specifies the stream mode or the format of the data
+                      // that is encoded in the QR code.
+  unsigned int modeData;  // Indicates specifiers used by the user to
+                          // postprocess the data if it requires it.
+  unsigned char* data;  // Shows the encoded data in the QR code.
+  unsigned int
+      dataLength;  // Specifies the length of the data found in the QR code.
+} QRCodeDataToken;
+
+typedef struct ParticleFilterOptions_struct {
+  int rejectMatches;  // Set this parameter to TRUE to transfer only those
+                      // particles that do not meet all the criteria.
+  int rejectBorder;  // Set this element to TRUE to reject border particles.
+  int connectivity8;  // Set this parameter to TRUE to use connectivity-8 to
+                      // determine whether particles are touching.
+} ParticleFilterOptions;
+
+typedef struct StraightEdgeReport2_struct {
+  StraightEdge* straightEdges;  // Contains an array of found straight edges.
+  unsigned int
+      numStraightEdges;  // Indicates the number of straight edges found.
+  SearchLineInfo* searchLines;  // Contains an array of all search lines used in
+                                // the detection.
+  unsigned int
+      numSearchLines;  // The number of search lines used in the edge detection.
+} StraightEdgeReport2;
+
+typedef struct StraightEdgeOptions_struct {
+  unsigned int numLines;  // Specifies the number of straight edges to find.
+  StraightEdgeSearchMode
+      searchMode;  // Specifies the method used to find the straight edge.
+  double minScore;  // Specifies the minimum score of a detected straight edge.
+  double maxScore;  // Specifies the maximum score of a detected edge.
+  double orientation;  // Specifies the angle at which the straight edge is
+                       // expected to be found.
+  double angleRange;  // Specifies the +/- range around the orientation within
+                      // which the straight edge is expected to be found.
+  double angleTolerance;  // Specifies the expected angular accuracy of the
+                          // straight edge.
+  unsigned int stepSize;  // Specifies the gap in pixels between the search
+                          // lines used with the rake-based methods.
+  double minSignalToNoiseRatio;  // Specifies the minimum signal to noise ratio
+                                 // (SNR) of the edge points used to fit the
+                                 // straight edge.
+  double minCoverage;  // Specifies the minimum number of points as a percentage
+                       // of the number of search lines that need to be included
+                       // in the detected straight edge.
+  unsigned int houghIterations;  // Specifies the number of iterations used in
+                                 // the Hough-based method.
+} StraightEdgeOptions;
+
+typedef struct StraightEdge_struct {
+  LineFloat straightEdgeCoordinates;  // End points of the detected straight
+                                      // edge in pixel coordinates.
+  LineFloat calibratedStraightEdgeCoordinates;  // End points of the detected
+                                                // straight edge in real-world
+                                                // coordinates.
+  double angle;  // Angle of the found edge using the pixel coordinates.
+  double calibratedAngle;  // Angle of the found edge using the real-world
+                           // coordinates.
+  double score;  // Describes the score of the detected edge.
+  double straightness;  // The straightness value of the detected straight edge.
+  double averageSignalToNoiseRatio;  // Describes the average signal to noise
+                                     // ratio (SNR) of the detected edge.
+  int calibrationValid;  // Indicates if the calibration data for the straight
+                         // edge is valid.
+  EdgeInfo* usedEdges;  // An array of edges that were used to determine this
+                        // straight line.
+  unsigned int
+      numUsedEdges;  // Indicates the number of edges in the usedEdges array.
+} StraightEdge;
+
+typedef struct QRCodeSearchOptions_struct {
+  QRRotationMode rotationMode;  // Specifies the amount of QR code rotation the
+                                // function should allow for.
+  unsigned int skipLocation;  // If set to TRUE, specifies that the function
+                              // should assume that the QR code occupies the
+                              // entire image (or the entire search region).
+  unsigned int edgeThreshold;  // The strength of the weakest edge the function
+                               // uses to find the coarse location of the QR
+                               // code in the image.
+  QRDemodulationMode demodulationMode;  // The demodulation mode the function
+                                        // uses to locate the QR code.
+  QRCellSampleSize cellSampleSize;  // The cell sample size the function uses to
+                                    // locate the QR code.
+  QRCellFilterMode cellFilterMode;  // The cell filter mode the function uses to
+                                    // locate the QR code.
+  unsigned int skewDegreesAllowed;  // Specifies the amount of skew in the QR
+                                    // code the function should allow for.
+} QRCodeSearchOptions;
+
+typedef struct QRCodeSizeOptions_struct {
+  unsigned int minSize;  // Specifies the minimum size (in pixels) of the QR
+                         // code in the image.
+  unsigned int maxSize;  // Specifies the maximum size (in pixels) of the QR
+                         // code in the image.
+} QRCodeSizeOptions;
+
+typedef struct QRCodeDescriptionOptions_struct {
+  QRDimensions dimensions;  // The number of rows and columns that are populated
+                            // for the QR code, measured in cells.
+  QRPolarities polarity;  // The polarity of the QR code.
+  QRMirrorMode mirror;  // This element is TRUE if the QR code appears mirrored
+                        // in the image and FALSE if the QR code appears
+                        // normally in the image.
+  QRModelType
+      modelType;  // This option allows you to specify the type of QR code.
+} QRCodeDescriptionOptions;
+
+typedef struct QRCodeReport_struct {
+  unsigned int found;  // This element is TRUE if the function located and
+                       // decoded a QR code and FALSE if the function failed to
+                       // locate and decode a QR code.
+  unsigned char* data;  // The data encoded in the QR code.
+  unsigned int dataLength;  // The length of the data array.
+  PointFloat boundingBox[4];  // An array of four points describing the
+                              // rectangle surrounding the QR code.
+  QRCodeDataToken* tokenizedData;  // Contains the data tokenized in exactly the
+                                   // way it was encoded in the code.
+  unsigned int sizeOfTokenizedData;  // Size of the tokenized data.
+  unsigned int numErrorsCorrected;  // The number of errors the function
+                                    // corrected when decoding the QR code.
+  unsigned int dimensions;  // The number of rows and columns that are populated
+                            // for the QR code, measured in cells.
+  unsigned int version;  // The version of the QR code.
+  QRModelType modelType;  // This option allows you to specify what type of QR
+                          // code this is.
+  QRStreamMode streamMode;  // The format of the data encoded in the stream.
+  QRPolarities matrixPolarity;  // The polarity of the QR code.
+  unsigned int mirrored;  // This element is TRUE if the QR code appears
+                          // mirrored in the image and FALSE if the QR code
+                          // appears normally in the image.
+  unsigned int positionInAppendStream;  // Indicates what position the QR code
+                                        // is in with respect to the stream of
+                                        // data in all codes.
+  unsigned int sizeOfAppendStream;  // Specifies how many QR codes are part of a
+                                    // larger array of codes.
+  int firstEAN128ApplicationID;  // The first EAN-128 Application ID encountered
+                                 // in the stream.
+  int firstECIDesignator;  // The first Regional Language Designator encountered
+                           // in the stream.
+  unsigned int appendStreamIdentifier;  // Specifies what stream the QR code is
+                                        // in relation to when the code is part
+                                        // of a larger array of codes.
+  unsigned int minimumEdgeStrength;  // The strength of the weakest edge the
+                                     // function used to find the coarse
+                                     // location of the QR code in the image.
+  QRDemodulationMode demodulationMode;  // The demodulation mode the function
+                                        // used to locate the QR code.
+  QRCellSampleSize cellSampleSize;  // The cell sample size the function used to
+                                    // locate the QR code.
+  QRCellFilterMode cellFilterMode;  // The cell filter mode the function used to
+                                    // locate the QR code.
+} QRCodeReport;
+
+typedef struct AIMGradeReport_struct {
+  AIMGrade overallGrade;  // The overall letter grade, which is equal to the
+                          // lowest of the other five letter grades.
+  AIMGrade decodingGrade;  // The letter grade assigned to a Data Matrix barcode
+                           // based on the success of the function in decoding
+                           // the Data Matrix barcode.
+  AIMGrade symbolContrastGrade;  // The letter grade assigned to a Data Matrix
+                                 // barcode based on the symbol contrast raw
+                                 // score.
+  float symbolContrast;  // The symbol contrast raw score representing the
+                         // percentage difference between the mean of the
+                         // reflectance of the darkest 10 percent and lightest
+                         // 10 percent of the Data Matrix barcode.
+  AIMGrade printGrowthGrade;  // The print growth letter grade for the Data
+                              // Matrix barcode.
+  float printGrowth;  // The print growth raw score for the barcode, which is
+                      // based on the extent to which dark or light markings
+                      // appropriately fill their module boundaries.
+  AIMGrade axialNonuniformityGrade;  // The axial nonuniformity grade for the
+                                     // Data Matrix barcode.
+  float axialNonuniformity;  // The axial nonuniformity raw score for the
+                             // barcode, which is based on how much the sampling
+                             // point spacing differs from one axis to another.
+  AIMGrade unusedErrorCorrectionGrade;  // The unused error correction letter
+                                        // grade for the Data Matrix barcode.
+  float unusedErrorCorrection;  // The unused error correction raw score for the
+                                // Data Matrix barcode, which is based on the
+                                // extent to which regional or spot damage in
+                                // the Data Matrix barcode has eroded the
+                                // reading safety margin provided by the error
+                                // correction.
+} AIMGradeReport;
+
+typedef struct DataMatrixSizeOptions_struct {
+  unsigned int minSize;  // Specifies the minimum size (in pixels) of the Data
+                         // Matrix barcode in the image.
+  unsigned int maxSize;  // Specifies the maximum size (in pixels) of the Data
+                         // Matrix barcode in the image.
+  unsigned int quietZoneWidth;  // Specifies the expected minimum size of the
+                                // quiet zone, in pixels.
+} DataMatrixSizeOptions;
+
+typedef struct DataMatrixDescriptionOptions_struct {
+  float aspectRatio;  // Specifies the ratio of the width of each Data Matrix
+                      // barcode cell (in pixels) to the height of the Data
+                      // Matrix barcode (in pixels).
+  unsigned int rows;  // Specifies the number of rows in the Data Matrix
+                      // barcode.
+  unsigned int
+      columns;  // Specifies the number of columns in the Data Matrix barcode.
+  int rectangle;  // Set this element to TRUE to specify that the Data Matrix
+                  // barcode is rectangular.
+  DataMatrixECC ecc;  // Specifies the ECC used for this Data Matrix barcode.
+  DataMatrixPolarity polarity;  // Specifies the data-to-background contrast for
+                                // the Data Matrix barcode.
+  DataMatrixCellFillMode cellFill;  // Specifies the fill percentage for a cell
+                                    // of the Data Matrix barcode that is in the
+                                    // "ON" state.
+  float minBorderIntegrity;  // Specifies the minimum percentage of the border
+                             // (locator pattern and timing pattern) the
+                             // function should expect in the Data Matrix
+                             // barcode.
+  DataMatrixMirrorMode mirrorMode;  // Specifies if the Data Matrix barcode
+                                    // appears normally in the image or if the
+                                    // barcode appears mirrored in the image.
+} DataMatrixDescriptionOptions;
+
+typedef struct DataMatrixSearchOptions_struct {
+  DataMatrixRotationMode rotationMode;  // Specifies the amount of Data Matrix
+                                        // barcode rotation the function should
+                                        // allow for.
+  int skipLocation;  // If set to TRUE, specifies that the function should
+                     // assume that the Data Matrix barcode occupies the entire
+                     // image (or the entire search region).
+  unsigned int edgeThreshold;  // Specifies the minimum contrast a pixel must
+                               // have in order to be considered part of a
+                               // matrix cell edge.
+  DataMatrixDemodulationMode demodulationMode;  // Specifies the mode the
+                                                // function should use to
+                                                // demodulate (determine which
+                                                // cells are on and which cells
+                                                // are off) the Data Matrix
+                                                // barcode.
+  DataMatrixCellSampleSize cellSampleSize;  // Specifies the sample size, in
+                                            // pixels, the function should take
+                                            // to determine if each cell is on
+                                            // or off.
+  DataMatrixCellFilterMode cellFilterMode;  // Specifies the mode the function
+                                            // uses to determine the pixel value
+                                            // for each cell.
+  unsigned int skewDegreesAllowed;  // Specifies the amount of skew in the Data
+                                    // Matrix barcode the function should allow
+                                    // for.
+  unsigned int maxIterations;  // Specifies the maximum number of iterations
+                               // before the function stops looking for the Data
+                               // Matrix barcode.
+  unsigned int initialSearchVectorWidth;  // Specifies the number of pixels the
+                                          // function should average together to
+                                          // determine the location of an edge.
+} DataMatrixSearchOptions;
+
+typedef struct DataMatrixReport_struct {
+  int found;  // This element is TRUE if the function located and decoded a Data
+              // Matrix barcode and FALSE if the function failed to locate and
+              // decode a Data Matrix barcode.
+  int binary;  // This element is TRUE if the Data Matrix barcode contains
+               // binary data and FALSE if the Data Matrix barcode contains text
+               // data.
+  unsigned char* data;  // The data encoded in the Data Matrix barcode.
+  unsigned int dataLength;  // The length of the data array.
+  PointFloat boundingBox[4];  // An array of four points describing the
+                              // rectangle surrounding the Data Matrix barcode.
+  unsigned int numErrorsCorrected;  // The number of errors the function
+                                    // corrected when decoding the Data Matrix
+                                    // barcode.
+  unsigned int numErasuresCorrected;  // The number of erasures the function
+                                      // corrected when decoding the Data Matrix
+                                      // barcode.
+  float aspectRatio;  // Specifies the aspect ratio of the Data Matrix barcode
+                      // in the image, which equals the ratio of the width of a
+                      // Data Matrix barcode cell (in pixels) to the height of a
+                      // Data Matrix barcode cell (in pixels).
+  unsigned int rows;  // The number of rows in the Data Matrix barcode.
+  unsigned int columns;  // The number of columns in the Data Matrix barcode.
+  DataMatrixECC
+      ecc;  // The Error Correction Code (ECC) used by the Data Matrix barcode.
+  DataMatrixPolarity polarity;  // The polarity of the Data Matrix barcode.
+  DataMatrixCellFillMode
+      cellFill;  // The cell fill percentage of the Data Matrix barcode.
+  float borderIntegrity;  // The percentage of the Data Matrix barcode border
+                          // that appears correctly in the image.
+  int mirrored;  // This element is TRUE if the Data Matrix barcode appears
+                 // mirrored in the image and FALSE if the Data Matrix barcode
+                 // appears normally in the image.
+  unsigned int minimumEdgeStrength;  // The strength of the weakest edge the
+                                     // function used to find the coarse
+                                     // location of the Data Matrix barcode in
+                                     // the image.
+  DataMatrixDemodulationMode demodulationMode;  // The demodulation mode the
+                                                // function used to locate the
+                                                // Data Matrix barcode.
+  DataMatrixCellSampleSize cellSampleSize;  // The cell sample size the function
+                                            // used to locate the Data Matrix
+                                            // barcode.
+  DataMatrixCellFilterMode cellFilterMode;  // The cell filter mode the function
+                                            // used to locate the Data Matrix
+                                            // barcode.
+  unsigned int iterations;  // The number of iterations the function took in
+                            // attempting to locate the Data Matrix barcode.
+} DataMatrixReport;
+
+typedef struct JPEG2000FileAdvancedOptions_struct {
+  WaveletTransformMode waveletMode;  // Determines which wavelet transform to
+                                     // use when writing the file.
+  int useMultiComponentTransform;  // Set this parameter to TRUE to use an
+                                   // additional transform on RGB images.
+  unsigned int maxWaveletTransformLevel;  // Specifies the maximum allowed level
+                                          // of wavelet transform.
+  float quantizationStepSize;  // Specifies the absolute base quantization step
+                               // size for derived quantization mode.
+} JPEG2000FileAdvancedOptions;
+
+typedef struct MatchGeometricPatternAdvancedOptions2_struct {
+  int minFeaturesUsed;  // Specifies the minimum number of features the function
+                        // uses when matching.
+  int maxFeaturesUsed;  // Specifies the maximum number of features the function
+                        // uses when matching.
+  int subpixelIterations;  // Specifies the maximum number of incremental
+                           // improvements used to refine matches with subpixel
+                           // information.
+  double subpixelTolerance;  // Specifies the maximum amount of change, in
+                             // pixels, between consecutive incremental
+                             // improvements in the match position before the
+                             // function stops refining the match position.
+  int initialMatchListLength;  // Specifies the maximum size of the match list.
+  float matchTemplateCurveScore;  // Set this element to TRUE to specify that
+                                  // the function should calculate the match
+                                  // curve to template curve score and return it
+                                  // for each match result.
+  int correlationScore;  // Set this element to TRUE to specify that the
+                         // function should calculate the correlation score and
+                         // return it for each match result.
+  double minMatchSeparationDistance;  // Specifies the minimum separation
+                                      // distance, in pixels, between the
+                                      // origins of two matches that have unique
+                                      // positions.
+  double minMatchSeparationAngle;  // Specifies the minimum angular difference,
+                                   // in degrees, between two matches that have
+                                   // unique angles.
+  double minMatchSeparationScale;  // Specifies the minimum difference in scale,
+                                   // expressed as a percentage, between two
+                                   // matches that have unique scales.
+  double maxMatchOverlap;  // Specifies the maximum amount of overlap, expressed
+                           // as a percentage, allowed between the bounding
+                           // rectangles of two unique matches.
+  int coarseResult;  // Specifies whether you want the function to spend less
+                     // time accurately estimating the location of a match.
+  int smoothContours;  // Set this element to TRUE to specify smoothing be done
+                       // on the contours of the inspection image before feature
+                       // extraction.
+  int enableCalibrationSupport;  // Set this element to TRUE to specify the
+                                 // algorithm treat the inspection image as a
+                                 // calibrated image.
+} MatchGeometricPatternAdvancedOptions2;
+
+typedef struct InspectionAlignment_struct {
+  PointFloat position;  // The location of the center of the golden template in
+                        // the image under inspection.
+  float rotation;  // The rotation of the golden template in the image under
+                   // inspection, in degrees.
+  float scale;  // The percentage of the size of the area under inspection
+                // compared to the size of the golden template.
+} InspectionAlignment;
+
+typedef struct InspectionOptions_struct {
+  RegistrationMethod registrationMethod;  // Specifies how the function
+                                          // registers the golden template and
+                                          // the target image.
+  NormalizationMethod normalizationMethod;  // Specifies how the function
+                                            // normalizes the golden template to
+                                            // the target image.
+  int edgeThicknessToIgnore;  // Specifies desired thickness of edges to be
+                              // ignored.
+  float brightThreshold;  // Specifies the threshold for areas where the target
+                          // image is brighter than the golden template.
+  float darkThreshold;  // Specifies the threshold for areas where the target
+                        // image is darker than the golden template.
+  int binary;  // Specifies whether the function should return a binary image
+               // giving the location of defects, or a grayscale image giving
+               // the intensity of defects.
+} InspectionOptions;
+
+typedef struct CharReport2_struct {
+  const char* character;  // The character value.
+  PointFloat corner[4];  // An array of four points that describes the rectangle
+                         // that surrounds the character.
+  int lowThreshold;  // The minimum value of the threshold range used for this
+                     // character.
+  int highThreshold;  // The maximum value of the threshold range used for this
+                      // character.
+  int classificationScore;  // The degree to which the assigned character class
+                            // represents the object better than the other
+                            // character classes in the character set.
+  int verificationScore;  // The similarity of the character and the reference
+                          // character for the character class.
+  int verified;  // This element is TRUE if a reference character was found for
+                 // the character class and FALSE if a reference character was
+                 // not found.
+} CharReport2;
+
+typedef struct CharInfo2_struct {
+  const char* charValue;  // Retrieves the character value of the corresponding
+                          // character in the character set.
+  const Image* charImage;  // The image you used to train this character.
+  const Image* internalImage;  // The internal representation that NI Vision
+                               // uses to match objects to this character.
+  int isReferenceChar;  // This element is TRUE if the character is the
+                        // reference character for the character class.
+} CharInfo2;
+
+typedef struct ReadTextReport2_struct {
+  const char* readString;  // The read string.
+  CharReport2* characterReport;  // An array of reports describing the
+                                 // properties of each identified character.
+  int numCharacterReports;  // The number of identified characters.
+} ReadTextReport2;
+
+typedef struct EllipseFeature_struct {
+  PointFloat position;  // The location of the center of the ellipse.
+  double rotation;  // The orientation of the semi-major axis of the ellipse
+                    // with respect to the horizontal.
+  double minorRadius;  // The length of the semi-minor axis of the ellipse.
+  double majorRadius;  // The length of the semi-major axis of the ellipse.
+} EllipseFeature;
+
+typedef struct CircleFeature_struct {
+  PointFloat position;  // The location of the center of the circle.
+  double radius;  // The radius of the circle.
+} CircleFeature;
+
+typedef struct ConstCurveFeature_struct {
+  PointFloat
+      position;  // The center of the circle that this constant curve lies upon.
+  double radius;  // The radius of the circle that this constant curve lies
+                  // upon.
+  double startAngle;  // When traveling along the constant curve from one
+                      // endpoint to the next in a counterclockwise manner, this
+                      // is the angular component of the vector originating at
+                      // the center of the constant curve and pointing towards
+                      // the first endpoint of the constant curve.
+  double endAngle;  // When traveling along the constant curve from one endpoint
+                    // to the next in a counterclockwise manner, this is the
+                    // angular component of the vector originating at the center
+                    // of the constant curve and pointing towards the second
+                    // endpoint of the constant curve.
+} ConstCurveFeature;
+
+typedef struct RectangleFeature_struct {
+  PointFloat position;  // The center of the rectangle.
+  PointFloat corner[4];  // The four corners of the rectangle.
+  double rotation;  // The orientation of the rectangle with respect to the
+                    // horizontal.
+  double width;  // The width of the rectangle.
+  double height;  // The height of the rectangle.
+} RectangleFeature;
+
+typedef struct LegFeature_struct {
+  PointFloat position;  // The location of the leg feature.
+  PointFloat corner[4];  // The four corners of the leg feature.
+  double rotation;  // The orientation of the leg with respect to the
+                    // horizontal.
+  double width;  // The width of the leg.
+  double height;  // The height of the leg.
+} LegFeature;
+
+typedef struct CornerFeature_struct {
+  PointFloat position;  // The location of the corner feature.
+  double rotation;  // The angular component of the vector bisecting the corner
+                    // from position.
+  double enclosedAngle;  // The measure of the enclosed angle of the corner.
+  int isVirtual;
+} CornerFeature;
+
+typedef struct LineFeature_struct {
+  PointFloat startPoint;  // The starting point of the line.
+  PointFloat endPoint;  // The ending point of the line.
+  double length;  // The length of the line measured in pixels from the start
+                  // point to the end point.
+  double
+      rotation;  // The orientation of the line with respect to the horizontal.
+} LineFeature;
+
+typedef struct ParallelLinePairFeature_struct {
+  PointFloat
+      firstStartPoint;  // The starting point of the first line of the pair.
+  PointFloat firstEndPoint;  // The ending point of the first line of the pair.
+  PointFloat
+      secondStartPoint;  // The starting point of the second line of the pair.
+  PointFloat secondEndPoint;  // The ending point of the second line of the
+                              // pair.
+  double rotation;  // The orientation of the feature with respect to the
+                    // horizontal.
+  double distance;  // The distance from the first line to the second line.
+} ParallelLinePairFeature;
+
+typedef struct PairOfParallelLinePairsFeature_struct {
+  ParallelLinePairFeature
+      firstParallelLinePair;  // The first parallel line pair.
+  ParallelLinePairFeature
+      secondParallelLinePair;  // The second parallel line pair.
+  double rotation;  // The orientation of the feature with respect to the
+                    // horizontal.
+  double distance;  // The distance from the midline of the first parallel line
+                    // pair to the midline of the second parallel line pair.
+} PairOfParallelLinePairsFeature;
+
+typedef union GeometricFeature_union {
+  CircleFeature* circle;  // A pointer to a CircleFeature.
+  EllipseFeature* ellipse;  // A pointer to an EllipseFeature.
+  ConstCurveFeature* constCurve;  // A pointer to a ConstCurveFeature.
+  RectangleFeature* rectangle;  // A pointer to a RectangleFeature.
+  LegFeature* leg;  // A pointer to a LegFeature.
+  CornerFeature* corner;  // A pointer to a CornerFeature.
+  ParallelLinePairFeature*
+      parallelLinePair;  // A pointer to a ParallelLinePairFeature.
+  PairOfParallelLinePairsFeature*
+      pairOfParallelLinePairs;  // A pointer to a
+                                // PairOfParallelLinePairsFeature.
+  LineFeature* line;  // A pointer to a LineFeature.
+  ClosedCurveFeature* closedCurve;  // A pointer to a ClosedCurveFeature.
+} GeometricFeature;
+
+typedef struct FeatureData_struct {
+  FeatureType type;  // An enumeration representing the type of the feature.
+  PointFloat*
+      contourPoints;  // A set of points describing the contour of the feature.
+  int numContourPoints;  // The number of points in the contourPoints array.
+  GeometricFeature
+      feature;  // The feature data specific to this type of feature.
+} FeatureData;
+
+typedef struct GeometricPatternMatch2_struct {
+  PointFloat
+      position;  // The location of the origin of the template in the match.
+  float rotation;  // The rotation of the match relative to the template image,
+                   // in degrees.
+  float scale;  // The size of the match relative to the size of the template
+                // image, expressed as a percentage.
+  float score;  // The accuracy of the match.
+  PointFloat corner[4];  // An array of four points describing the rectangle
+                         // surrounding the template image.
+  int inverse;  // This element is TRUE if the match is an inverse of the
+                // template image.
+  float occlusion;  // The percentage of the match that is occluded.
+  float templateMatchCurveScore;  // The accuracy of the match obtained by
+                                  // comparing the template curves to the curves
+                                  // in the match region.
+  float matchTemplateCurveScore;  // The accuracy of the match obtained by
+                                  // comparing the curves in the match region to
+                                  // the template curves.
+  float correlationScore;  // The accuracy of the match obtained by comparing
+                           // the template image to the match region using a
+                           // correlation metric that compares the two regions
+                           // as a function of their pixel values.
+  String255 label;  // The label corresponding to this match when the match is
+                    // returned by imaqMatchMultipleGeometricPatterns().
+  FeatureData* featureData;  // The features used in this match.
+  int numFeatureData;  // The size of the featureData array.
+  PointFloat calibratedPosition;  // The location of the origin of the template
+                                  // in the match.
+  float calibratedRotation;  // The rotation of the match relative to the
+                             // template image, in degrees.
+  PointFloat calibratedCorner[4];  // An array of four points describing the
+                                   // rectangle surrounding the template image.
+} GeometricPatternMatch2;
+
+typedef struct ClosedCurveFeature_struct {
+  PointFloat position;  // The center of the closed curve feature.
+  double arcLength;  // The arc length of the closed curve feature.
+} ClosedCurveFeature;
+
+typedef struct LineMatch_struct {
+  PointFloat startPoint;  // The starting point of the matched line.
+  PointFloat endPoint;  // The ending point of the matched line.
+  double length;  // The length of the line measured in pixels from the start
+                  // point to the end point.
+  double rotation;  // The orientation of the matched line.
+  double score;  // The score of the matched line.
+} LineMatch;
+
+typedef struct LineDescriptor_struct {
+  double minLength;  // Specifies the minimum length of a line the function will
+                     // return.
+  double maxLength;  // Specifies the maximum length of a line the function will
+                     // return.
+} LineDescriptor;
+
+typedef struct RectangleDescriptor_struct {
+  double minWidth;  // Specifies the minimum width of a rectangle the algorithm
+                    // will return.
+  double maxWidth;  // Specifies the maximum width of a rectangle the algorithm
+                    // will return.
+  double minHeight;  // Specifies the minimum height of a rectangle the
+                     // algorithm will return.
+  double maxHeight;  // Specifies the maximum height of a rectangle the
+                     // algorithm will return.
+} RectangleDescriptor;
+
+typedef struct RectangleMatch_struct {
+  PointFloat corner[4];  // The corners of the matched rectangle.
+  double rotation;  // The orientation of the matched rectangle.
+  double width;  // The width of the matched rectangle.
+  double height;  // The height of the matched rectangle.
+  double score;  // The score of the matched rectangle.
+} RectangleMatch;
+
+typedef struct EllipseDescriptor_struct {
+  double minMajorRadius;  // Specifies the minimum length of the semi-major axis
+                          // of an ellipse the function will return.
+  double maxMajorRadius;  // Specifies the maximum length of the semi-major axis
+                          // of an ellipse the function will return.
+  double minMinorRadius;  // Specifies the minimum length of the semi-minor axis
+                          // of an ellipse the function will return.
+  double maxMinorRadius;  // Specifies the maximum length of the semi-minor axis
+                          // of an ellipse the function will return.
+} EllipseDescriptor;
+
+typedef struct EllipseMatch_struct {
+  PointFloat position;  // The location of the center of the matched ellipse.
+  double rotation;  // The orientation of the matched ellipse.
+  double
+      majorRadius;  // The length of the semi-major axis of the matched ellipse.
+  double
+      minorRadius;  // The length of the semi-minor axis of the matched ellipse.
+  double score;  // The score of the matched ellipse.
+} EllipseMatch;
+
+typedef struct CircleMatch_struct {
+  PointFloat position;  // The location of the center of the matched circle.
+  double radius;  // The radius of the matched circle.
+  double score;  // The score of the matched circle.
+} CircleMatch;
+
+typedef struct CircleDescriptor_struct {
+  double minRadius;  // Specifies the minimum radius of a circle the function
+                     // will return.
+  double maxRadius;  // Specifies the maximum radius of a circle the function
+                     // will return.
+} CircleDescriptor;
+
+typedef struct ShapeDetectionOptions_struct {
+  unsigned int mode;  // Specifies the method used when looking for the shape in
+                      // the image.
+  RangeFloat* angleRanges;  // An array of angle ranges, in degrees, where each
+                            // range specifies how much you expect the shape to
+                            // be rotated in the image.
+  int numAngleRanges;  // The size of the orientationRanges array.
+  RangeFloat scaleRange;  // A range that specifies the sizes of the shapes you
+                          // expect to be in the image, expressed as a ratio
+                          // percentage representing the size of the pattern in
+                          // the image divided by size of the original pattern
+                          // multiplied by 100.
+  double minMatchScore;
+} ShapeDetectionOptions;
+
+typedef struct Curve_struct {
+  PointFloat* points;  // The points on the curve.
+  unsigned int numPoints;  // The number of points in the curve.
+  int closed;  // This element is TRUE if the curve is closed and FALSE if the
+               // curve is open.
+  double curveLength;  // The length of the curve.
+  double minEdgeStrength;  // The lowest edge strength detected on the curve.
+  double maxEdgeStrength;  // The highest edge strength detected on the curve.
+  double averageEdgeStrength;  // The average of all edge strengths detected on
+                               // the curve.
+} Curve;
+
+typedef struct CurveOptions_struct {
+  ExtractionMode extractionMode;  // Specifies the method the function uses to
+                                  // identify curves in the image.
+  int threshold;  // Specifies the minimum contrast a seed point must have in
+                  // order to begin a curve.
+  EdgeFilterSize filterSize;  // Specifies the width of the edge filter the
+                              // function uses to identify curves in the image.
+  int minLength;  // Specifies the length, in pixels, of the smallest curve the
+                  // function will extract.
+  int rowStepSize;  // Specifies the distance, in the y direction, between lines
+                    // the function inspects for curve seed points.
+  int columnStepSize;  // Specifies the distance, in the x direction, between
+                       // columns the function inspects for curve seed points.
+  int maxEndPointGap;  // Specifies the maximum gap, in pixels, between the
+                       // endpoints of a curve that the function identifies as a
+                       // closed curve.
+  int onlyClosed;  // Set this element to TRUE to specify that the function
+                   // should only identify closed curves in the image.
+  int subpixelAccuracy;  // Set this element to TRUE to specify that the
+                         // function identifies the location of curves with
+                         // subpixel accuracy by interpolating between points to
+                         // find the crossing of threshold.
+} CurveOptions;
+
+typedef struct Barcode2DInfo_struct {
+  Barcode2DType type;  // The type of the 2D barcode.
+  int binary;  // This element is TRUE if the 2D barcode contains binary data
+               // and FALSE if the 2D barcode contains text data.
+  unsigned char* data;  // The data encoded in the 2D barcode.
+  unsigned int dataLength;  // The length of the data array.
+  PointFloat boundingBox[4];  // An array of four points describing the
+                              // rectangle surrounding the 2D barcode.
+  unsigned int numErrorsCorrected;  // The number of errors the function
+                                    // corrected when decoding the 2D barcode.
+  unsigned int numErasuresCorrected;  // The number of erasures the function
+                                      // corrected when decoding the 2D barcode.
+  unsigned int rows;  // The number of rows in the 2D barcode.
+  unsigned int columns;  // The number of columns in the 2D barcode.
+} Barcode2DInfo;
+
+typedef struct DataMatrixOptions_struct {
+  Barcode2DSearchMode searchMode;  // Specifies the mode the function uses to
+                                   // search for barcodes.
+  Barcode2DContrast contrast;  // Specifies the contrast of the barcodes that
+                               // the function searches for.
+  Barcode2DCellShape cellShape;  // Specifies the shape of the barcode data
+                                 // cells, which affects how the function
+                                 // decodes the barcode.
+  Barcode2DShape barcodeShape;  // Specifies the shape of the barcodes that the
+                                // function searches for.
+  DataMatrixSubtype subtype;  // Specifies the Data Matrix subtypes of the
+                              // barcodes that the function searches for.
+} DataMatrixOptions;
+
+typedef struct ClassifierAccuracyReport_struct {
+  int size;  // The size of the arrays in this structure.
+  float accuracy;  // The overall accuracy of the classifier, from 0 to 1000.
+  char** classNames;  // The names of the classes of this classifier.
+  double* classAccuracy;  // An array of size elements that contains accuracy
+                          // information for each class.
+  double* classPredictiveValue;  // An array containing size elements that
+                                 // contains the predictive values of each
+                                 // class.
+  int** classificationDistribution;  // A two-dimensional array containing
+                                     // information about how the classifier
+                                     // classifies its samples.
+} ClassifierAccuracyReport;
+
+typedef struct NearestNeighborClassResult_struct {
+  char* className;  // The name of the class.
+  float standardDeviation;  // The standard deviation of the members of this
+                            // class.
+  int count;  // The number of samples in this class.
+} NearestNeighborClassResult;
+
+typedef struct NearestNeighborTrainingReport_struct {
+  float** classDistancesTable;  // The confidence in the training.
+  NearestNeighborClassResult* allScores;  // All classes and their scores.
+  int allScoresSize;  // The number of entries in allScores.
+} NearestNeighborTrainingReport;
+
+typedef struct ParticleClassifierPreprocessingOptions_struct {
+  int manualThreshold;  // Set this element to TRUE to specify the threshold
+                        // range manually.
+  RangeFloat manualThresholdRange;  // If a manual threshold is being done, the
+                                    // range of pixels to keep.
+  ThresholdMethod autoThresholdMethod;  // If an automatic threshold is being
+                                        // done, the method used to calculate
+                                        // the threshold range.
+  RangeFloat limits;  // The limits on the automatic threshold range.
+  ParticleType particleType;  // Specifies what kind of particles to look for.
+  int rejectBorder;  // Set this element to TRUE to reject border particles.
+  int numErosions;  // The number of erosions to perform.
+} ParticleClassifierPreprocessingOptions;
+
+typedef struct ClassifierSampleInfo_struct {
+  char* className;  // The name of the class this sample is in.
+  double* featureVector;  // The feature vector of this sample, or NULL if this
+                          // is not a custom classifier session.
+  int featureVectorSize;  // The number of elements in the feature vector.
+  Image* thumbnail;  // A thumbnail image of this sample, or NULL if no image
+                     // was specified.
+} ClassifierSampleInfo;
+
+typedef struct ClassScore_struct {
+  char* className;  // The name of the class.
+  float distance;  // The distance from the item to this class.
+} ClassScore;
+
+typedef struct ClassifierReport_struct {
+  char* bestClassName;  // The name of the best class for the sample.
+  float classificationScore;  // The similarity of the sample and the two
+                              // closest classes in the classifier.
+  float identificationScore;  // The similarity of the sample and the assigned
+                              // class.
+  ClassScore* allScores;  // All classes and their scores.
+  int allScoresSize;  // The number of entries in allScores.
+} ClassifierReport;
+
+typedef struct NearestNeighborOptions_struct {
+  NearestNeighborMethod method;  // The method to use.
+  NearestNeighborMetric metric;  // The metric to use.
+  int k;  // The value of k, if the IMAQ_K_NEAREST_NEIGHBOR method is used.
+} NearestNeighborOptions;
+
+typedef struct ParticleClassifierOptions_struct {
+  float scaleDependence;  // The relative importance of scale when classifying
+                          // particles.
+  float mirrorDependence;  // The relative importance of mirror symmetry when
+                           // classifying particles.
+} ParticleClassifierOptions;
+
+typedef struct RGBU64Value_struct {
+  unsigned short B;  // The blue value of the color.
+  unsigned short G;  // The green value of the color.
+  unsigned short R;  // The red value of the color.
+  unsigned short alpha;  // The alpha value of the color, which represents extra
+                         // information about a color image, such as gamma
+                         // correction.
+} RGBU64Value;
+
+typedef struct GeometricPatternMatch_struct {
+  PointFloat
+      position;  // The location of the origin of the template in the match.
+  float rotation;  // The rotation of the match relative to the template image,
+                   // in degrees.
+  float scale;  // The size of the match relative to the size of the template
+                // image, expressed as a percentage.
+  float score;  // The accuracy of the match.
+  PointFloat corner[4];  // An array of four points describing the rectangle
+                         // surrounding the template image.
+  int inverse;  // This element is TRUE if the match is an inverse of the
+                // template image.
+  float occlusion;  // The percentage of the match that is occluded.
+  float templateMatchCurveScore;  // The accuracy of the match obtained by
+                                  // comparing the template curves to the curves
+                                  // in the match region.
+  float matchTemplateCurveScore;  // The accuracy of the match obtained by
+                                  // comparing the curves in the match region to
+                                  // the template curves.
+  float correlationScore;  // The accuracy of the match obtained by comparing
+                           // the template image to the match region using a
+                           // correlation metric that compares the two regions
+                           // as a function of their pixel values.
+} GeometricPatternMatch;
+
+typedef struct MatchGeometricPatternAdvancedOptions_struct {
+  int minFeaturesUsed;  // Specifies the minimum number of features the function
+                        // uses when matching.
+  int maxFeaturesUsed;  // Specifies the maximum number of features the function
+                        // uses when matching.
+  int subpixelIterations;  // Specifies the maximum number of incremental
+                           // improvements used to refine matches with subpixel
+                           // information.
+  double subpixelTolerance;  // Specifies the maximum amount of change, in
+                             // pixels, between consecutive incremental
+                             // improvements in the match position before the
+                             // function stops refining the match position.
+  int initialMatchListLength;  // Specifies the maximum size of the match list.
+  int matchTemplateCurveScore;  // Set this element to TRUE to specify that the
+                                // function should calculate the match curve to
+                                // template curve score and return it for each
+                                // match result.
+  int correlationScore;  // Set this element to TRUE to specify that the
+                         // function should calculate the correlation score and
+                         // return it for each match result.
+  double minMatchSeparationDistance;  // Specifies the minimum separation
+                                      // distance, in pixels, between the
+                                      // origins of two matches that have unique
+                                      // positions.
+  double minMatchSeparationAngle;  // Specifies the minimum angular difference,
+                                   // in degrees, between two matches that have
+                                   // unique angles.
+  double minMatchSeparationScale;  // Specifies the minimum difference in scale,
+                                   // expressed as a percentage, between two
+                                   // matches that have unique scales.
+  double maxMatchOverlap;  // Specifies the maximum amount of overlap, expressed
+                           // as a percentage, allowed between the bounding
+                           // rectangles of two unique matches.
+  int coarseResult;  // Specifies whether you want the function to spend less
+                     // time accurately estimating the location of a match.
+} MatchGeometricPatternAdvancedOptions;
+
+typedef struct MatchGeometricPatternOptions_struct {
+  unsigned int mode;  // Specifies the method imaqMatchGeometricPattern() uses
+                      // when looking for the pattern in the image.
+  int subpixelAccuracy;  // Set this element to TRUE to specify that the
+                         // function should calculate match locations with
+                         // subpixel accuracy.
+  RangeFloat* angleRanges;  // An array of angle ranges, in degrees, where each
+                            // range specifies how much you expect the template
+                            // to be rotated in the image.
+  int numAngleRanges;  // Number of angle ranges in the angleRanges array.
+  RangeFloat scaleRange;  // A range that specifies the sizes of the pattern you
+                          // expect to be in the image, expressed as a ratio
+                          // percentage representing the size of the pattern in
+                          // the image divided by size of the original pattern
+                          // multiplied by 100.
+  RangeFloat occlusionRange;  // A range that specifies the percentage of the
+                              // pattern you expect to be occluded in the image.
+  int numMatchesRequested;  // Number of valid matches expected.
+  float minMatchScore;  // The minimum score a match can have for the function
+                        // to consider the match valid.
+} MatchGeometricPatternOptions;
+
+typedef struct LearnGeometricPatternAdvancedOptions_struct {
+  int minRectLength;  // Specifies the minimum length for each side of a
+                      // rectangular feature.
+  double minRectAspectRatio;  // Specifies the minimum aspect ratio of a
+                              // rectangular feature.
+  int minRadius;  // Specifies the minimum radius for a circular feature.
+  int minLineLength;  // Specifies the minimum length for a linear feature.
+  double minFeatureStrength;  // Specifies the minimum strength for a feature.
+  int maxFeaturesUsed;  // Specifies the maximum number of features the function
+                        // uses when learning.
+  int maxPixelDistanceFromLine;  // Specifies the maximum number of pixels
+                                 // between an edge pixel and a linear feature
+                                 // for the function to consider that edge pixel
+                                 // as part of the linear feature.
+} LearnGeometricPatternAdvancedOptions;
+
+typedef struct FitEllipseOptions_struct {
+  int rejectOutliers;  // Whether to use every given point or only a subset of
+                       // the points to fit the ellipse.
+  double minScore;  // Specifies the required quality of the fitted ellipse.
+  double pixelRadius;  // The acceptable distance, in pixels, that a point
+                       // determined to belong to the ellipse can be from the
+                       // circumference of the ellipse.
+  int maxIterations;  // Specifies the number of refinement iterations you allow
+                      // the function to perform on the initial subset of
+                      // points.
+} FitEllipseOptions;
+
+typedef struct FitCircleOptions_struct {
+  int rejectOutliers;  // Whether to use every given point or only a subset of
+                       // the points to fit the circle.
+  double minScore;  // Specifies the required quality of the fitted circle.
+  double pixelRadius;  // The acceptable distance, in pixels, that a point
+                       // determined to belong to the circle can be from the
+                       // circumference of the circle.
+  int maxIterations;  // Specifies the number of refinement iterations you allow
+                      // the function to perform on the initial subset of
+                      // points.
+} FitCircleOptions;
+
+typedef struct ConstructROIOptions2_struct {
+  int windowNumber;  // The window number of the image window.
+  const char* windowTitle;  // Specifies the message string that the function
+                            // displays in the title bar of the window.
+  PaletteType type;  // The palette type to use.
+  RGBValue* palette;  // If type is IMAQ_PALETTE_USER, this array is the palette
+                      // of colors to use with the window.
+  int numColors;  // If type is IMAQ_PALETTE_USER, this element is the number of
+                  // colors in the palette array.
+  unsigned int maxContours;  // The maximum number of contours the user will be
+                             // able to select.
+} ConstructROIOptions2;
+
+typedef struct HSLValue_struct {
+  unsigned char L;  // The color luminance.
+  unsigned char S;  // The color saturation.
+  unsigned char H;  // The color hue.
+  unsigned char alpha;  // The alpha value of the color, which represents extra
+                        // information about a color image, such as gamma
+                        // correction.
+} HSLValue;
+
+typedef struct HSVValue_struct {
+  unsigned char V;  // The color value.
+  unsigned char S;  // The color saturation.
+  unsigned char H;  // The color hue.
+  unsigned char alpha;  // The alpha value of the color, which represents extra
+                        // information about a color image, such as gamma
+                        // correction.
+} HSVValue;
+
+typedef struct HSIValue_struct {
+  unsigned char I;  // The color intensity.
+  unsigned char S;  // The color saturation.
+  unsigned char H;  // The color hue.
+  unsigned char alpha;  // The alpha value of the color, which represents extra
+                        // information about a color image, such as gamma
+                        // correction.
+} HSIValue;
+
+typedef struct CIELabValue_struct {
+  double b;  // The yellow/blue information of the color.
+  double a;  // The red/green information of the color.
+  double L;  // The color lightness.
+  unsigned char alpha;  // The alpha value of the color, which represents extra
+                        // information about a color image, such as gamma
+                        // correction.
+} CIELabValue;
+
+typedef struct CIEXYZValue_struct {
+  double Z;  // The Z color information.
+  double Y;  // The color luminance.
+  double X;  // The X color information.
+  unsigned char alpha;  // The alpha value of the color, which represents extra
+                        // information about a color image, such as gamma
+                        // correction.
+} CIEXYZValue;
+
+typedef union Color2_union {
+  RGBValue rgb;  // The information needed to describe a color in the RGB (Red,
+                 // Green, and Blue) color space.
+  HSLValue hsl;  // The information needed to describe a color in the HSL (Hue,
+                 // Saturation, and Luminance) color space.
+  HSVValue hsv;  // The information needed to describe a color in the HSI (Hue,
+                 // Saturation, and Value) color space.
+  HSIValue hsi;  // The information needed to describe a color in the HSI (Hue,
+                 // Saturation, and Intensity) color space.
+  CIELabValue cieLab;  // The information needed to describe a color in the CIE
+                       // L*a*b* (L, a, b) color space.
+  CIEXYZValue cieXYZ;  // The information needed to describe a color in the CIE
+                       // XYZ (X, Y, Z) color space.
+  int rawValue;  // The integer value for the data in the color union.
+} Color2;
+
+typedef struct BestEllipse2_struct {
+  PointFloat center;  // The coordinate location of the center of the ellipse.
+  PointFloat majorAxisStart;  // The coordinate location of the start of the
+                              // major axis of the ellipse.
+  PointFloat majorAxisEnd;  // The coordinate location of the end of the major
+                            // axis of the ellipse.
+  PointFloat minorAxisStart;  // The coordinate location of the start of the
+                              // minor axis of the ellipse.
+  PointFloat minorAxisEnd;  // The coordinate location of the end of the minor
+                            // axis of the ellipse.
+  double area;  // The area of the ellipse.
+  double perimeter;  // The length of the perimeter of the ellipse.
+  double error;  // Represents the least square error of the fitted ellipse to
+                 // the entire set of points.
+  int valid;  // This element is TRUE if the function achieved the minimum score
+              // within the number of allowed refinement iterations and FALSE if
+              // the function did not achieve the minimum score.
+  int* pointsUsed;  // An array of the indexes for the points array indicating
+                    // which points the function used to fit the ellipse.
+  int numPointsUsed;  // The number of points the function used to fit the
+                      // ellipse.
+} BestEllipse2;
+
+typedef struct LearnPatternAdvancedOptions_struct {
+  LearnPatternAdvancedShiftOptions* shiftOptions;  // Use this element to
+                                                   // control the behavior of
+                                                   // imaqLearnPattern2() during
+                                                   // the shift-invariant
+                                                   // learning phase.
+  LearnPatternAdvancedRotationOptions*
+      rotationOptions;  // Use this element to control the behavior of
+                        // imaqLearnPattern2()during the rotation-invariant
+                        // learning phase.
+} LearnPatternAdvancedOptions;
+
+typedef struct AVIInfo_struct {
+  unsigned int width;  // The width of each frame.
+  unsigned int height;  // The height of each frame.
+  ImageType imageType;  // The type of images this AVI contains.
+  unsigned int numFrames;  // The number of frames in the AVI.
+  unsigned int framesPerSecond;  // The number of frames per second this AVI
+                                 // should be shown at.
+  char* filterName;  // The name of the compression filter used to create this
+                     // AVI.
+  int hasData;  // Specifies whether this AVI has data attached to each frame or
+                // not.
+  unsigned int maxDataSize;  // If this AVI has data, the maximum size of the
+                             // data in each frame.
+} AVIInfo;
+
+typedef struct LearnPatternAdvancedShiftOptions_struct {
+  int initialStepSize;  // The largest number of image pixels to shift the
+                        // sample across the inspection image during the initial
+                        // phase of shift-invariant matching.
+  int initialSampleSize;  // Specifies the number of template pixels that you
+                          // want to include in a sample for the initial phase
+                          // of shift-invariant matching.
+  double initialSampleSizeFactor;  // Specifies the size of the sample for the
+                                   // initial phase of shift-invariant matching
+                                   // as a percent of the template size, in
+                                   // pixels.
+  int finalSampleSize;  // Specifies the number of template pixels you want to
+                        // add to initialSampleSize for the final phase of
+                        // shift-invariant matching.
+  double finalSampleSizeFactor;  // Specifies the size of the sample for the
+                                 // final phase of shift-invariant matching as a
+                                 // percent of the edge points in the template,
+                                 // in pixels.
+  int subpixelSampleSize;  // Specifies the number of template pixels that you
+                           // want to include in a sample for the subpixel phase
+                           // of shift-invariant matching.
+  double subpixelSampleSizeFactor;  // Specifies the size of the sample for the
+                                    // subpixel phase of shift-invariant
+                                    // matching as a percent of the template
+                                    // size, in pixels.
+} LearnPatternAdvancedShiftOptions;
+
+typedef struct LearnPatternAdvancedRotationOptions_struct {
+  SearchStrategy searchStrategySupport;  // Specifies the aggressiveness of the
+                                         // rotation search strategy available
+                                         // during the matching phase.
+  int initialStepSize;  // The largest number of image pixels to shift the
+                        // sample across the inspection image during the initial
+                        // phase of matching.
+  int initialSampleSize;  // Specifies the number of template pixels that you
+                          // want to include in a sample for the initial phase
+                          // of rotation-invariant matching.
+  double initialSampleSizeFactor;  // Specifies the size of the sample for the
+                                   // initial phase of rotation-invariant
+                                   // matching as a percent of the template
+                                   // size, in pixels.
+  int initialAngularAccuracy;  // Sets the angle accuracy, in degrees, to use
+                               // during the initial phase of rotation-invariant
+                               // matching.
+  int finalSampleSize;  // Specifies the number of template pixels you want to
+                        // add to initialSampleSize for the final phase of
+                        // rotation-invariant matching.
+  double finalSampleSizeFactor;  // Specifies the size of the sample for the
+                                 // final phase of rotation-invariant matching
+                                 // as a percent of the edge points in the
+                                 // template, in pixels.
+  int finalAngularAccuracy;  // Sets the angle accuracy, in degrees, to use
+                             // during the final phase of the rotation-invariant
+                             // matching.
+  int subpixelSampleSize;  // Specifies the number of template pixels that you
+                           // want to include in a sample for the subpixel phase
+                           // of rotation-invariant matching.
+  double subpixelSampleSizeFactor;  // Specifies the size of the sample for the
+                                    // subpixel phase of rotation-invariant
+                                    // matching as a percent of the template
+                                    // size, in pixels.
+} LearnPatternAdvancedRotationOptions;
+
+typedef struct MatchPatternAdvancedOptions_struct {
+  int subpixelIterations;  // Defines the maximum number of incremental
+                           // improvements used to refine matching using
+                           // subpixel information.
+  double subpixelTolerance;  // Defines the maximum amount of change, in pixels,
+                             // between consecutive incremental improvements in
+                             // the match position that you want to trigger the
+                             // end of the refinement process.
+  int initialMatchListLength;  // Specifies the maximum size of the match list.
+  int matchListReductionFactor;  // Specifies the reduction of the match list as
+                                 // matches are refined.
+  int initialStepSize;  // Specifies the number of pixels to shift the sample
+                        // across the inspection image during the initial phase
+                        // of shift-invariant matching.
+  SearchStrategy searchStrategy;  // Specifies the aggressiveness of the
+                                  // rotation search strategy.
+  int intermediateAngularAccuracy;  // Specifies the accuracy to use during the
+                                    // intermediate phase of rotation-invariant
+                                    // matching.
+} MatchPatternAdvancedOptions;
+
+typedef struct ParticleFilterCriteria2_struct {
+  MeasurementType parameter;  // The morphological measurement that the function
+                              // uses for filtering.
+  float lower;  // The lower bound of the criteria range.
+  float upper;  // The upper bound of the criteria range.
+  int calibrated;  // Set this element to TRUE to take calibrated measurements.
+  int exclude;  // Set this element to TRUE to indicate that a match occurs when
+                // the measurement is outside the criteria range.
+} ParticleFilterCriteria2;
+
+typedef struct BestCircle2_struct {
+  PointFloat center;  // The coordinate location of the center of the circle.
+  double radius;  // The radius of the circle.
+  double area;  // The area of the circle.
+  double perimeter;  // The length of the perimeter of the circle.
+  double error;  // Represents the least square error of the fitted circle to
+                 // the entire set of points.
+  int valid;  // This element is TRUE if the function achieved the minimum score
+              // within the number of allowed refinement iterations and FALSE if
+              // the function did not achieve the minimum score.
+  int* pointsUsed;  // An array of the indexes for the points array indicating
+                    // which points the function used to fit the circle.
+  int numPointsUsed;  // The number of points the function used to fit the
+                      // circle.
+} BestCircle2;
+
+typedef struct OCRSpacingOptions_struct {
+  int minCharSpacing;  // The minimum number of pixels that must be between two
+                       // characters for NI Vision to train or read the
+                       // characters separately.
+  int minCharSize;  // The minimum number of pixels required for an object to be
+                    // a potentially identifiable character.
+  int maxCharSize;  // The maximum number of pixels required for an object to be
+                    // a potentially identifiable character.
+  int maxHorizontalElementSpacing;  // The maximum horizontal spacing, in
+                                    // pixels, allowed between character
+                                    // elements to train or read the character
+                                    // elements as a single character.
+  int maxVerticalElementSpacing;  // The maximum vertical element spacing in
+                                  // pixels.
+  int minBoundingRectWidth;  // The minimum possible width, in pixels, for a
+                             // character bounding rectangle.
+  int maxBoundingRectWidth;  // The maximum possible width, in pixels, for a
+                             // character bounding rectangle.
+  int minBoundingRectHeight;  // The minimum possible height, in pixels, for a
+                              // character bounding rectangle.
+  int maxBoundingRectHeight;  // The maximum possible height, in pixels, for a
+                              // character bounding rectangle.
+  int autoSplit;  // Set this element to TRUE to automatically adjust the
+                  // location of the character bounding rectangle when
+                  // characters overlap vertically.
+} OCRSpacingOptions;
+
+typedef struct OCRProcessingOptions_struct {
+  ThresholdMode mode;  // The thresholding mode.
+  int lowThreshold;  // The low threshold value when you set mode to
+                     // IMAQ_FIXED_RANGE.
+  int highThreshold;  // The high threshold value when you set mode to
+                      // IMAQ_FIXED_RANGE.
+  int blockCount;  // The number of blocks for threshold calculation algorithms
+                   // that require blocks.
+  int fastThreshold;  // Set this element to TRUE to use a faster, less accurate
+                      // threshold calculation algorithm.
+  int biModalCalculation;  // Set this element to TRUE to calculate both the low
+                           // and high threshold values when using the fast
+                           // thresholding method.
+  int darkCharacters;  // Set this element to TRUE to read or train dark
+                       // characters on a light background.
+  int removeParticlesTouchingROI;  // Set this element to TRUE to remove the
+                                   // particles touching the ROI.
+  int erosionCount;  // The number of erosions to perform.
+} OCRProcessingOptions;
+
+typedef struct ReadTextOptions_struct {
+  String255 validChars[255];  // An array of strings that specifies the valid
+                              // characters.
+  int numValidChars;  // The number of strings in the validChars array that you
+                      // have initialized.
+  char substitutionChar;  // The character to substitute for objects that the
+                          // function cannot match with any of the trained
+                          // characters.
+  ReadStrategy readStrategy;  // The read strategy, which determines how closely
+                              // the function analyzes images in the reading
+                              // process to match objects with trained
+                              // characters.
+  int acceptanceLevel;  // The minimum acceptance level at which an object is
+                        // considered a trained character.
+  int aspectRatio;  // The maximum aspect ratio variance percentage for valid
+                    // characters.
+  ReadResolution readResolution;  // The read resolution, which determines how
+                                  // much of the trained character data the
+                                  // function uses to match objects to trained
+                                  // characters.
+} ReadTextOptions;
+
+typedef struct CharInfo_struct {
+  const char* charValue;  // Retrieves the character value of the corresponding
+                          // character in the character set.
+  const Image* charImage;  // The image you used to train this character.
+  const Image* internalImage;  // The internal representation that NI Vision
+                               // uses to match objects to this character.
+} CharInfo;
+
+#if !defined(USERINT_HEADER) && !defined(_CVI_RECT_DEFINED)
+typedef struct Rect_struct {
+  int top;  // Location of the top edge of the rectangle.
+  int left;  // Location of the left edge of the rectangle.
+  int height;  // Height of the rectangle.
+  int width;  // Width of the rectangle.
+} Rect;
+#define _CVI_RECT_DEFINED
+#endif
+
+typedef struct CharReport_struct {
+  const char* character;  // The character value.
+  PointFloat corner[4];  // An array of four points that describes the rectangle
+                         // that surrounds the character.
+  int reserved;  // This element is reserved.
+  int lowThreshold;  // The minimum value of the threshold range used for this
+                     // character.
+  int highThreshold;  // The maximum value of the threshold range used for this
+                      // character.
+} CharReport;
+
+typedef struct ReadTextReport_struct {
+  const char* readString;  // The read string.
+  const CharReport* characterReport;  // An array of reports describing the
+                                      // properties of each identified
+                                      // character.
+  int numCharacterReports;  // The number of identified characters.
+} ReadTextReport;
+
+#if !defined(USERINT_HEADER) && !defined(_CVI_POINT_DEFINED)
+typedef struct Point_struct {
+  int x;  // The x-coordinate of the point.
+  int y;  // The y-coordinate of the point.
+} Point;
+#define _CVI_POINT_DEFINED
+#endif
+
+typedef struct Annulus_struct {
+  Point center;  // The coordinate location of the center of the annulus.
+  int innerRadius;  // The internal radius of the annulus.
+  int outerRadius;  // The external radius of the annulus.
+  double startAngle;  // The start angle, in degrees, of the annulus.
+  double endAngle;  // The end angle, in degrees, of the annulus.
+} Annulus;
+
+typedef struct EdgeLocationReport_struct {
+  PointFloat* edges;  // The coordinate location of all edges detected by the
+                      // search line.
+  int numEdges;  // The number of points in the edges array.
+} EdgeLocationReport;
+
+typedef struct EdgeOptions_struct {
+  unsigned
+      threshold;  // Specifies the threshold value for the contrast of the edge.
+  unsigned width;  // The number of pixels that the function averages to find
+                   // the contrast at either side of the edge.
+  unsigned steepness;  // The span, in pixels, of the slope of the edge
+                       // projected along the path specified by the input
+                       // points.
+  InterpolationMethod subpixelType;  // The method for interpolating.
+  unsigned subpixelDivisions;  // The number of samples the function obtains
+                               // from a pixel.
+} EdgeOptions;
+
+typedef struct EdgeReport_struct {
+  float location;  // The location of the edge from the first point in the
+                   // points array.
+  float contrast;  // The contrast at the edge.
+  PolarityType polarity;  // The polarity of the edge.
+  float reserved;  // This element is reserved.
+  PointFloat coordinate;  // The coordinates of the edge.
+} EdgeReport;
+
+typedef struct ExtremeReport_struct {
+  double location;  // The locations of the extreme.
+  double amplitude;  // The amplitude of the extreme.
+  double secondDerivative;  // The second derivative of the extreme.
+} ExtremeReport;
+
+typedef struct FitLineOptions_struct {
+  float minScore;  // Specifies the required quality of the fitted line.
+  float pixelRadius;  // Specifies the neighborhood pixel relationship for the
+                      // initial subset of points being used.
+  int numRefinements;  // Specifies the number of refinement iterations you
+                       // allow the function to perform on the initial subset of
+                       // points.
+} FitLineOptions;
+
+typedef struct DisplayMapping_struct {
+  MappingMethod method;  // Describes the method for converting 16-bit pixels to
+                         // 8-bit pixels.
+  int minimumValue;  // When method is IMAQ_RANGE, minimumValue represents the
+                     // value that is mapped to 0.
+  int maximumValue;  // When method is IMAQ_RANGE, maximumValue represents the
+                     // value that is mapped to 255.
+  int shiftCount;  // When method is IMAQ_DOWNSHIFT, shiftCount represents the
+                   // number of bits the function right-shifts the 16-bit pixel
+                   // values.
+} DisplayMapping;
+
+typedef struct DetectExtremesOptions_struct {
+  double threshold;  // Defines which extremes are too small.
+  int width;  // Specifies the number of consecutive data points the function
+              // uses in the quadratic least-squares fit.
+} DetectExtremesOptions;
+
+typedef struct ImageInfo_struct {
+  CalibrationUnit imageUnit;  // If you set calibration information with
+                              // imaqSetSimpleCalibrationInfo(), imageUnit is
+                              // the calibration unit.
+  float stepX;  // If you set calibration information with
+                // imaqSetCalibrationInfo(), stepX is the distance in the
+                // calibration unit between two pixels in the x direction.
+  float stepY;  // If you set calibration information with
+                // imaqSetCalibrationInfo(), stepY is the distance in the
+                // calibration unit between two pixels in the y direction.
+  ImageType imageType;  // The type of the image.
+  int xRes;  // The number of columns in the image.
+  int yRes;  // The number of rows in the image.
+  int xOffset;  // If you set mask offset information with imaqSetMaskOffset(),
+                // xOffset is the offset of the mask origin in the x direction.
+  int yOffset;  // If you set mask offset information with imaqSetMaskOffset(),
+                // yOffset is the offset of the mask origin in the y direction.
+  int border;  // The number of border pixels around the image.
+  int pixelsPerLine;  // The number of pixels stored for each line of the image.
+  void* reserved0;  // This element is reserved.
+  void* reserved1;  // This element is reserved.
+  void* imageStart;  // A pointer to pixel (0,0).
+} ImageInfo;
+
+typedef struct LCDOptions_struct {
+  int litSegments;  // Set this parameter to TRUE if the segments are brighter
+                    // than the background.
+  float threshold;  // Determines whether a segment is ON or OFF.
+  int sign;  // Indicates whether the function must read the sign of the
+             // indicator.
+  int decimalPoint;  // Determines whether to look for a decimal separator after
+                     // each digit.
+} LCDOptions;
+
+typedef struct LCDReport_struct {
+  const char* text;  // A string of the characters of the LCD.
+  LCDSegments* segmentInfo;  // An array of LCDSegment structures describing
+                             // which segments of each digit are on.
+  int numCharacters;  // The number of characters that the function reads.
+  int reserved;  // This element is reserved.
+} LCDReport;
+
+typedef struct LCDSegments_struct {
+  unsigned a : 1;  // True if the a segment is on.
+  unsigned b : 1;  // True if the b segment is on.
+  unsigned c : 1;  // True if the c segment is on.
+  unsigned d : 1;  // True if the d segment is on.
+  unsigned e : 1;  // True if the e segment is on.
+  unsigned f : 1;  // True if the f segment is on.
+  unsigned g : 1;  // True if the g segment is on.
+  unsigned reserved : 25;  // This element is reserved.
+} LCDSegments;
+
+typedef struct LearnCalibrationOptions_struct {
+  CalibrationMode mode;  // Specifies the type of algorithm you want to use to
+                         // reduce distortion in your image.
+  ScalingMethod method;  // Defines the scaling method correction functions use
+                         // to correct the image.
+  CalibrationROI roi;  // Specifies the ROI correction functions use when
+                       // correcting an image.
+  int learnMap;  // Set this element to TRUE if you want the function to
+                 // calculate and store an error map during the learning
+                 // process.
+  int learnTable;  // Set this element to TRUE if you want the function to
+                   // calculate and store the correction table.
+} LearnCalibrationOptions;
+
+typedef struct LearnColorPatternOptions_struct {
+  LearningMode learnMode;  // Specifies the invariance mode the function uses
+                           // when learning the pattern.
+  ImageFeatureMode featureMode;  // Specifies the features the function uses
+                                 // when learning the color pattern.
+  int threshold;  // Specifies the saturation threshold the function uses to
+                  // distinguish between two colors that have the same hue
+                  // values.
+  ColorIgnoreMode ignoreMode;  // Specifies whether the function excludes
+                               // certain colors from the color features of the
+                               // template image.
+  ColorInformation* colorsToIgnore;  // An array of ColorInformation structures
+                                     // providing a set of colors to exclude
+                                     // from the color features of the template
+                                     // image.
+  int numColorsToIgnore;  // The number of ColorInformation structures in the
+                          // colorsToIgnore array.
+} LearnColorPatternOptions;
+
+typedef struct Line_struct {
+  Point start;  // The coordinate location of the start of the line.
+  Point end;  // The coordinate location of the end of the line.
+} Line;
+
+typedef struct LinearAverages_struct {
+  float* columnAverages;  // An array containing the mean pixel value of each
+                          // column.
+  int columnCount;  // The number of elements in the columnAverages array.
+  float* rowAverages;  // An array containing the mean pixel value of each row.
+  int rowCount;  // The number of elements in the rowAverages array.
+  float* risingDiagAverages;  // An array containing the mean pixel value of
+                              // each diagonal running from the lower left to
+                              // the upper right of the inspected area of the
+                              // image.
+  int risingDiagCount;  // The number of elements in the risingDiagAverages
+                        // array.
+  float* fallingDiagAverages;  // An array containing the mean pixel value of
+                               // each diagonal running from the upper left to
+                               // the lower right of the inspected area of the
+                               // image.
+  int fallingDiagCount;  // The number of elements in the fallingDiagAverages
+                         // array.
+} LinearAverages;
+
+typedef struct LineProfile_struct {
+  float*
+      profileData;  // An array containing the value of each pixel in the line.
+  Rect boundingBox;  // The bounding rectangle of the line.
+  float min;  // The smallest pixel value in the line profile.
+  float max;  // The largest pixel value in the line profile.
+  float mean;  // The mean value of the pixels in the line profile.
+  float stdDev;  // The standard deviation of the line profile.
+  int dataCount;  // The size of the profileData array.
+} LineProfile;
+
+typedef struct MatchColorPatternOptions_struct {
+  MatchingMode matchMode;  // Specifies the method to use when looking for the
+                           // color pattern in the image.
+  ImageFeatureMode featureMode;  // Specifies the features to use when looking
+                                 // for the color pattern in the image.
+  int minContrast;  // Specifies the minimum contrast expected in the image.
+  int subpixelAccuracy;  // Set this parameter to TRUE to return areas in the
+                         // image that match the pattern area with subpixel
+                         // accuracy.
+  RotationAngleRange* angleRanges;  // An array of angle ranges, in degrees,
+                                    // where each range specifies how much you
+                                    // expect the pattern to be rotated in the
+                                    // image.
+  int numRanges;  // Number of angle ranges in the angleRanges array.
+  double colorWeight;  // Determines the percent contribution of the color score
+                       // to the final color pattern matching score.
+  ColorSensitivity sensitivity;  // Specifies the sensitivity of the color
+                                 // information in the image.
+  SearchStrategy strategy;  // Specifies how the color features of the image are
+                            // used during the search phase.
+  int numMatchesRequested;  // Number of valid matches expected.
+  float minMatchScore;  // The minimum score a match can have for the function
+                        // to consider the match valid.
+} MatchColorPatternOptions;
+
+typedef struct HistogramReport_struct {
+  int* histogram;  // An array describing the number of pixels that fell into
+                   // each class.
+  int histogramCount;  // The number of elements in the histogram array.
+  float min;  // The smallest pixel value that the function classified.
+  float max;  // The largest pixel value that the function classified.
+  float start;  // The smallest pixel value that fell into the first class.
+  float width;  // The size of each class.
+  float mean;  // The mean value of the pixels that the function classified.
+  float stdDev;  // The standard deviation of the pixels that the function
+                 // classified.
+  int numPixels;  // The number of pixels that the function classified.
+} HistogramReport;
+
+typedef struct ArcInfo_struct {
+  Rect boundingBox;  // The coordinate location of the bounding box of the arc.
+  double startAngle;  // The counterclockwise angle from the x-axis in degrees
+                      // to the start of the arc.
+  double endAngle;  // The counterclockwise angle from the x-axis in degrees to
+                    // the end of the arc.
+} ArcInfo;
+
+typedef struct AxisReport_struct {
+  PointFloat origin;  // The origin of the coordinate system, which is the
+                      // intersection of the two axes of the coordinate system.
+  PointFloat mainAxisEnd;  // The end of the main axis, which is the result of
+                           // the computation of the intersection of the main
+                           // axis with the rectangular search area.
+  PointFloat secondaryAxisEnd;  // The end of the secondary axis, which is the
+                                // result of the computation of the intersection
+                                // of the secondary axis with the rectangular
+                                // search area.
+} AxisReport;
+
+typedef struct BarcodeInfo_struct {
+  const char* outputString;  // A string containing the decoded barcode data.
+  int size;  // The size of the output string.
+  char outputChar1;  // The contents of this character depend on the barcode
+                     // type.
+  char outputChar2;  // The contents of this character depend on the barcode
+                     // type.
+  double confidenceLevel;  // A quality measure of the decoded barcode ranging
+                           // from 0 to 100, with 100 being the best.
+  BarcodeType type;  // The type of barcode.
+} BarcodeInfo;
+
+typedef struct BCGOptions_struct {
+  float brightness;  // Adjusts the brightness of the image.
+  float contrast;  // Adjusts the contrast of the image.
+  float gamma;  // Performs gamma correction.
+} BCGOptions;
+
+typedef struct BestCircle_struct {
+  PointFloat center;  // The coordinate location of the center of the circle.
+  double radius;  // The radius of the circle.
+  double area;  // The area of the circle.
+  double perimeter;  // The length of the perimeter of the circle.
+  double error;  // Represents the least square error of the fitted circle to
+                 // the entire set of points.
+} BestCircle;
+
+typedef struct BestEllipse_struct {
+  PointFloat center;  // The coordinate location of the center of the ellipse.
+  PointFloat majorAxisStart;  // The coordinate location of the start of the
+                              // major axis of the ellipse.
+  PointFloat majorAxisEnd;  // The coordinate location of the end of the major
+                            // axis of the ellipse.
+  PointFloat minorAxisStart;  // The coordinate location of the start of the
+                              // minor axis of the ellipse.
+  PointFloat minorAxisEnd;  // The coordinate location of the end of the minor
+                            // axis of the ellipse.
+  double area;  // The area of the ellipse.
+  double perimeter;  // The length of the perimeter of the ellipse.
+} BestEllipse;
+
+typedef struct BestLine_struct {
+  PointFloat start;  // The coordinate location of the start of the line.
+  PointFloat end;  // The coordinate location of the end of the line.
+  LineEquation equation;  // Defines the three coefficients of the equation of
+                          // the best fit line.
+  int valid;  // This element is TRUE if the function achieved the minimum score
+              // within the number of allowed refinement iterations and FALSE if
+              // the function did not achieve the minimum score.
+  double error;  // Represents the least square error of the fitted line to the
+                 // entire set of points.
+  int* pointsUsed;  // An array of the indexes for the points array indicating
+                    // which points the function used to fit the line.
+  int numPointsUsed;  // The number of points the function used to fit the line.
+} BestLine;
+
+typedef struct BrowserOptions_struct {
+  int width;  // The width to make the browser.
+  int height;  // The height to make the browser image.
+  int imagesPerLine;  // The number of images to place on a single line.
+  RGBValue backgroundColor;  // The background color of the browser.
+  int frameSize;  // Specifies the number of pixels with which to border each
+                  // thumbnail.
+  BrowserFrameStyle style;  // The style for the frame around each thumbnail.
+  float ratio;  // Specifies the width to height ratio of each thumbnail.
+  RGBValue focusColor;  // The color to use to display focused cells.
+} BrowserOptions;
+
+typedef struct CoordinateSystem_struct {
+  PointFloat origin;  // The origin of the coordinate system.
+  float angle;  // The angle, in degrees, of the x-axis of the coordinate system
+                // relative to the image x-axis.
+  AxisOrientation axisOrientation;  // The direction of the y-axis of the
+                                    // coordinate reference system.
+} CoordinateSystem;
+
+typedef struct CalibrationInfo_struct {
+  float* errorMap;  // The error map for the calibration.
+  int mapColumns;  // The number of columns in the error map.
+  int mapRows;  // The number of rows in the error map.
+  ROI* userRoi;  // Specifies the ROI the user provided when learning the
+                 // calibration.
+  ROI* calibrationRoi;  // Specifies the ROI that corresponds to the region of
+                        // the image where the calibration information is
+                        // accurate.
+  LearnCalibrationOptions options;  // Specifies the calibration options the
+                                    // user provided when learning the
+                                    // calibration.
+  GridDescriptor grid;  // Specifies the scaling constants for the image.
+  CoordinateSystem system;  // Specifies the coordinate system for the real
+                            // world coordinates.
+  RangeFloat range;  // The range of the grayscale the function used to
+                     // represent the circles in the grid image.
+  float quality;  // The quality score of the learning process, which is a value
+                  // between 0-1000.
+} CalibrationInfo;
+
+typedef struct CalibrationPoints_struct {
+  PointFloat* pixelCoordinates;  // The array of pixel coordinates.
+  PointFloat* realWorldCoordinates;  // The array of corresponding real-world
+                                     // coordinates.
+  int numCoordinates;  // The number of coordinates in both of the arrays.
+} CalibrationPoints;
+
+typedef struct CaliperOptions_struct {
+  TwoEdgePolarityType
+      polarity;  // Specifies the edge polarity of the edge pairs.
+  float separation;  // The distance between edge pairs.
+  float separationDeviation;  // Sets the range around the separation value.
+} CaliperOptions;
+
+typedef struct CaliperReport_struct {
+  float edge1Contrast;  // The contrast of the first edge.
+  PointFloat edge1Coord;  // The coordinates of the first edge.
+  float edge2Contrast;  // The contrast of the second edge.
+  PointFloat edge2Coord;  // The coordinates of the second edge.
+  float separation;  // The distance between the two edges.
+  float reserved;  // This element is reserved.
+} CaliperReport;
+
+typedef struct DrawTextOptions_struct {
+  char fontName[32];  // The font name to use.
+  int fontSize;  // The size of the font.
+  int bold;  // Set this parameter to TRUE to bold text.
+  int italic;  // Set this parameter to TRUE to italicize text.
+  int underline;  // Set this parameter to TRUE to underline text.
+  int strikeout;  // Set this parameter to TRUE to strikeout text.
+  TextAlignment textAlignment;  // Sets the alignment of text.
+  FontColor fontColor;  // Sets the font color.
+} DrawTextOptions;
+
+typedef struct CircleReport_struct {
+  Point center;  // The coordinate point of the center of the circle.
+  int radius;  // The radius of the circle, in pixels.
+  int area;  // The area of the circle, in pixels.
+} CircleReport;
+
+typedef struct ClosedContour_struct {
+  Point* points;  // The points that make up the closed contour.
+  int numPoints;  // The number of points in the array.
+} ClosedContour;
+
+typedef struct ColorHistogramReport_struct {
+  HistogramReport plane1;  // The histogram report of the first color plane.
+  HistogramReport plane2;  // The histogram report of the second plane.
+  HistogramReport plane3;  // The histogram report of the third plane.
+} ColorHistogramReport;
+
+typedef struct ColorInformation_struct {
+  int infoCount;  // The size of the info array.
+  int saturation;  // The saturation level the function uses to learn the color
+                   // information.
+  double* info;  // An array of color information that represents the color
+                 // spectrum analysis of a region of an image in a compact form.
+} ColorInformation;
+
+typedef struct Complex_struct {
+  float r;  // The real part of the value.
+  float i;  // The imaginary part of the value.
+} Complex;
+
+typedef struct ConcentricRakeReport_struct {
+  ArcInfo* rakeArcs;  // An array containing the location of each concentric arc
+                      // line used for edge detection.
+  int numArcs;  // The number of arc lines in the rakeArcs array.
+  PointFloat* firstEdges;  // The coordinate location of all edges detected as
+                           // first edges.
+  int numFirstEdges;  // The number of points in the first edges array.
+  PointFloat* lastEdges;  // The coordinate location of all edges detected as
+                          // last edges.
+  int numLastEdges;  // The number of points in the last edges array.
+  EdgeLocationReport* allEdges;  // An array of reports describing the location
+                                 // of the edges located by each concentric rake
+                                 // arc line.
+  int* linesWithEdges;  // An array of indices into the rakeArcs array
+                        // indicating the concentric rake arc lines on which the
+                        // function detected at least one edge.
+  int numLinesWithEdges;  // The number of concentric rake arc lines along which
+                          // the function detected edges.
+} ConcentricRakeReport;
+
+typedef struct ConstructROIOptions_struct {
+  int windowNumber;  // The window number of the image window.
+  const char* windowTitle;  // Specifies the message string that the function
+                            // displays in the title bar of the window.
+  PaletteType type;  // The palette type to use.
+  RGBValue* palette;  // If type is IMAQ_PALETTE_USER, this array is the palette
+                      // of colors to use with the window.
+  int numColors;  // If type is IMAQ_PALETTE_USER, this element is the number of
+                  // colors in the palette array.
+} ConstructROIOptions;
+
+typedef struct ContourInfo_struct {
+  ContourType type;  // The contour type.
+  unsigned numPoints;  // The number of points that make up the contour.
+  Point* points;  // The points describing the contour.
+  RGBValue contourColor;  // The contour color.
+} ContourInfo;
+
+typedef union ContourUnion_union {
+  Point* point;  // Use this member when the contour is of type IMAQ_POINT.
+  Line* line;  // Use this member when the contour is of type IMAQ_LINE.
+  Rect* rect;  // Use this member when the contour is of type IMAQ_RECT.
+  Rect* ovalBoundingBox;  // Use this member when the contour is of type
+                          // IMAQ_OVAL.
+  ClosedContour* closedContour;  // Use this member when the contour is of type
+                                 // IMAQ_CLOSED_CONTOUR.
+  OpenContour* openContour;  // Use this member when the contour is of type
+                             // IMAQ_OPEN_CONTOUR.
+  Annulus* annulus;  // Use this member when the contour is of type
+                     // IMAQ_ANNULUS.
+  RotatedRect* rotatedRect;  // Use this member when the contour is of type
+                             // IMAQ_ROTATED_RECT.
+} ContourUnion;
+
+typedef struct ContourInfo2_struct {
+  ContourType type;  // The contour type.
+  RGBValue color;  // The contour color.
+  ContourUnion structure;  // The information necessary to describe the contour
+                           // in coordinate space.
+} ContourInfo2;
+
+typedef struct ContourPoint_struct {
+  double x;  // The x-coordinate value in the image.
+  double y;  // The y-coordinate value in the image.
+  double curvature;  // The change in slope at this edge point of the segment.
+  double xDisplacement;  // The x displacement of the current edge pixel from a
+                         // cubic spline fit of the current edge segment.
+  double yDisplacement;  // The y displacement of the current edge pixel from a
+                         // cubic spline fit of the current edge segment.
+} ContourPoint;
+
+typedef struct CoordinateTransform_struct {
+  Point initialOrigin;  // The origin of the initial coordinate system.
+  float initialAngle;  // The angle, in degrees, of the x-axis of the initial
+                       // coordinate system relative to the image x-axis.
+  Point finalOrigin;  // The origin of the final coordinate system.
+  float finalAngle;  // The angle, in degrees, of the x-axis of the final
+                     // coordinate system relative to the image x-axis.
+} CoordinateTransform;
+
+typedef struct CoordinateTransform2_struct {
+  CoordinateSystem
+      referenceSystem;  // Defines the coordinate system for input coordinates.
+  CoordinateSystem measurementSystem;  // Defines the coordinate system in which
+                                       // the function should perform
+                                       // measurements.
+} CoordinateTransform2;
+
+typedef struct CannyOptions_struct {
+  float sigma;  // The sigma of the Gaussian smoothing filter that the function
+                // applies to the image before edge detection.
+  float upperThreshold;  // The upper fraction of pixel values in the image from
+                         // which the function chooses a seed or starting point
+                         // of an edge segment.
+  float lowerThreshold;  // The function multiplies this value by upperThreshold
+                         // to determine the lower threshold for all the pixels
+                         // in an edge segment.
+  int windowSize;  // The window size of the Gaussian filter that the function
+                   // applies to the image.
+} CannyOptions;
+
+typedef struct Range_struct {
+  int minValue;  // The minimum value of the range.
+  int maxValue;  // The maximum value of the range.
+} Range;
+
+typedef struct UserPointSymbol_struct {
+  int cols;  // Number of columns in the symbol.
+  int rows;  // Number of rows in the symbol.
+  int* pixels;  // The pixels of the symbol.
+} UserPointSymbol;
+
+typedef struct View3DOptions_struct {
+  int sizeReduction;  // A divisor the function uses when determining the final
+                      // height and width of the 3D image.
+  int maxHeight;  // Defines the maximum height of a pixel from the image source
+                  // drawn in 3D.
+  Direction3D direction;  // Defines the 3D orientation.
+  float alpha;  // Determines the angle between the horizontal and the baseline.
+  float beta;  // Determines the angle between the horizontal and the second
+               // baseline.
+  int border;  // Defines the border size.
+  int background;  // Defines the background color.
+  Plane3D plane;  // Indicates the view a function uses to show complex images.
+} View3DOptions;
+
+typedef struct MatchPatternOptions_struct {
+  MatchingMode mode;  // Specifies the method to use when looking for the
+                      // pattern in the image.
+  int minContrast;  // Specifies the minimum contrast expected in the image.
+  int subpixelAccuracy;  // Set this element to TRUE to return areas in the
+                         // image that match the pattern area with subpixel
+                         // accuracy.
+  RotationAngleRange* angleRanges;  // An array of angle ranges, in degrees,
+                                    // where each range specifies how much you
+                                    // expect the pattern to be rotated in the
+                                    // image.
+  int numRanges;  // Number of angle ranges in the angleRanges array.
+  int numMatchesRequested;  // Number of valid matches expected.
+  int matchFactor;  // Controls the number of potential matches that the
+                    // function examines.
+  float minMatchScore;  // The minimum score a match can have for the function
+                        // to consider the match valid.
+} MatchPatternOptions;
+
+typedef struct TIFFFileOptions_struct {
+  int rowsPerStrip;  // Indicates the number of rows that the function writes
+                     // per strip.
+  PhotometricMode
+      photoInterp;  // Designates which photometric interpretation to use.
+  TIFFCompressionType compressionType;  // Indicates the type of compression to
+                                        // use on the TIFF file.
+} TIFFFileOptions;
+
+typedef union Color_union {
+  RGBValue rgb;  // The information needed to describe a color in the RGB (Red,
+                 // Green, and Blue) color space.
+  HSLValue hsl;  // The information needed to describe a color in the HSL (Hue,
+                 // Saturation, and Luminance) color space.
+  HSVValue hsv;  // The information needed to describe a color in the HSI (Hue,
+                 // Saturation, and Value) color space.
+  HSIValue hsi;  // The information needed to describe a color in the HSI (Hue,
+                 // Saturation, and Intensity) color space.
+  int rawValue;  // The integer value for the data in the color union.
+} Color;
+
+typedef union PixelValue_union {
+  float grayscale;  // A grayscale pixel value.
+  RGBValue rgb;  // A RGB pixel value.
+  HSLValue hsl;  // A HSL pixel value.
+  Complex complex;  // A complex pixel value.
+  RGBU64Value rgbu64;  // An unsigned 64-bit RGB pixel value.
+} PixelValue;
+
+typedef struct OpenContour_struct {
+  Point* points;  // The points that make up the open contour.
+  int numPoints;  // The number of points in the array.
+} OpenContour;
+
+typedef struct OverlayTextOptions_struct {
+  const char* fontName;  // The name of the font to use.
+  int fontSize;  // The size of the font.
+  int bold;  // Set this element to TRUE to bold the text.
+  int italic;  // Set this element to TRUE to italicize the text.
+  int underline;  // Set this element to TRUE to underline the text.
+  int strikeout;  // Set this element to TRUE to strikeout the text.
+  TextAlignment horizontalTextAlignment;  // Sets the alignment of the text.
+  VerticalTextAlignment
+      verticalTextAlignment;  // Sets the vertical alignment for the text.
+  RGBValue backgroundColor;  // Sets the color for the text background pixels.
+  double angle;  // The counterclockwise angle, in degrees, of the text relative
+                 // to the x-axis.
+} OverlayTextOptions;
+
+typedef struct ParticleFilterCriteria_struct {
+  MeasurementValue parameter;  // The morphological measurement that the
+                               // function uses for filtering.
+  float lower;  // The lower bound of the criteria range.
+  float upper;  // The upper bound of the criteria range.
+  int exclude;  // Set this element to TRUE to indicate that a match occurs when
+                // the value is outside the criteria range.
+} ParticleFilterCriteria;
+
+typedef struct ParticleReport_struct {
+  int area;  // The number of pixels in the particle.
+  float calibratedArea;  // The size of the particle, calibrated to the
+                         // calibration information of the image.
+  float perimeter;  // The length of the perimeter, calibrated to the
+                    // calibration information of the image.
+  int numHoles;  // The number of holes in the particle.
+  int areaOfHoles;  // The total surface area, in pixels, of all the holes in a
+                    // particle.
+  float perimeterOfHoles;  // The length of the perimeter of all the holes in
+                           // the particle calibrated to the calibration
+                           // information of the image.
+  Rect boundingBox;  // The smallest rectangle that encloses the particle.
+  float sigmaX;  // The sum of the particle pixels on the x-axis.
+  float sigmaY;  // The sum of the particle pixels on the y-axis.
+  float sigmaXX;  // The sum of the particle pixels on the x-axis, squared.
+  float sigmaYY;  // The sum of the particle pixels on the y-axis, squared.
+  float sigmaXY;  // The sum of the particle pixels on the x-axis and y-axis.
+  int longestLength;  // The length of the longest horizontal line segment.
+  Point longestPoint;  // The location of the leftmost pixel of the longest
+                       // segment in the particle.
+  int projectionX;  // The length of the particle when projected onto the
+                    // x-axis.
+  int projectionY;  // The length of the particle when projected onto the
+                    // y-axis.
+  int connect8;  // This element is TRUE if the function used connectivity-8 to
+                 // determine if particles are touching.
+} ParticleReport;
+
+typedef struct PatternMatch_struct {
+  PointFloat position;  // The location of the center of the match.
+  float rotation;  // The rotation of the match relative to the template image,
+                   // in degrees.
+  float scale;  // The size of the match relative to the size of the template
+                // image, expressed as a percentage.
+  float score;  // The accuracy of the match.
+  PointFloat corner[4];  // An array of four points describing the rectangle
+                         // surrounding the template image.
+} PatternMatch;
+
+typedef struct QuantifyData_struct {
+  float mean;  // The mean value of the pixel values.
+  float stdDev;  // The standard deviation of the pixel values.
+  float min;  // The smallest pixel value.
+  float max;  // The largest pixel value.
+  float calibratedArea;  // The area, calibrated to the calibration information
+                         // of the image.
+  int pixelArea;  // The area, in number of pixels.
+  float relativeSize;  // The proportion, expressed as a percentage, of the
+                       // associated region relative to the whole image.
+} QuantifyData;
+
+typedef struct QuantifyReport_struct {
+  QuantifyData global;  // Statistical data of the whole image.
+  QuantifyData* regions;  // An array of QuantifyData structures containing
+                          // statistical data of each region of the image.
+  int regionCount;  // The number of regions.
+} QuantifyReport;
+
+typedef struct RakeOptions_struct {
+  int threshold;  // Specifies the threshold value for the contrast of the edge.
+  int width;  // The number of pixels that the function averages to find the
+              // contrast at either side of the edge.
+  int steepness;  // The span, in pixels, of the slope of the edge projected
+                  // along the path specified by the input points.
+  int subsamplingRatio;  // Specifies the number of pixels that separate two
+                         // consecutive search lines.
+  InterpolationMethod subpixelType;  // The method for interpolating.
+  int subpixelDivisions;  // The number of samples the function obtains from a
+                          // pixel.
+} RakeOptions;
+
+typedef struct RakeReport_struct {
+  LineFloat* rakeLines;  // The coordinate location of each of the rake lines
+                         // used by the function.
+  int numRakeLines;  // The number of lines in the rakeLines array.
+  PointFloat* firstEdges;  // The coordinate location of all edges detected as
+                           // first edges.
+  unsigned int numFirstEdges;  // The number of points in the firstEdges array.
+  PointFloat* lastEdges;  // The coordinate location of all edges detected as
+                          // last edges.
+  unsigned int numLastEdges;  // The number of points in the lastEdges array.
+  EdgeLocationReport* allEdges;  // An array of reports describing the location
+                                 // of the edges located by each rake line.
+  int* linesWithEdges;  // An array of indices into the rakeLines array
+                        // indicating the rake lines on which the function
+                        // detected at least one edge.
+  int numLinesWithEdges;  // The number of rake lines along which the function
+                          // detected edges.
+} RakeReport;
+
+typedef struct TransformReport_struct {
+  PointFloat* points;  // An array of transformed coordinates.
+  int* validPoints;  // An array of values that describe the validity of each of
+                     // the coordinates according to the region of interest you
+                     // calibrated using either imaqLearnCalibrationGrid() or
+                     // imaqLearnCalibrationPoints().
+  int numPoints;  // The length of both the points array and the validPoints
+                  // array.
+} TransformReport;
+
+typedef struct ShapeReport_struct {
+  Rect coordinates;  // The bounding rectangle of the object.
+  Point centroid;  // The coordinate location of the centroid of the object.
+  int size;  // The size, in pixels, of the object.
+  double score;  // A value ranging between 1 and 1,000 that specifies how
+                 // similar the object in the image is to the template.
+} ShapeReport;
+
+typedef struct MeterArc_struct {
+  PointFloat
+      needleBase;  // The coordinate location of the base of the meter needle.
+  PointFloat* arcCoordPoints;  // An array of points describing the coordinate
+                               // location of the meter arc.
+  int numOfArcCoordPoints;  // The number of points in the arcCoordPoints array.
+  int needleColor;  // This element is TRUE when the meter has a light-colored
+                    // needle on a dark background.
+} MeterArc;
+
+typedef struct ThresholdData_struct {
+  float rangeMin;  // The lower boundary of the range to keep.
+  float rangeMax;  // The upper boundary of the range to keep.
+  float newValue;  // If useNewValue is TRUE, newValue is the replacement value
+                   // for pixels within the range.
+  int useNewValue;  // If TRUE, the function sets pixel values within [rangeMin,
+                    // rangeMax] to the value specified in newValue.
+} ThresholdData;
+
+typedef struct StructuringElement_struct {
+  int matrixCols;  // Number of columns in the matrix.
+  int matrixRows;  // Number of rows in the matrix.
+  int hexa;  // Set this element to TRUE if you specify a hexagonal structuring
+             // element in kernel.
+  int* kernel;  // The values of the structuring element.
+} StructuringElement;
+
+typedef struct SpokeReport_struct {
+  LineFloat* spokeLines;  // The coordinate location of each of the spoke lines
+                          // used by the function.
+  int numSpokeLines;  // The number of lines in the spokeLines array.
+  PointFloat* firstEdges;  // The coordinate location of all edges detected as
+                           // first edges.
+  int numFirstEdges;  // The number of points in the firstEdges array.
+  PointFloat* lastEdges;  // The coordinate location of all edges detected as
+                          // last edges.
+  int numLastEdges;  // The number of points in the lastEdges array.
+  EdgeLocationReport* allEdges;  // An array of reports describing the location
+                                 // of the edges located by each spoke line.
+  int* linesWithEdges;  // An array of indices into the spokeLines array
+                        // indicating the rake lines on which the function
+                        // detected at least one edge.
+  int numLinesWithEdges;  // The number of spoke lines along which the function
+                          // detects edges.
+} SpokeReport;
+
+typedef struct SimpleEdgeOptions_struct {
+  LevelType type;  // Determines how the function evaluates the threshold and
+                   // hysteresis values.
+  int threshold;  // The pixel value at which an edge occurs.
+  int hysteresis;  // A value that helps determine edges in noisy images.
+  EdgeProcess process;  // Determines which edges the function looks for.
+  int subpixel;  // Set this element to TRUE to find edges with subpixel
+                 // accuracy by interpolating between points to find the
+                 // crossing of the given threshold.
+} SimpleEdgeOptions;
+
+typedef struct SelectParticleCriteria_struct {
+  MeasurementValue parameter;  // The morphological measurement that the
+                               // function uses for filtering.
+  float lower;  // The lower boundary of the criteria range.
+  float upper;  // The upper boundary of the criteria range.
+} SelectParticleCriteria;
+
+typedef struct SegmentInfo_struct {
+  int numberOfPoints;  // The number of points in the segment.
+  int isOpen;  // If TRUE, the contour is open.
+  double weight;  // The significance of the edge in terms of the gray values
+                  // that constitute the edge.
+  ContourPoint* points;  // The points of the segment.
+} SegmentInfo;
+
+typedef struct RotationAngleRange_struct {
+  float lower;  // The lowest amount of rotation, in degrees, a valid pattern
+                // can have.
+  float upper;  // The highest amount of rotation, in degrees, a valid pattern
+                // can have.
+} RotationAngleRange;
+
+typedef struct RotatedRect_struct {
+  int top;  // Location of the top edge of the rectangle before rotation.
+  int left;  // Location of the left edge of the rectangle before rotation.
+  int height;  // Height of the rectangle.
+  int width;  // Width of the rectangle.
+  double angle;  // The rotation, in degrees, of the rectangle.
+} RotatedRect;
+
+typedef struct ROIProfile_struct {
+  LineProfile report;  // Quantifying information about the points along the
+                       // edge of each contour in the ROI.
+  Point* pixels;  // An array of the points along the edge of each contour in
+                  // the ROI.
+} ROIProfile;
+
+typedef struct ToolWindowOptions_struct {
+  int showSelectionTool;  // If TRUE, the selection tool becomes visible.
+  int showZoomTool;  // If TRUE, the zoom tool becomes visible.
+  int showPointTool;  // If TRUE, the point tool becomes visible.
+  int showLineTool;  // If TRUE, the line tool becomes visible.
+  int showRectangleTool;  // If TRUE, the rectangle tool becomes visible.
+  int showOvalTool;  // If TRUE, the oval tool becomes visible.
+  int showPolygonTool;  // If TRUE, the polygon tool becomes visible.
+  int showClosedFreehandTool;  // If TRUE, the closed freehand tool becomes
+                               // visible.
+  int showPolyLineTool;  // If TRUE, the polyline tool becomes visible.
+  int showFreehandTool;  // If TRUE, the freehand tool becomes visible.
+  int showAnnulusTool;  // If TRUE, the annulus becomes visible.
+  int showRotatedRectangleTool;  // If TRUE, the rotated rectangle tool becomes
+                                 // visible.
+  int showPanTool;  // If TRUE, the pan tool becomes visible.
+  int showZoomOutTool;  // If TRUE, the zoom out tool becomes visible.
+  int reserved2;  // This element is reserved and should be set to FALSE.
+  int reserved3;  // This element is reserved and should be set to FALSE.
+  int reserved4;  // This element is reserved and should be set to FALSE.
+} ToolWindowOptions;
+
+typedef struct SpokeOptions_struct {
+  int threshold;  // Specifies the threshold value for the contrast of the edge.
+  int width;  // The number of pixels that the function averages to find the
+              // contrast at either side of the edge.
+  int steepness;  // The span, in pixels, of the slope of the edge projected
+                  // along the path specified by the input points.
+  double subsamplingRatio;  // The angle, in degrees, between each radial search
+                            // line in the spoke.
+  InterpolationMethod subpixelType;  // The method for interpolating.
+  int subpixelDivisions;  // The number of samples the function obtains from a
+                          // pixel.
+} SpokeOptions;
+
+#if !defined __GNUC__ && !defined _M_X64
+#pragma pack(pop)
+#endif
+
+//============================================================================
+// Callback Function Type
+//============================================================================
+#ifndef __GNUC__
+typedef void(IMAQ_CALLBACK* EventCallback)(WindowEventType event,
+                                           int windowNumber, Tool tool,
+                                           Rect rect);
+#endif
+
+//============================================================================
+//  Globals
+//============================================================================
+#ifndef __GNUC__
+#pragma const_seg("IMAQVisionColorConstants")
+#endif
+static const RGBValue IMAQ_RGB_TRANSPARENT = {0, 0, 0, 1};
+static const RGBValue IMAQ_RGB_RED = {0, 0, 255, 0};
+static const RGBValue IMAQ_RGB_BLUE = {255, 0, 0, 0};
+static const RGBValue IMAQ_RGB_GREEN = {0, 255, 0, 0};
+static const RGBValue IMAQ_RGB_YELLOW = {0, 255, 255, 0};
+static const RGBValue IMAQ_RGB_WHITE = {255, 255, 255, 0};
+static const RGBValue IMAQ_RGB_BLACK = {0, 0, 0, 0};
+#ifndef __GNUC__
+#pragma const_seg()
+#endif
+
+//============================================================================
+//  Backwards Compatibility
+//============================================================================
+typedef ColorSensitivity ColorComplexity;
+#define IMAQ_COMPLEXITY_LOW IMAQ_SENSITIVITY_LOW
+#define IMAQ_COMPLEXITY_MED IMAQ_SENSITIVITY_MED
+#define IMAQ_COMPLEXITY_HIGH IMAQ_SENSITIVITY_HIGH
+#define ERR_INVALID_COLORCOMPLEXITY ERR_INVALID_COLORSENSITIVITY
+
+//============================================================================
+//  Logical functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAnd(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAndConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqCompare(Image* dest, const Image* source,
+                                       const Image* compareImage,
+                                       ComparisonFunction compare);
+IMAQ_FUNC int IMAQ_STDCALL imaqCompareConstant(Image* dest, const Image* source,
+                                               PixelValue value,
+                                               ComparisonFunction compare);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLogicalDifference(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqLogicalDifferenceConstant(Image* dest,
+                                                         const Image* source,
+                                                         PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqNand(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqNandConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqNor(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqNorConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOr(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOrConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqXnor(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqXnorConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqXor(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqXorConstant(Image* dest, const Image* source, PixelValue value);
+
+//============================================================================
+//  Particle Analysis functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCountParticles(Image* image, int connectivity8, int* numParticles);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMeasureParticle(Image* image, int particleNumber, int calibrated,
+                    MeasurementType measurement, double* value);
+IMAQ_FUNC MeasureParticlesReport* IMAQ_STDCALL
+imaqMeasureParticles(Image* image,
+                     MeasureParticlesCalibrationMode calibrationMode,
+                     const MeasurementType* measurements,
+                     size_t numMeasurements);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqParticleFilter4(Image* dest, Image* source,
+                    const ParticleFilterCriteria2* criteria, int criteriaCount,
+                    const ParticleFilterOptions2* options, const ROI* roi,
+                    int* numParticles);
+
+//============================================================================
+//  Morphology functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqConvexHull(Image* dest, Image* source, int connectivity8);
+IMAQ_FUNC int IMAQ_STDCALL imaqDanielssonDistance(Image* dest, Image* source);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFillHoles(Image* dest, const Image* source, int connectivity8);
+IMAQ_FUNC CircleReport* IMAQ_STDCALL
+imaqFindCircles(Image* dest, Image* source, float minRadius, float maxRadius,
+                int* numCircles);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLabel2(Image* dest, Image* source, int connectivity8, int* particleCount);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMorphology(Image* dest, Image* source, MorphologyMethod method,
+               const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqRejectBorder(Image* dest, Image* source, int connectivity8);
+IMAQ_FUNC int IMAQ_STDCALL imaqSegmentation(Image* dest, Image* source);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSeparation(Image* dest, Image* source, int erosions,
+               const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSimpleDistance(Image* dest, Image* source,
+                   const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSizeFilter(Image* dest, Image* source, int connectivity8, int erosions,
+               SizeType keepSize, const StructuringElement* structuringElement);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSkeleton(Image* dest, Image* source, SkeletonMethod method);
+
+//============================================================================
+//  Acquisition functions
+//============================================================================
+IMAQ_FUNC Image* IMAQ_STDCALL imaqCopyFromRing(SESSION_ID sessionID,
+                                               Image* image, int imageToCopy,
+                                               int* imageNumber, Rect rect);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqEasyAcquire(const char* interfaceName);
+IMAQ_FUNC Image* IMAQ_STDCALL
+imaqExtractFromRing(SESSION_ID sessionID, int imageToExtract, int* imageNumber);
+IMAQ_FUNC Image* IMAQ_STDCALL
+imaqGrab(SESSION_ID sessionID, Image* image, int immediate);
+IMAQ_FUNC int IMAQ_STDCALL imaqReleaseImage(SESSION_ID sessionID);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupGrab(SESSION_ID sessionID, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupRing(SESSION_ID sessionID, Image** images,
+                                         int numImages, int skipCount,
+                                         Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupSequence(SESSION_ID sessionID,
+                                             Image** images, int numImages,
+                                             int skipCount, Rect rect);
+IMAQ_FUNC Image* IMAQ_STDCALL
+imaqSnap(SESSION_ID sessionID, Image* image, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqStartAcquisition(SESSION_ID sessionID);
+IMAQ_FUNC int IMAQ_STDCALL imaqStopAcquisition(SESSION_ID sessionID);
+
+//============================================================================
+//  Arithmetic functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAbsoluteDifference(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL imaqAbsoluteDifferenceConstant(Image* dest,
+                                                          const Image* source,
+                                                          PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAdd(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAddConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAverage(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAverageConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqDivide2(Image* dest, const Image* sourceA,
+                                       const Image* sourceB,
+                                       RoundingMode roundingMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqDivideConstant2(Image* dest, const Image* source,
+                                               PixelValue value,
+                                               RoundingMode roundingMode);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMax(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMaxConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMin(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMinConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqModulo(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqModuloConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL imaqMulDiv(Image* dest, const Image* sourceA,
+                                      const Image* sourceB, float value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMultiply(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMultiplyConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSubtract(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSubtractConstant(Image* dest, const Image* source, PixelValue value);
+
+//============================================================================
+//  Caliper functions
+//============================================================================
+IMAQ_FUNC CaliperReport* IMAQ_STDCALL
+imaqCaliperTool(const Image* image, const Point* points, int numPoints,
+                const EdgeOptions* edgeOptions,
+                const CaliperOptions* caliperOptions, int* numEdgePairs);
+IMAQ_FUNC ConcentricRakeReport2* IMAQ_STDCALL
+imaqConcentricRake2(Image* image, ROI* roi, ConcentricRakeDirection direction,
+                    EdgeProcess process, int stepSize,
+                    EdgeOptions2* edgeOptions);
+IMAQ_FUNC ExtremeReport* IMAQ_STDCALL
+imaqDetectExtremes(const double* pixels, int numPixels, DetectionMode mode,
+                   const DetectExtremesOptions* options, int* numExtremes);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDetectRotation(const Image* referenceImage, const Image* testImage,
+                   PointFloat referenceCenter, PointFloat testCenter,
+                   int radius, float precision, double* angle);
+IMAQ_FUNC EdgeReport2* IMAQ_STDCALL
+imaqEdgeTool4(Image* image, ROI* roi, EdgeProcess processType,
+              EdgeOptions2* edgeOptions, const unsigned int reverseDirection);
+IMAQ_FUNC FindEdgeReport* IMAQ_STDCALL
+imaqFindEdge2(Image* image, const ROI* roi, const CoordinateSystem* baseSystem,
+              const CoordinateSystem* newSystem,
+              const FindEdgeOptions2* findEdgeOptions,
+              const StraightEdgeOptions* straightEdgeOptions);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFindTransformRect2(Image* image, const ROI* roi, FindTransformMode mode,
+                       CoordinateSystem* baseSystem,
+                       CoordinateSystem* newSystem,
+                       const FindTransformRectOptions2* findTransformOptions,
+                       const StraightEdgeOptions* straightEdgeOptions,
+                       AxisReport* axisReport);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFindTransformRects2(Image* image, const ROI* primaryROI,
+                        const ROI* secondaryROI, FindTransformMode mode,
+                        CoordinateSystem* baseSystem,
+                        CoordinateSystem* newSystem,
+                        const FindTransformRectsOptions2* findTransformOptions,
+                        const StraightEdgeOptions* primaryStraightEdgeOptions,
+                        const StraightEdgeOptions* secondaryStraightEdgeOptions,
+                        AxisReport* axisReport);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLineGaugeTool2(const Image* image, Point start, Point end,
+                   LineGaugeMethod method, const EdgeOptions* edgeOptions,
+                   const CoordinateTransform2* transform, float* distance);
+IMAQ_FUNC RakeReport2* IMAQ_STDCALL
+imaqRake2(Image* image, ROI* roi, RakeDirection direction, EdgeProcess process,
+          int stepSize, EdgeOptions2* edgeOptions);
+IMAQ_FUNC PointFloat* IMAQ_STDCALL
+imaqSimpleEdge(const Image* image, const Point* points, int numPoints,
+               const SimpleEdgeOptions* options, int* numEdges);
+IMAQ_FUNC SpokeReport2* IMAQ_STDCALL
+imaqSpoke2(Image* image, ROI* roi, SpokeDirection direction,
+           EdgeProcess process, int stepSize, EdgeOptions2* edgeOptions);
+IMAQ_FUNC StraightEdgeReport2* IMAQ_STDCALL
+imaqStraightEdge(const Image* image, const ROI* roi,
+                 SearchDirection searchDirection,
+                 const EdgeOptions2* edgeOptions,
+                 const StraightEdgeOptions* straightEdgeOptions);
+IMAQ_FUNC StraightEdgeReport2* IMAQ_STDCALL
+imaqStraightEdge2(const Image* image, const ROI* roi,
+                  SearchDirection searchDirection,
+                  const EdgeOptions2* edgeOptions,
+                  const StraightEdgeOptions* straightEdgeOptions,
+                  unsigned int optimizedMode);
+
+//============================================================================
+//  Spatial Filters functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCannyEdgeFilter(Image* dest, const Image* source,
+                                               const CannyOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqConvolve2(Image* dest, Image* source, float* kernel, int matrixRows,
+              int matrixCols, float normalize, Image* mask,
+              RoundingMode roundingMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqCorrelate(Image* dest, Image* source,
+                                         const Image* templateImage, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqEdgeFilter(Image* dest, Image* source,
+                                          OutlineMethod method,
+                                          const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqLowPass(Image* dest, Image* source, int width,
+                                       int height, float tolerance,
+                                       const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqMedianFilter(Image* dest, Image* source,
+                                            int width, int height,
+                                            const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqNthOrderFilter(Image* dest, Image* source,
+                                              int width, int height, int n,
+                                              const Image* mask);
+
+//============================================================================
+//  Drawing functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqDrawLineOnImage(Image* dest, const Image* source,
+                                               DrawMode mode, Point start,
+                                               Point end, float newPixelValue);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDrawShapeOnImage(Image* dest, const Image* source, Rect rect, DrawMode mode,
+                     ShapeMode shape, float newPixelValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqDrawTextOnImage(Image* dest, const Image* source,
+                                               Point coord, const char* text,
+                                               const DrawTextOptions* options,
+                                               int* fontNameUsed);
+
+//============================================================================
+//  Interlacing functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqInterlaceCombine(Image* frame, const Image* odd, const Image* even);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqInterlaceSeparate(const Image* frame, Image* odd, Image* even);
+
+//============================================================================
+//  Image Information functions
+//============================================================================
+IMAQ_FUNC char** IMAQ_STDCALL
+imaqEnumerateCustomKeys(const Image* image, unsigned int* size);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetBitDepth(const Image* image, unsigned int* bitDepth);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetBytesPerPixel(const Image* image, int* byteCount);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetImageInfo(const Image* image, ImageInfo* info);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetImageSize(const Image* image, int* width, int* height);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetImageType(const Image* image, ImageType* type);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetMaskOffset(const Image* image, Point* offset);
+IMAQ_FUNC void* IMAQ_STDCALL
+imaqGetPixelAddress(const Image* image, Point pixel);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetVisionInfoTypes(const Image* image, unsigned int* present);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsImageEmpty(const Image* image, int* empty);
+IMAQ_FUNC void* IMAQ_STDCALL
+imaqReadCustomData(const Image* image, const char* key, unsigned int* size);
+IMAQ_FUNC int IMAQ_STDCALL imaqRemoveCustomData(Image* image, const char* key);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqRemoveVisionInfo2(const Image* image, unsigned int info);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetBitDepth(Image* image, unsigned int bitDepth);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetImageSize(Image* image, int width, int height);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetMaskOffset(Image* image, Point offset);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteCustomData(Image* image, const char* key,
+                                               const void* data,
+                                               unsigned int size);
+
+//============================================================================
+//  Display functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqAreToolsContextSensitive(int* sensitive);
+IMAQ_FUNC int IMAQ_STDCALL imaqCloseWindow(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDisplayImage(const Image* image, int windowNumber, int resize);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetLastKey(char* keyPressed, int* windowNumber, int* modifiers);
+IMAQ_FUNC void* IMAQ_STDCALL imaqGetSystemWindowHandle(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowCenterPos(int windowNumber, Point* centerPosition);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetToolContextSensitivity(int sensitive);
+IMAQ_FUNC int IMAQ_STDCALL imaqShowWindow(int windowNumber, int visible);
+
+//============================================================================
+//  Image Manipulation functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCast(Image* dest, const Image* source,
+                                    ImageType type, const float* lookup,
+                                    int shift);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCopyRect(Image* dest, const Image* source, Rect rect, Point destLoc);
+IMAQ_FUNC int IMAQ_STDCALL imaqDuplicate(Image* dest, const Image* source);
+IMAQ_FUNC void* IMAQ_STDCALL imaqFlatten(const Image* image, FlattenType type,
+                                         CompressionType compression,
+                                         int quality, unsigned int* size);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFlip(Image* dest, const Image* source, FlipAxis axis);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMask(Image* dest, const Image* source, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqResample(Image* dest, const Image* source,
+                                        int newWidth, int newHeight,
+                                        InterpolationMethod method, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqRotate2(Image* dest, const Image* source, float angle, PixelValue fill,
+            InterpolationMethod method, int maintainSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqScale(Image* dest, const Image* source,
+                                     int xScale, int yScale,
+                                     ScalingMode scaleMode, Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqShift(Image* dest, const Image* source,
+                                     int shiftX, int shiftY, PixelValue fill);
+IMAQ_FUNC int IMAQ_STDCALL imaqTranspose(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqUnflatten(Image* image, const void* data, unsigned int size);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqUnwrapImage(Image* dest, const Image* source, Annulus annulus,
+                RectOrientation orientation, InterpolationMethod method);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqView3D(Image* dest, Image* source, const View3DOptions* options);
+
+//============================================================================
+//  File I/O functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCloseAVI(AVISession session);
+IMAQ_FUNC AVISession IMAQ_STDCALL
+imaqCreateAVI(const char* fileName, const char* compressionFilter, int quality,
+              unsigned int framesPerSecond, unsigned int maxDataSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetAVIInfo(AVISession session, AVIInfo* info);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetFileInfo(const char* fileName, CalibrationUnit* calibrationUnit,
+                float* calibrationX, float* calibrationY, int* width,
+                int* height, ImageType* imageType);
+IMAQ_FUNC FilterName* IMAQ_STDCALL imaqGetFilterNames(int* numFilters);
+IMAQ_FUNC char** IMAQ_STDCALL
+imaqLoadImagePopup(const char* defaultDirectory, const char* defaultFileSpec,
+                   const char* fileTypeList, const char* title,
+                   int allowMultiplePaths, ButtonLabel buttonLabel,
+                   int restrictDirectory, int restrictExtension,
+                   int allowCancel, int allowMakeDirectory, int* cancelled,
+                   int* numPaths);
+IMAQ_FUNC AVISession IMAQ_STDCALL imaqOpenAVI(const char* fileName);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadAVIFrame(Image* image, AVISession session,
+                                            unsigned int frameNum, void* data,
+                                            unsigned int* dataSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqReadFile(Image* image, const char* fileName,
+                                        RGBValue* colorTable, int* numColors);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqReadVisionFile(Image* image, const char* fileName, RGBValue* colorTable,
+                   int* numColors);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteAVIFrame(Image* image, AVISession session,
+                                             const void* data,
+                                             unsigned int dataLength);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteBMPFile(const Image* image,
+                                            const char* fileName, int compress,
+                                            const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteFile(const Image* image,
+                                         const char* fileName,
+                                         const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWriteJPEGFile(const Image* image, const char* fileName,
+                  unsigned int quality, void* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWriteJPEG2000File(const Image* image, const char* fileName, int lossless,
+                      float compressionRatio,
+                      const JPEG2000FileAdvancedOptions* advancedOptions,
+                      const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWritePNGFile2(const Image* image, const char* fileName,
+                  unsigned int compressionSpeed, const RGBValue* colorTable,
+                  int useBitDepth);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWriteTIFFFile(const Image* image, const char* fileName,
+                  const TIFFFileOptions* options, const RGBValue* colorTable);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteVisionFile(const Image* image,
+                                               const char* fileName,
+                                               const RGBValue* colorTable);
+
+//============================================================================
+//  Analytic Geometry functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqBuildCoordinateSystem(const Point* points, ReferenceMode mode,
+                          AxisOrientation orientation,
+                          CoordinateSystem* system);
+IMAQ_FUNC BestCircle2* IMAQ_STDCALL
+imaqFitCircle2(const PointFloat* points, int numPoints,
+               const FitCircleOptions* options);
+IMAQ_FUNC BestEllipse2* IMAQ_STDCALL
+imaqFitEllipse2(const PointFloat* points, int numPoints,
+                const FitEllipseOptions* options);
+IMAQ_FUNC BestLine* IMAQ_STDCALL imaqFitLine(const PointFloat* points,
+                                             int numPoints,
+                                             const FitLineOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetAngle(PointFloat start1, PointFloat end1,
+                                        PointFloat start2, PointFloat end2,
+                                        float* angle);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetBisectingLine(PointFloat start1, PointFloat end1, PointFloat start2,
+                     PointFloat end2, PointFloat* bisectStart,
+                     PointFloat* bisectEnd);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetDistance(PointFloat point1, PointFloat point2, float* distance);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetIntersection(PointFloat start1, PointFloat end1, PointFloat start2,
+                    PointFloat end2, PointFloat* intersection);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetMidLine(PointFloat refLineStart, PointFloat refLineEnd, PointFloat point,
+               PointFloat* midLineStart, PointFloat* midLineEnd);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetPerpendicularLine(PointFloat refLineStart, PointFloat refLineEnd,
+                         PointFloat point, PointFloat* perpLineStart,
+                         PointFloat* perpLineEnd, double* distance);
+IMAQ_FUNC SegmentInfo* IMAQ_STDCALL
+imaqGetPointsOnContour(const Image* image, int* numSegments);
+IMAQ_FUNC Point* IMAQ_STDCALL
+imaqGetPointsOnLine(Point start, Point end, int* numPoints);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetPolygonArea(const PointFloat* points, int numPoints, float* area);
+IMAQ_FUNC float* IMAQ_STDCALL
+imaqInterpolatePoints(const Image* image, const Point* points, int numPoints,
+                      InterpolationMethod method, int subpixel,
+                      int* interpCount);
+
+//============================================================================
+//  Clipboard functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqClipboardToImage(Image* dest, RGBValue* palette);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqImageToClipboard(const Image* image, const RGBValue* palette);
+
+//============================================================================
+//  Border functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqFillBorder(Image* image, BorderMethod method);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetBorderSize(const Image* image, int* borderSize);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetBorderSize(Image* image, int size);
+
+//============================================================================
+//  Image Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqArrayToImage(Image* image, const void* array, int numCols, int numRows);
+IMAQ_FUNC Image* IMAQ_STDCALL imaqCreateImage(ImageType type, int borderSize);
+IMAQ_FUNC void* IMAQ_STDCALL
+imaqImageToArray(const Image* image, Rect rect, int* columns, int* rows);
+
+//============================================================================
+//  Color Processing functions
+//============================================================================
+IMAQ_FUNC Color2 IMAQ_STDCALL
+imaqChangeColorSpace2(const Color2* sourceColor, ColorMode sourceSpace,
+                      ColorMode destSpace, double offset,
+                      const CIEXYZValue* whiteReference);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqColorBCGTransform(Image* dest, const Image* source,
+                      const BCGOptions* redOptions,
+                      const BCGOptions* greenOptions,
+                      const BCGOptions* blueOptions, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqColorEqualize(Image* dest, const Image* source, int colorEqualization);
+IMAQ_FUNC ColorHistogramReport* IMAQ_STDCALL
+imaqColorHistogram2(Image* image, int numClasses, ColorMode mode,
+                    const CIEXYZValue* whiteReference, Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqColorLookup(Image* dest, const Image* source, ColorMode mode,
+                const Image* mask, const short* plane1, const short* plane2,
+                const short* plane3);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqColorThreshold(Image* dest, const Image* source, int replaceValue,
+                   ColorMode mode, const Range* plane1Range,
+                   const Range* plane2Range, const Range* plane3Range);
+IMAQ_FUNC SupervisedColorSegmentationReport* IMAQ_STDCALL
+imaqSupervisedColorSegmentation(ClassifierSession* session, Image* labelImage,
+                                const Image* srcImage, const ROI* roi,
+                                const ROILabel* labelIn,
+                                unsigned int numLabelIn, int maxDistance,
+                                int minIdentificationScore,
+                                const ColorSegmenationOptions* segmentOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetColorSegmentationMaxDistance(
+    ClassifierSession* session, const ColorSegmenationOptions* segmentOptions,
+    SegmentationDistanceLevel distLevel, int* maxDistance);
+
+//============================================================================
+//  Transform functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqBCGTransform(Image* dest, const Image* source,
+                                            const BCGOptions* options,
+                                            const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqEqualize(Image* dest, const Image* source,
+                                        float min, float max,
+                                        const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqInverse(Image* dest, const Image* source, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL imaqMathTransform(Image* dest, const Image* source,
+                                             MathTransformMethod method,
+                                             float rangeMin, float rangeMax,
+                                             float power, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWatershedTransform(Image* dest, const Image* source, int connectivity8,
+                       int* zoneCount);
+IMAQ_FUNC int IMAQ_STDCALL imaqLookup2(Image* dest, const Image* source,
+                                       const int* table, const Image* mask);
+
+//============================================================================
+//  Window Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAreScrollbarsVisible(int windowNumber, int* visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqBringWindowToTop(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetMousePos(Point* position, int* windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowBackground(int windowNumber, WindowBackgroundFillStyle* fillStyle,
+                        WindowBackgroundHatchStyle* hatchStyle,
+                        RGBValue* fillColor, RGBValue* backgroundColor);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowDisplayMapping(int windowNum, DisplayMapping* mapping);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowGrid(int windowNumber, int* xResolution, int* yResolution);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowHandle(int* handle);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetWindowPos(int windowNumber, Point* position);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowSize(int windowNumber, int* width, int* height);
+IMAQ_FUNC char* IMAQ_STDCALL imaqGetWindowTitle(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowZoom2(int windowNumber, float* xZoom, float* yZoom);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqIsWindowNonTearing(int windowNumber, int* nonTearing);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsWindowVisible(int windowNumber, int* visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqMoveWindow(int windowNumber, Point position);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetupWindow(int windowNumber, int configuration);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowBackground(int windowNumber, WindowBackgroundFillStyle fillStyle,
+                        WindowBackgroundHatchStyle hatchStyle,
+                        const RGBValue* fillColor,
+                        const RGBValue* backgroundColor);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowDisplayMapping(int windowNumber, const DisplayMapping* mapping);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowGrid(int windowNumber, int xResolution, int yResolution);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowMaxContourCount(int windowNumber, unsigned int maxContourCount);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowNonTearing(int windowNumber, int nonTearing);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowPalette(int windowNumber, PaletteType type,
+                     const RGBValue* palette, int numColors);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowSize(int windowNumber, int width, int height);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowThreadPolicy(WindowThreadPolicy policy);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowTitle(int windowNumber, const char* title);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowZoomToFit(int windowNumber, int zoomToFit);
+IMAQ_FUNC int IMAQ_STDCALL imaqShowScrollbars(int windowNumber, int visible);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqZoomWindow2(int windowNumber, float xZoom, float yZoom, Point center);
+
+//============================================================================
+//  Utilities functions
+//============================================================================
+IMAQ_FUNC const float* IMAQ_STDCALL
+imaqGetKernel(KernelFamily family, int size, int number);
+IMAQ_FUNC Annulus IMAQ_STDCALL
+imaqMakeAnnulus(Point center, int innerRadius, int outerRadius,
+                double startAngle, double endAngle);
+IMAQ_FUNC Point IMAQ_STDCALL imaqMakePoint(int xCoordinate, int yCoordinate);
+IMAQ_FUNC PointFloat IMAQ_STDCALL
+imaqMakePointFloat(float xCoordinate, float yCoordinate);
+IMAQ_FUNC Rect IMAQ_STDCALL
+imaqMakeRect(int top, int left, int height, int width);
+IMAQ_FUNC Rect IMAQ_STDCALL
+imaqMakeRectFromRotatedRect(RotatedRect rotatedRect);
+IMAQ_FUNC RotatedRect IMAQ_STDCALL
+imaqMakeRotatedRect(int top, int left, int height, int width, double angle);
+IMAQ_FUNC RotatedRect IMAQ_STDCALL imaqMakeRotatedRectFromRect(Rect rect);
+IMAQ_FUNC int IMAQ_STDCALL imaqMulticoreOptions(MulticoreOperation operation,
+                                                unsigned int* customNumCores);
+
+//============================================================================
+//  Tool Window functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqCloseToolWindow(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetCurrentTool(Tool* currentTool);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetLastEvent(WindowEventType* type,
+                                            int* windowNumber, Tool* tool,
+                                            Rect* rect);
+IMAQ_FUNC void* IMAQ_STDCALL imaqGetToolWindowHandle(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetToolWindowPos(Point* position);
+IMAQ_FUNC int IMAQ_STDCALL imaqIsToolWindowVisible(int* visible);
+IMAQ_FUNC int IMAQ_STDCALL imaqMoveToolWindow(Point position);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetCurrentTool(Tool currentTool);
+#ifndef __GNUC__
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetEventCallback(EventCallback callback, int synchronous);
+#endif
+IMAQ_FUNC int IMAQ_STDCALL imaqSetToolColor(const RGBValue* color);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetupToolWindow(int showCoordinates, int maxIconsPerLine,
+                    const ToolWindowOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqShowToolWindow(int visible);
+
+//============================================================================
+//  Meter functions
+//============================================================================
+IMAQ_FUNC MeterArc* IMAQ_STDCALL
+imaqGetMeterArc(int lightNeedle, MeterArcMode mode, const ROI* roi,
+                PointFloat base, PointFloat start, PointFloat end);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqReadMeter(const Image* image, const MeterArc* arcInfo, double* percentage,
+              PointFloat* endOfNeedle);
+
+//============================================================================
+//  Calibration functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCopyCalibrationInfo2(Image* dest, Image* source, Point offset);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCorrectCalibratedImage(Image* dest, const Image* source, PixelValue fill,
+                           InterpolationMethod method, const ROI* roi);
+IMAQ_FUNC CalibrationInfo* IMAQ_STDCALL
+imaqGetCalibrationInfo2(const Image* image);
+IMAQ_FUNC CalibrationInfo* IMAQ_STDCALL
+imaqGetCalibrationInfo3(Image* image, unsigned int isGetErrorMap);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLearnCalibrationGrid(Image* image, const ROI* roi,
+                         const LearnCalibrationOptions* options,
+                         const GridDescriptor* grid,
+                         const CoordinateSystem* system,
+                         const RangeFloat* range, float* quality);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLearnCalibrationPoints(Image* image, const CalibrationPoints* points,
+                           const ROI* roi,
+                           const LearnCalibrationOptions* options,
+                           const GridDescriptor* grid,
+                           const CoordinateSystem* system, float* quality);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetCoordinateSystem(Image* image, const CoordinateSystem* system);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetSimpleCalibration(Image* image, ScalingMethod method, int learnTable,
+                         const GridDescriptor* grid,
+                         const CoordinateSystem* system);
+IMAQ_FUNC TransformReport* IMAQ_STDCALL
+imaqTransformPixelToRealWorld(const Image* image,
+                              const PointFloat* pixelCoordinates,
+                              int numCoordinates);
+IMAQ_FUNC TransformReport* IMAQ_STDCALL
+imaqTransformRealWorldToPixel(const Image* image,
+                              const PointFloat* realWorldCoordinates,
+                              int numCoordinates);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetSimpleCalibration2(Image* image, const GridDescriptor* gridDescriptor);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCalibrationSetAxisInfo(Image* image, CoordinateSystem* axisInfo);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCalibrationGetThumbnailImage(Image* templateImage, Image* image,
+                                 CalibrationThumbnailType type,
+                                 unsigned int index);
+IMAQ_FUNC GetCalibrationInfoReport* IMAQ_STDCALL
+imaqCalibrationGetCalibrationInfo(Image* image, unsigned int isGetErrorMap);
+IMAQ_FUNC GetCameraParametersReport* IMAQ_STDCALL
+imaqCalibrationGetCameraParameters(Image* templateImage);
+IMAQ_FUNC int IMAQ_STDCALL imaqCalibrationCompactInformation(Image* image);
+
+//============================================================================
+//  Pixel Manipulation functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqArrayToComplexPlane(Image* dest, const Image* source,
+                        const float* newPixels, ComplexPlane plane);
+IMAQ_FUNC float* IMAQ_STDCALL
+imaqComplexPlaneToArray(const Image* image, ComplexPlane plane, Rect rect,
+                        int* rows, int* columns);
+IMAQ_FUNC int IMAQ_STDCALL imaqExtractColorPlanes(const Image* image,
+                                                  ColorMode mode, Image* plane1,
+                                                  Image* plane2, Image* plane3);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqExtractComplexPlane(Image* dest, const Image* source, ComplexPlane plane);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFillImage(Image* image, PixelValue value, const Image* mask);
+IMAQ_FUNC void* IMAQ_STDCALL
+imaqGetLine(const Image* image, Point start, Point end, int* numPoints);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetPixel(const Image* image, Point pixel, PixelValue* value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqReplaceColorPlanes(Image* dest, const Image* source, ColorMode mode,
+                       const Image* plane1, const Image* plane2,
+                       const Image* plane3);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqReplaceComplexPlane(Image* dest, const Image* source,
+                        const Image* newValues, ComplexPlane plane);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetLine(Image* image, const void* array,
+                                       int arraySize, Point start, Point end);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetPixel(Image* image, Point coord, PixelValue value);
+
+//============================================================================
+//  Color Matching functions
+//============================================================================
+IMAQ_FUNC ColorInformation* IMAQ_STDCALL
+imaqLearnColor(const Image* image, const ROI* roi, ColorSensitivity sensitivity,
+               int saturation);
+IMAQ_FUNC int* IMAQ_STDCALL imaqMatchColor(const Image* image,
+                                           const ColorInformation* info,
+                                           const ROI* roi, int* numScores);
+
+//============================================================================
+//  Frequency Domain Analysis functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAttenuate(Image* dest, const Image* source, AttenuateMode highlow);
+IMAQ_FUNC int IMAQ_STDCALL imaqConjugate(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqFFT(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFlipFrequencies(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqInverseFFT(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL imaqTruncate(Image* dest, const Image* source,
+                                        TruncateMode highlow,
+                                        float ratioToKeep);
+
+//============================================================================
+//  Barcode I/O functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGradeDataMatrixBarcodeAIM(const Image* image, AIMGradeReport* report);
+IMAQ_FUNC BarcodeInfo* IMAQ_STDCALL
+imaqReadBarcode(const Image* image, BarcodeType type, const ROI* roi,
+                int validate);
+IMAQ_FUNC DataMatrixReport* IMAQ_STDCALL imaqReadDataMatrixBarcode2(
+    Image* image, const ROI* roi, DataMatrixGradingMode prepareForGrading,
+    const DataMatrixDescriptionOptions* descriptionOptions,
+    const DataMatrixSizeOptions* sizeOptions,
+    const DataMatrixSearchOptions* searchOptions);
+IMAQ_FUNC Barcode2DInfo* IMAQ_STDCALL
+imaqReadPDF417Barcode(const Image* image, const ROI* roi,
+                      Barcode2DSearchMode searchMode,
+                      unsigned int* numBarcodes);
+IMAQ_FUNC QRCodeReport* IMAQ_STDCALL
+imaqReadQRCode(Image* image, const ROI* roi, QRGradingMode reserved,
+               const QRCodeDescriptionOptions* descriptionOptions,
+               const QRCodeSizeOptions* sizeOptions,
+               const QRCodeSearchOptions* searchOptions);
+
+//============================================================================
+//  LCD functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFindLCDSegments(ROI* roi, const Image* image, const LCDOptions* options);
+IMAQ_FUNC LCDReport* IMAQ_STDCALL
+imaqReadLCD(const Image* image, const ROI* roi, const LCDOptions* options);
+
+//============================================================================
+//  Shape Matching functions
+//============================================================================
+IMAQ_FUNC ShapeReport* IMAQ_STDCALL
+imaqMatchShape(Image* dest, Image* source, const Image* templateImage,
+               int scaleInvariant, int connectivity8, double tolerance,
+               int* numMatches);
+
+//============================================================================
+//  Contours functions
+//============================================================================
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqAddAnnulusContour(ROI* roi, Annulus annulus);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqAddClosedContour(ROI* roi, const Point* points, int numPoints);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqAddLineContour(ROI* roi, Point start, Point end);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqAddOpenContour(ROI* roi, const Point* points, int numPoints);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddOvalContour(ROI* roi, Rect boundingBox);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddPointContour(ROI* roi, Point point);
+IMAQ_FUNC ContourID IMAQ_STDCALL imaqAddRectContour(ROI* roi, Rect rect);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqAddRotatedRectContour2(ROI* roi, RotatedRect rect);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqCopyContour(ROI* destRoi, const ROI* sourceRoi, ContourID id);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqGetContour(const ROI* roi, unsigned int index);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetContourColor(const ROI* roi, ContourID id, RGBValue* contourColor);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetContourCount(const ROI* roi);
+IMAQ_FUNC ContourInfo2* IMAQ_STDCALL
+imaqGetContourInfo2(const ROI* roi, ContourID id);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMoveContour(ROI* roi, ContourID id, int deltaX, int deltaY);
+IMAQ_FUNC int IMAQ_STDCALL imaqRemoveContour(ROI* roi, ContourID id);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetContourColor(ROI* roi, ContourID id, const RGBValue* color);
+
+//============================================================================
+//  Regions of Interest functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqConstructROI2(const Image* image, ROI* roi, Tool initialTool,
+                  const ToolWindowOptions* tools,
+                  const ConstructROIOptions2* options, int* okay);
+IMAQ_FUNC ROI* IMAQ_STDCALL imaqCreateROI(void);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetROIBoundingBox(const ROI* roi, Rect* boundingBox);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetROIColor(const ROI* roi, RGBValue* roiColor);
+IMAQ_FUNC ROI* IMAQ_STDCALL imaqGetWindowROI(int windowNumber);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetROIColor(ROI* roi, const RGBValue* color);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetWindowROI(int windowNumber, const ROI* roi);
+
+//============================================================================
+//  Image Analysis functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCentroid(const Image* image, PointFloat* centroid, const Image* mask);
+IMAQ_FUNC Curve* IMAQ_STDCALL
+imaqExtractCurves(const Image* image, const ROI* roi,
+                  const CurveOptions* curveOptions, unsigned int* numCurves);
+IMAQ_FUNC HistogramReport* IMAQ_STDCALL
+imaqHistogram(const Image* image, int numClasses, float min, float max,
+              const Image* mask);
+IMAQ_FUNC LinearAverages* IMAQ_STDCALL
+imaqLinearAverages2(Image* image, LinearAveragesMode mode, Rect rect);
+IMAQ_FUNC LineProfile* IMAQ_STDCALL
+imaqLineProfile(const Image* image, Point start, Point end);
+IMAQ_FUNC QuantifyReport* IMAQ_STDCALL
+imaqQuantify(const Image* image, const Image* mask);
+
+//============================================================================
+//  Error Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqClearError(void);
+IMAQ_FUNC char* IMAQ_STDCALL imaqGetErrorText(int errorCode);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetLastError(void);
+IMAQ_FUNC const char* IMAQ_STDCALL imaqGetLastErrorFunc(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetError(int errorCode, const char* function);
+
+//============================================================================
+//  Threshold functions
+//============================================================================
+IMAQ_FUNC ThresholdData* IMAQ_STDCALL
+imaqAutoThreshold2(Image* dest, const Image* source, int numClasses,
+                   ThresholdMethod method, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLocalThreshold(Image* dest, const Image* source, unsigned int windowWidth,
+                   unsigned int windowHeight, LocalThresholdMethod method,
+                   double deviationWeight, ObjectType type, float replaceValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqMagicWand(Image* dest, const Image* source,
+                                         Point coord, float tolerance,
+                                         int connectivity8, float replaceValue);
+IMAQ_FUNC int IMAQ_STDCALL imaqMultithreshold(Image* dest, const Image* source,
+                                              const ThresholdData* ranges,
+                                              int numRanges);
+IMAQ_FUNC int IMAQ_STDCALL imaqThreshold(Image* dest, const Image* source,
+                                         float rangeMin, float rangeMax,
+                                         int useNewValue, float newValue);
+
+//============================================================================
+//  Memory Management functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqDispose(void* object);
+
+//============================================================================
+//  Pattern Matching functions
+//============================================================================
+IMAQ_FUNC CircleMatch* IMAQ_STDCALL
+imaqDetectCircles(const Image* image, const CircleDescriptor* circleDescriptor,
+                  const CurveOptions* curveOptions,
+                  const ShapeDetectionOptions* shapeDetectionOptions,
+                  const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC EllipseMatch* IMAQ_STDCALL
+imaqDetectEllipses(const Image* image,
+                   const EllipseDescriptor* ellipseDescriptor,
+                   const CurveOptions* curveOptions,
+                   const ShapeDetectionOptions* shapeDetectionOptions,
+                   const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC LineMatch* IMAQ_STDCALL
+imaqDetectLines(const Image* image, const LineDescriptor* lineDescriptor,
+                const CurveOptions* curveOptions,
+                const ShapeDetectionOptions* shapeDetectionOptions,
+                const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC RectangleMatch* IMAQ_STDCALL
+imaqDetectRectangles(const Image* image,
+                     const RectangleDescriptor* rectangleDescriptor,
+                     const CurveOptions* curveOptions,
+                     const ShapeDetectionOptions* shapeDetectionOptions,
+                     const ROI* roi, int* numMatchesReturned);
+IMAQ_FUNC FeatureData* IMAQ_STDCALL
+imaqGetGeometricFeaturesFromCurves(const Curve* curves, unsigned int numCurves,
+                                   const FeatureType* featureTypes,
+                                   unsigned int numFeatureTypes,
+                                   unsigned int* numFeatures);
+IMAQ_FUNC FeatureData* IMAQ_STDCALL
+imaqGetGeometricTemplateFeatureInfo(const Image* pattern,
+                                    unsigned int* numFeatures);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLearnColorPattern(Image* image, const LearnColorPatternOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnGeometricPattern(
+    Image* image, PointFloat originOffset, const CurveOptions* curveOptions,
+    const LearnGeometricPatternAdvancedOptions* advancedLearnOptions,
+    const Image* mask);
+IMAQ_FUNC MultipleGeometricPattern* IMAQ_STDCALL
+imaqLearnMultipleGeometricPatterns(const Image** patterns,
+                                   unsigned int numberOfPatterns,
+                                   const String255* labels);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLearnPattern3(Image* image, LearningMode learningMode,
+                  LearnPatternAdvancedOptions* advancedOptions,
+                  const Image* mask);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL
+imaqMatchColorPattern(const Image* image, Image* pattern,
+                      const MatchColorPatternOptions* options, Rect searchRect,
+                      int* numMatches);
+IMAQ_FUNC GeometricPatternMatch2* IMAQ_STDCALL imaqMatchGeometricPattern2(
+    const Image* image, const Image* pattern, const CurveOptions* curveOptions,
+    const MatchGeometricPatternOptions* matchOptions,
+    const MatchGeometricPatternAdvancedOptions2* advancedMatchOptions,
+    const ROI* roi, int* numMatches);
+IMAQ_FUNC GeometricPatternMatch2* IMAQ_STDCALL
+imaqMatchMultipleGeometricPatterns(
+    const Image* image, const MultipleGeometricPattern* multiplePattern,
+    const ROI* roi, int* numMatches);
+IMAQ_FUNC MultipleGeometricPattern* IMAQ_STDCALL
+imaqReadMultipleGeometricPatternFile(const char* fileName,
+                                     String255 description);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL
+imaqRefineMatches(const Image* image, const Image* pattern,
+                  const PatternMatch* candidatesIn, int numCandidatesIn,
+                  MatchPatternOptions* options,
+                  MatchPatternAdvancedOptions* advancedOptions,
+                  int* numCandidatesOut);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetMultipleGeometricPatternsOptions(
+    MultipleGeometricPattern* multiplePattern, const char* label,
+    const CurveOptions* curveOptions,
+    const MatchGeometricPatternOptions* matchOptions,
+    const MatchGeometricPatternAdvancedOptions2* advancedMatchOptions);
+IMAQ_FUNC int IMAQ_STDCALL imaqWriteMultipleGeometricPatternFile(
+    const MultipleGeometricPattern* multiplePattern, const char* fileName,
+    const char* description);
+IMAQ_FUNC GeometricPatternMatch3* IMAQ_STDCALL imaqMatchGeometricPattern3(
+    const Image* image, const Image* pattern, const CurveOptions* curveOptions,
+    const MatchGeometricPatternOptions* matchOptions,
+    const MatchGeometricPatternAdvancedOptions3* advancedMatchOptions,
+    const ROI* roi, size_t* numMatches);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnGeometricPattern2(
+    Image* image, PointFloat originOffset, double angleOffset,
+    const CurveOptions* curveOptions,
+    const LearnGeometricPatternAdvancedOptions2* advancedLearnOptions,
+    const Image* mask);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL
+imaqMatchPattern3(const Image* image, const Image* pattern,
+                  const MatchPatternOptions* options,
+                  const MatchPatternAdvancedOptions* advancedOptions,
+                  const ROI* roi, int* numMatches);
+
+//============================================================================
+//  Overlay functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqClearOverlay(Image* image, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCopyOverlay(Image* dest, const Image* source, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetOverlayProperties(const Image* image, const char* group,
+                         TransformBehaviors* transformBehaviors);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMergeOverlay(Image* dest, const Image* source, const RGBValue* palette,
+                 unsigned int numColors, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayArc(Image* image, const ArcInfo* arc,
+                                          const RGBValue* color,
+                                          DrawMode drawMode, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayBitmap(Image* image, Point destLoc, const RGBValue* bitmap,
+                  unsigned int numCols, unsigned int numRows,
+                  const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayClosedContour(Image* image, const Point* points, int numPoints,
+                         const RGBValue* color, DrawMode drawMode,
+                         const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayLine(Image* image, Point start, Point end,
+                                           const RGBValue* color,
+                                           const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayMetafile(Image* image,
+                                               const void* metafile, Rect rect,
+                                               const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayOpenContour(Image* image, const Point* points, int numPoints,
+                       const RGBValue* color, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL imaqOverlayOval(Image* image, Rect boundingBox,
+                                           const RGBValue* color,
+                                           DrawMode drawMode, char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayPoints(Image* image, const Point* points, int numPoints,
+                  const RGBValue* colors, int numColors, PointSymbol symbol,
+                  const UserPointSymbol* userSymbol, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayRect(Image* image, Rect rect, const RGBValue* color,
+                DrawMode drawMode, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayROI(Image* image, const ROI* roi, PointSymbol symbol,
+               const UserPointSymbol* userSymbol, const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqOverlayText(Image* image, Point origin, const char* text,
+                const RGBValue* color, const OverlayTextOptions* options,
+                const char* group);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetOverlayProperties(Image* image, const char* group,
+                         TransformBehaviors* transformBehaviors);
+
+//============================================================================
+//  OCR functions
+//============================================================================
+IMAQ_FUNC CharSet* IMAQ_STDCALL imaqCreateCharSet(void);
+IMAQ_FUNC int IMAQ_STDCALL imaqDeleteChar(CharSet* set, int index);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetCharCount(const CharSet* set);
+IMAQ_FUNC CharInfo2* IMAQ_STDCALL
+imaqGetCharInfo2(const CharSet* set, int index);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqReadOCRFile(const char* fileName, CharSet* set, String255 setDescription,
+                ReadTextOptions* readOptions,
+                OCRProcessingOptions* processingOptions,
+                OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC ReadTextReport3* IMAQ_STDCALL
+imaqReadText3(const Image* image, const CharSet* set, const ROI* roi,
+              const ReadTextOptions* readOptions,
+              const OCRProcessingOptions* processingOptions,
+              const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqRenameChar(CharSet* set, int index, const char* newCharValue);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetReferenceChar(const CharSet* set, int index, int isReferenceChar);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqTrainChars(const Image* image, CharSet* set, int index,
+               const char* charValue, const ROI* roi,
+               const OCRProcessingOptions* processingOptions,
+               const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC int* IMAQ_STDCALL
+imaqVerifyPatterns(const Image* image, const CharSet* set,
+                   const String255* expectedPatterns, int patternCount,
+                   const ROI* roi, int* numScores);
+IMAQ_FUNC int* IMAQ_STDCALL
+imaqVerifyText(const Image* image, const CharSet* set,
+               const char* expectedString, const ROI* roi, int* numScores);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWriteOCRFile(const char* fileName, const CharSet* set,
+                 const char* setDescription, const ReadTextOptions* readOptions,
+                 const OCRProcessingOptions* processingOptions,
+                 const OCRSpacingOptions* spacingOptions);
+
+//============================================================================
+//  Geometric Matching functions
+//============================================================================
+IMAQ_FUNC ExtractContourReport* IMAQ_STDCALL
+imaqExtractContour(Image* image, const ROI* roi,
+                   ExtractContourDirection direction,
+                   CurveParameters* curveParams,
+                   const ConnectionConstraint* connectionConstraintParams,
+                   unsigned int numOfConstraints,
+                   ExtractContourSelection selection, Image* contourImage);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqContourOverlay(Image* image, const Image* contourImage,
+                   const ContourOverlaySettings* pointsSettings,
+                   const ContourOverlaySettings* eqnSettings,
+                   const char* groupName);
+IMAQ_FUNC ContourComputeCurvatureReport* IMAQ_STDCALL
+imaqContourComputeCurvature(const Image* contourImage, unsigned int kernel);
+IMAQ_FUNC CurvatureAnalysisReport* IMAQ_STDCALL
+imaqContourClassifyCurvature(const Image* contourImage, unsigned int kernel,
+                             RangeLabel* curvatureClasses,
+                             unsigned int numCurvatureClasses);
+IMAQ_FUNC ComputeDistancesReport* IMAQ_STDCALL
+imaqContourComputeDistances(const Image* targetImage,
+                            const Image* templateImage,
+                            const SetupMatchPatternData* matchSetupData,
+                            unsigned int smoothingKernel);
+IMAQ_FUNC ClassifyDistancesReport* IMAQ_STDCALL imaqContourClassifyDistances(
+    const Image* targetImage, const Image* templateImage,
+    const SetupMatchPatternData* matchSetupData, unsigned int smoothingKernel,
+    const RangeLabel* distanceRanges, unsigned int numDistanceRanges);
+IMAQ_FUNC ContourInfoReport* IMAQ_STDCALL
+imaqContourInfo(const Image* contourImage);
+IMAQ_FUNC SetupMatchPatternData* IMAQ_STDCALL imaqContourSetupMatchPattern(
+    MatchMode* matchMode, unsigned int enableSubPixelAccuracy,
+    CurveParameters* curveParams, unsigned int useLearnCurveParameters,
+    const RangeSettingDouble* rangeSettings, unsigned int numRangeSettings);
+IMAQ_FUNC int IMAQ_STDCALL imaqContourAdvancedSetupMatchPattern(
+    SetupMatchPatternData* matchSetupData,
+    GeometricAdvancedSetupDataOption* geometricOptions,
+    unsigned int numGeometricOptions);
+IMAQ_FUNC ContourFitLineReport* IMAQ_STDCALL
+imaqContourFitLine(Image* image, double pixelRadius);
+IMAQ_FUNC PartialCircle* IMAQ_STDCALL
+imaqContourFitCircle(Image* image, double pixelRadius, int rejectOutliers);
+IMAQ_FUNC PartialEllipse* IMAQ_STDCALL
+imaqContourFitEllipse(Image* image, double pixelRadius, int rejectOutliers);
+IMAQ_FUNC ContourFitSplineReport* IMAQ_STDCALL
+imaqContourFitSpline(Image* image, int degree, int numberOfControlPoints);
+IMAQ_FUNC ContourFitPolynomialReport* IMAQ_STDCALL
+imaqContourFitPolynomial(Image* image, int order);
+
+//============================================================================
+//  Edge Detection functions
+//============================================================================
+IMAQ_FUNC FindCircularEdgeReport* IMAQ_STDCALL
+imaqFindCircularEdge2(Image* image, const ROI* roi,
+                      const CoordinateSystem* baseSystem,
+                      const CoordinateSystem* newSystem,
+                      const FindCircularEdgeOptions* edgeOptions,
+                      const CircleFitOptions* circleFitOptions);
+IMAQ_FUNC FindConcentricEdgeReport* IMAQ_STDCALL imaqFindConcentricEdge2(
+    Image* image, const ROI* roi, const CoordinateSystem* baseSystem,
+    const CoordinateSystem* newSystem,
+    const FindConcentricEdgeOptions* edgeOptions,
+    const ConcentricEdgeFitOptions* concentricEdgeFitOptions);
+
+//============================================================================
+//  Morphology Reconstruction functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGrayMorphologyReconstruct(Image* dstImage, Image* srcImage,
+                              const Image* markerImage, PointFloat* points,
+                              int numOfPoints,
+                              MorphologyReconstructOperation operation,
+                              const StructuringElement* structuringElement,
+                              const ROI* roi);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqMorphologyReconstruct(Image* dstImage, Image* srcImage,
+                          const Image* markerImage, PointFloat* points,
+                          int numOfPoints,
+                          MorphologyReconstructOperation operation,
+                          Connectivity connectivity, const ROI* roi);
+
+//============================================================================
+//  Texture functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDetectTextureDefect(ClassifierSession* session, Image* destImage,
+                        const Image* srcImage, const ROI* roi,
+                        int initialStepSize, int finalStepSize,
+                        unsigned char defectPixelValue,
+                        double minClassificationScore);
+IMAQ_FUNC int IMAQ_STDCALL imaqClassificationTextureDefectOptions(
+    ClassifierSession* session, WindowSize* windowOptions,
+    WaveletOptions* waveletOptions, void** bandsUsed, int* numBandsUsed,
+    CooccurrenceOptions* cooccurrenceOptions, unsigned char setOperation);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCooccurrenceMatrix(const Image* srcImage, const ROI* roi, int levelPixel,
+                       const DisplacementVector* displacementVec,
+                       void* featureOptionArray,
+                       unsigned int featureOptionArraySize,
+                       void** cooccurrenceMatrixArray,
+                       int* coocurrenceMatrixRows, int* coocurrenceMatrixCols,
+                       void** featureVectorArray, int* featureVectorArraySize);
+IMAQ_FUNC ExtractTextureFeaturesReport* IMAQ_STDCALL
+imaqExtractTextureFeatures(const Image* srcImage, const ROI* roi,
+                           const WindowSize* windowOptions,
+                           const WaveletOptions* waveletOptions,
+                           void* waveletBands, unsigned int numWaveletBands,
+                           const CooccurrenceOptions* cooccurrenceOptions,
+                           unsigned char useWindow);
+IMAQ_FUNC WaveletBandsReport* IMAQ_STDCALL
+imaqExtractWaveletBands(const Image* srcImage,
+                        const WaveletOptions* waveletOptions,
+                        void* waveletBands, unsigned int numWaveletBands);
+
+//============================================================================
+//  Regions of Interest Manipulation functions
+//============================================================================
+IMAQ_FUNC ROI* IMAQ_STDCALL imaqMaskToROI(const Image* mask, int* withinLimit);
+IMAQ_FUNC ROIProfile* IMAQ_STDCALL
+imaqROIProfile(const Image* image, const ROI* roi);
+IMAQ_FUNC int IMAQ_STDCALL imaqROIToMask(Image* mask, const ROI* roi,
+                                         int fillValue, const Image* imageModel,
+                                         int* inSpace);
+IMAQ_FUNC int IMAQ_STDCALL imaqTransformROI2(ROI* roi,
+                                             const CoordinateSystem* baseSystem,
+                                             const CoordinateSystem* newSystem);
+IMAQ_FUNC LabelToROIReport* IMAQ_STDCALL
+imaqLabelToROI(const Image* image, const unsigned int* labelsIn,
+               unsigned int numLabelsIn, int maxNumVectors,
+               int isExternelEdges);
+
+//============================================================================
+//  Morphology functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGrayMorphology(Image* dest, Image* source, MorphologyMethod method,
+                   const StructuringElement* structuringElement);
+
+//============================================================================
+//  Classification functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqAddClassifierSample(Image* image, ClassifierSession* session,
+                        const ROI* roi, const char* sampleClass,
+                        double* featureVector, unsigned int vectorSize);
+IMAQ_FUNC ClassifierReportAdvanced* IMAQ_STDCALL
+imaqAdvanceClassify(Image* image, const ClassifierSession* session,
+                    const ROI* roi, double* featureVector,
+                    unsigned int vectorSize);
+IMAQ_FUNC ClassifierReport* IMAQ_STDCALL
+imaqClassify(Image* image, const ClassifierSession* session, const ROI* roi,
+             double* featureVector, unsigned int vectorSize);
+IMAQ_FUNC ClassifierSession* IMAQ_STDCALL
+imaqCreateClassifier(ClassifierType type);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDeleteClassifierSample(ClassifierSession* session, int index);
+IMAQ_FUNC ClassifierAccuracyReport* IMAQ_STDCALL
+imaqGetClassifierAccuracy(const ClassifierSession* session);
+IMAQ_FUNC ClassifierSampleInfo* IMAQ_STDCALL
+imaqGetClassifierSampleInfo(const ClassifierSession* session, int index,
+                            int* numSamples);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetColorClassifierOptions(const ClassifierSession* session,
+                              ColorOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetNearestNeighborOptions(const ClassifierSession* session,
+                              NearestNeighborOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetParticleClassifierOptions2(
+    const ClassifierSession* session,
+    ParticleClassifierPreprocessingOptions2* preprocessingOptions,
+    ParticleClassifierOptions* options);
+IMAQ_FUNC ClassifierSession* IMAQ_STDCALL
+imaqReadClassifierFile(ClassifierSession* session, const char* fileName,
+                       ReadClassifierFileMode mode, ClassifierType* type,
+                       ClassifierEngineType* engine, String255 description);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqRelabelClassifierSample(ClassifierSession* session, int index,
+                            const char* newClass);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetParticleClassifierOptions2(
+    ClassifierSession* session,
+    const ParticleClassifierPreprocessingOptions2* preprocessingOptions,
+    const ParticleClassifierOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetColorClassifierOptions(ClassifierSession* session,
+                              const ColorOptions* options);
+IMAQ_FUNC NearestNeighborTrainingReport* IMAQ_STDCALL
+imaqTrainNearestNeighborClassifier(ClassifierSession* session,
+                                   const NearestNeighborOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWriteClassifierFile(const ClassifierSession* session, const char* fileName,
+                        WriteClassifierFileMode mode,
+                        const String255 description);
+
+//============================================================================
+//  Measure Distances functions
+//============================================================================
+IMAQ_FUNC ClampMax2Report* IMAQ_STDCALL
+imaqClampMax2(Image* image, const ROI* roi, const CoordinateSystem* baseSystem,
+              const CoordinateSystem* newSystem,
+              const CurveOptions* curveSettings,
+              const ClampSettings* clampSettings,
+              const ClampOverlaySettings* clampOverlaySettings);
+
+//============================================================================
+//  Inspection functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCompareGoldenTemplate(const Image* image, const Image* goldenTemplate,
+                          Image* brightDefects, Image* darkDefects,
+                          const InspectionAlignment* alignment,
+                          const InspectionOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL imaqLearnGoldenTemplate(Image* goldenTemplate,
+                                                   PointFloat originOffset,
+                                                   const Image* mask);
+//============================================================================
+//  Obsolete functions
+//============================================================================
+IMAQ_FUNC int IMAQ_STDCALL imaqRotate(Image* dest, const Image* source,
+                                      float angle, PixelValue fill,
+                                      InterpolationMethod method);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqWritePNGFile(const Image* image, const char* fileName,
+                 unsigned int compressionSpeed, const RGBValue* colorTable);
+IMAQ_FUNC ParticleReport* IMAQ_STDCALL
+imaqSelectParticles(const Image* image, const ParticleReport* reports,
+                    int reportCount, int rejectBorder,
+                    const SelectParticleCriteria* criteria, int criteriaCount,
+                    int* selectedCount);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqParticleFilter(Image* dest, Image* source,
+                   const ParticleFilterCriteria* criteria, int criteriaCount,
+                   int rejectMatches, int connectivity8);
+IMAQ_FUNC ParticleReport* IMAQ_STDCALL
+imaqGetParticleInfo(Image* image, int connectivity8, ParticleInfoMode mode,
+                    int* reportCount);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCalcCoeff(const Image* image, const ParticleReport* report,
+              MeasurementValue parameter, float* coefficient);
+IMAQ_FUNC EdgeReport* IMAQ_STDCALL
+imaqEdgeTool(const Image* image, const Point* points, int numPoints,
+             const EdgeOptions* options, int* numEdges);
+IMAQ_FUNC CircleReport* IMAQ_STDCALL
+imaqCircles(Image* dest, const Image* source, float minRadius, float maxRadius,
+            int* numCircles);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLabel(Image* dest, Image* source, int connectivity8, int* particleCount);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFitEllipse(const PointFloat* points, int numPoints, BestEllipse* ellipse);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqFitCircle(const PointFloat* points, int numPoints, BestCircle* circle);
+IMAQ_FUNC Color IMAQ_STDCALL imaqChangeColorSpace(const Color* sourceColor,
+                                                  ColorMode sourceSpace,
+                                                  ColorMode destSpace);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL
+imaqMatchPattern(const Image* image, Image* pattern,
+                 const MatchPatternOptions* options, Rect searchRect,
+                 int* numMatches);
+IMAQ_FUNC int IMAQ_STDCALL imaqConvex(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqIsVisionInfoPresent(const Image* image, VisionInfoType type, int* present);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLineGaugeTool(const Image* image, Point start, Point end,
+                  LineGaugeMethod method, const EdgeOptions* edgeOptions,
+                  const CoordinateTransform* reference, float* distance);
+IMAQ_FUNC int IMAQ_STDCALL imaqBestCircle(const PointFloat* points,
+                                          int numPoints, PointFloat* center,
+                                          double* radius);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSavePattern(const Image* pattern, const char* fileName);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLoadPattern(Image* pattern, const char* fileName);
+IMAQ_FUNC int IMAQ_STDCALL imaqTransformROI(ROI* roi, Point originStart,
+                                            float angleStart, Point originFinal,
+                                            float angleFinal);
+IMAQ_FUNC int IMAQ_STDCALL imaqCoordinateReference(const Point* points,
+                                                   ReferenceMode mode,
+                                                   Point* origin, float* angle);
+IMAQ_FUNC ContourInfo* IMAQ_STDCALL
+imaqGetContourInfo(const ROI* roi, ContourID id);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetWindowOverlay(int windowNumber, const Overlay* overlay);
+IMAQ_FUNC Overlay* IMAQ_STDCALL imaqCreateOverlayFromROI(const ROI* roi);
+IMAQ_FUNC Overlay* IMAQ_STDCALL
+imaqCreateOverlayFromMetafile(const void* metafile);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqSetCalibrationInfo(Image* image, CalibrationUnit unit, float xDistance,
+                       float yDistance);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetCalibrationInfo(const Image* image, CalibrationUnit* unit,
+                       float* xDistance, float* yDistance);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqConstructROI(const Image* image, ROI* roi, Tool initialTool,
+                 const ToolWindowOptions* tools,
+                 const ConstructROIOptions* options, int* okay);
+IMAQ_FUNC int IMAQ_STDCALL imaqGetParticleClassifierOptions(
+    const ClassifierSession* session,
+    ParticleClassifierPreprocessingOptions* preprocessingOptions,
+    ParticleClassifierOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqZoomWindow(int windowNumber, int xZoom, int yZoom, Point center);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqGetWindowZoom(int windowNumber, int* xZoom, int* yZoom);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqParticleFilter3(Image* dest, Image* source,
+                    const ParticleFilterCriteria2* criteria, int criteriaCount,
+                    const ParticleFilterOptions* options, const ROI* roi,
+                    int* numParticles);
+IMAQ_FUNC ReadTextReport2* IMAQ_STDCALL
+imaqReadText2(const Image* image, const CharSet* set, const ROI* roi,
+              const ReadTextOptions* readOptions,
+              const OCRProcessingOptions* processingOptions,
+              const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLearnPattern2(Image* image, LearningMode learningMode,
+                  LearnPatternAdvancedOptions* advancedOptions);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqConvolve(Image* dest, Image* source, const float* kernel, int matrixRows,
+             int matrixCols, float normalize, const Image* mask);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDivideConstant(Image* dest, const Image* source, PixelValue value);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqDivide(Image* dest, const Image* sourceA, const Image* sourceB);
+IMAQ_FUNC EdgeReport2* IMAQ_STDCALL
+imaqEdgeTool3(const Image* image, const ROI* roi, EdgeProcess processType,
+              const EdgeOptions2* edgeOptions);
+IMAQ_FUNC ConcentricRakeReport* IMAQ_STDCALL
+imaqConcentricRake(const Image* image, const ROI* roi,
+                   ConcentricRakeDirection direction, EdgeProcess process,
+                   const RakeOptions* options);
+IMAQ_FUNC SpokeReport* IMAQ_STDCALL
+imaqSpoke(const Image* image, const ROI* roi, SpokeDirection direction,
+          EdgeProcess process, const SpokeOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqLearnPattern(Image* image, LearningMode learningMode);
+IMAQ_FUNC int IMAQ_STDCALL imaqLookup(Image* dest, const Image* source,
+                                      const short* table, const Image* mask);
+IMAQ_FUNC PatternMatch* IMAQ_STDCALL
+imaqMatchPattern2(const Image* image, const Image* pattern,
+                  const MatchPatternOptions* options,
+                  const MatchPatternAdvancedOptions* advancedOptions,
+                  Rect searchRect, int* numMatches);
+IMAQ_FUNC int IMAQ_STDCALL imaqSetParticleClassifierOptions(
+    ClassifierSession* session,
+    const ParticleClassifierPreprocessingOptions* preprocessingOptions,
+    const ParticleClassifierOptions* options);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqCopyCalibrationInfo(Image* dest, const Image* source);
+IMAQ_FUNC int IMAQ_STDCALL
+imaqParticleFilter2(Image* dest, Image* source,
+                    const ParticleFilterCriteria2* criteria, int criteriaCount,
+                    int rejectMatches, int connectivity8, int* numParticles);
+IMAQ_FUNC EdgeReport* IMAQ_STDCALL
+imaqEdgeTool2(const Image* image, const Point* points, int numPoints,
+              EdgeProcess process, const EdgeOptions* options, int* numEdges);
+IMAQ_FUNC ContourID IMAQ_STDCALL
+imaqAddRotatedRectContour(ROI* roi, RotatedRect rect);
+IMAQ_FUNC Barcode2DInfo* IMAQ_STDCALL
+imaqReadDataMatrixBarcode(const Image* image, const ROI* roi,
+                          const DataMatrixOptions* options,
+                          unsigned int* numBarcodes);
+IMAQ_FUNC LinearAverages* IMAQ_STDCALL
+imaqLinearAverages(const Image* image, Rect rect);
+IMAQ_FUNC GeometricPatternMatch* IMAQ_STDCALL imaqMatchGeometricPattern(
+    const Image* image, const Image* pattern, const CurveOptions* curveOptions,
+    const MatchGeometricPatternOptions* matchOptions,
+    const MatchGeometricPatternAdvancedOptions* advancedMatchOptions,
+    const ROI* roi, int* numMatches);
+IMAQ_FUNC CharInfo* IMAQ_STDCALL imaqGetCharInfo(const CharSet* set, int index);
+IMAQ_FUNC ReadTextReport* IMAQ_STDCALL
+imaqReadText(const Image* image, const CharSet* set, const ROI* roi,
+             const ReadTextOptions* readOptions,
+             const OCRProcessingOptions* processingOptions,
+             const OCRSpacingOptions* spacingOptions);
+IMAQ_FUNC ThresholdData* IMAQ_STDCALL
+imaqAutoThreshold(Image* dest, Image* source, int numClasses,
+                  ThresholdMethod method);
+IMAQ_FUNC ColorHistogramReport* IMAQ_STDCALL
+imaqColorHistogram(Image* image, int numClasses, ColorMode mode,
+                   const Image* mask);
+IMAQ_FUNC RakeReport* IMAQ_STDCALL
+imaqRake(const Image* image, const ROI* roi, RakeDirection direction,
+         EdgeProcess process, const RakeOptions* options);
+
+IMAQ_FUNC int IMAQ_STDCALL Priv_ReadJPEGString_C(Image* image,
+                                                 const unsigned char* string,
+                                                 unsigned int stringLength);
+#endif
diff --git a/wpilibc/Athena/include/pcre.h b/wpilibc/Athena/include/pcre.h
new file mode 100644
index 0000000..0605461
--- /dev/null
+++ b/wpilibc/Athena/include/pcre.h
@@ -0,0 +1,345 @@
+/*************************************************
+*       Perl-Compatible Regular Expressions      *
+*************************************************/
+
+/* This is the public header file for the PCRE library, to be #included by
+applications that call the PCRE functions.
+
+           Copyright (c) 1997-2008 University of Cambridge
+
+-----------------------------------------------------------------------------
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+    * Redistributions of source code must retain the above copyright notice,
+      this list of conditions and the following disclaimer.
+
+    * Redistributions in binary form must reproduce the above copyright
+      notice, this list of conditions and the following disclaimer in the
+      documentation and/or other materials provided with the distribution.
+
+    * Neither the name of the University of Cambridge nor the names of its
+      contributors may be used to endorse or promote products derived from
+      this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
+LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
+CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
+SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
+INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
+CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+POSSIBILITY OF SUCH DAMAGE.
+-----------------------------------------------------------------------------
+*/
+
+#ifndef _PCRE_H
+#define _PCRE_H
+
+/* The current PCRE version information. */
+
+#define PCRE_MAJOR 7
+#define PCRE_MINOR 8
+#define PCRE_PRERELEASE
+#define PCRE_DATE 2008 - 09 - 05
+
+/* When an application links to a PCRE DLL in Windows, the symbols that are
+imported have to be identified as such. When building PCRE, the appropriate
+export setting is defined in pcre_internal.h, which includes this file. So we
+don't change existing definitions of PCRE_EXP_DECL and PCRECPP_EXP_DECL. */
+
+/**
+ * NI CHANGE
+ *
+ * We don't build the DLL version. We only build the static lib version.
+ * Since we don't want to have to #define PCRE_STATIC in every component that
+ * includes pcre.h, we're just going to go ahead and define it here.
+ *
+ * Adam Kemp, 12/15/2008
+*/
+#define PCRE_STATIC
+
+#if defined(_WIN32) && !defined(PCRE_STATIC)
+#ifndef PCRE_EXP_DECL
+#define PCRE_EXP_DECL extern __declspec(dllimport)
+#endif
+#ifdef __cplusplus
+#ifndef PCRECPP_EXP_DECL
+#define PCRECPP_EXP_DECL extern __declspec(dllimport)
+#endif
+#ifndef PCRECPP_EXP_DEFN
+#define PCRECPP_EXP_DEFN __declspec(dllimport)
+#endif
+#endif
+#endif
+
+/* By default, we use the standard "extern" declarations. */
+
+#ifndef PCRE_EXP_DECL
+#ifdef __cplusplus
+#define PCRE_EXP_DECL extern "C"
+#else
+#define PCRE_EXP_DECL extern
+#endif
+#endif
+
+#ifdef __cplusplus
+#ifndef PCRECPP_EXP_DECL
+#define PCRECPP_EXP_DECL extern
+#endif
+#ifndef PCRECPP_EXP_DEFN
+#define PCRECPP_EXP_DEFN
+#endif
+#endif
+
+/**
+ * NI CHANGE
+ *
+ * We use __cdecl on win32 and the default calling convention elsewhere.
+ *
+ * Originall this macro did not appear in this file, but it was used in
+ * internal headers. I consider it an oversight on the part of the pcre
+ * developers that * it was not used in this file. If these functions use
+ * specific calling conventions then their prototypes should include that
+ * calling convention in case some other project uses a different default.
+ *
+ * Adam Kemp 12/15/2008
+*/
+#ifndef PCRE_CALL_CONVENTION
+#if defined(_WIN32) /* 32-bit and 64-bit */
+#define PCRE_CALL_CONVENTION __cdecl
+#else
+#define PCRE_CALL_CONVENTION
+#endif
+#else
+#define PCRE_CALL_CONVENTION
+#endif
+
+/* Have to include stdlib.h in order to ensure that size_t is defined;
+it is needed here for malloc. */
+
+#include <stdlib.h>
+
+/* Allow for C++ users */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/* Options */
+
+#define PCRE_CASELESS 0x00000001
+#define PCRE_MULTILINE 0x00000002
+#define PCRE_DOTALL 0x00000004
+#define PCRE_EXTENDED 0x00000008
+#define PCRE_ANCHORED 0x00000010
+#define PCRE_DOLLAR_ENDONLY 0x00000020
+#define PCRE_EXTRA 0x00000040
+#define PCRE_NOTBOL 0x00000080
+#define PCRE_NOTEOL 0x00000100
+#define PCRE_UNGREEDY 0x00000200
+#define PCRE_NOTEMPTY 0x00000400
+#define PCRE_UTF8 0x00000800
+#define PCRE_NO_AUTO_CAPTURE 0x00001000
+#define PCRE_NO_UTF8_CHECK 0x00002000
+#define PCRE_AUTO_CALLOUT 0x00004000
+#define PCRE_PARTIAL 0x00008000
+#define PCRE_DFA_SHORTEST 0x00010000
+#define PCRE_DFA_RESTART 0x00020000
+#define PCRE_FIRSTLINE 0x00040000
+#define PCRE_DUPNAMES 0x00080000
+#define PCRE_NEWLINE_CR 0x00100000
+#define PCRE_NEWLINE_LF 0x00200000
+#define PCRE_NEWLINE_CRLF 0x00300000
+#define PCRE_NEWLINE_ANY 0x00400000
+#define PCRE_NEWLINE_ANYCRLF 0x00500000
+#define PCRE_BSR_ANYCRLF 0x00800000
+#define PCRE_BSR_UNICODE 0x01000000
+#define PCRE_JAVASCRIPT_COMPAT 0x02000000
+
+/* Exec-time and get/set-time error codes */
+
+#define PCRE_ERROR_NOMATCH (-1)
+#define PCRE_ERROR_NULL (-2)
+#define PCRE_ERROR_BADOPTION (-3)
+#define PCRE_ERROR_BADMAGIC (-4)
+#define PCRE_ERROR_UNKNOWN_OPCODE (-5)
+#define PCRE_ERROR_UNKNOWN_NODE (-5) /* For backward compatibility */
+#define PCRE_ERROR_NOMEMORY (-6)
+#define PCRE_ERROR_NOSUBSTRING (-7)
+#define PCRE_ERROR_MATCHLIMIT (-8)
+#define PCRE_ERROR_CALLOUT (-9) /* Never used by PCRE itself */
+#define PCRE_ERROR_BADUTF8 (-10)
+#define PCRE_ERROR_BADUTF8_OFFSET (-11)
+#define PCRE_ERROR_PARTIAL (-12)
+#define PCRE_ERROR_BADPARTIAL (-13)
+#define PCRE_ERROR_INTERNAL (-14)
+#define PCRE_ERROR_BADCOUNT (-15)
+#define PCRE_ERROR_DFA_UITEM (-16)
+#define PCRE_ERROR_DFA_UCOND (-17)
+#define PCRE_ERROR_DFA_UMLIMIT (-18)
+#define PCRE_ERROR_DFA_WSSIZE (-19)
+#define PCRE_ERROR_DFA_RECURSE (-20)
+#define PCRE_ERROR_RECURSIONLIMIT (-21)
+#define PCRE_ERROR_NULLWSLIMIT (-22) /* No longer actually used */
+#define PCRE_ERROR_BADNEWLINE (-23)
+
+/* Request types for pcre_fullinfo() */
+
+#define PCRE_INFO_OPTIONS 0
+#define PCRE_INFO_SIZE 1
+#define PCRE_INFO_CAPTURECOUNT 2
+#define PCRE_INFO_BACKREFMAX 3
+#define PCRE_INFO_FIRSTBYTE 4
+#define PCRE_INFO_FIRSTCHAR 4 /* For backwards compatibility */
+#define PCRE_INFO_FIRSTTABLE 5
+#define PCRE_INFO_LASTLITERAL 6
+#define PCRE_INFO_NAMEENTRYSIZE 7
+#define PCRE_INFO_NAMECOUNT 8
+#define PCRE_INFO_NAMETABLE 9
+#define PCRE_INFO_STUDYSIZE 10
+#define PCRE_INFO_DEFAULT_TABLES 11
+#define PCRE_INFO_OKPARTIAL 12
+#define PCRE_INFO_JCHANGED 13
+#define PCRE_INFO_HASCRORLF 14
+
+/* Request types for pcre_config(). Do not re-arrange, in order to remain
+compatible. */
+
+#define PCRE_CONFIG_UTF8 0
+#define PCRE_CONFIG_NEWLINE 1
+#define PCRE_CONFIG_LINK_SIZE 2
+#define PCRE_CONFIG_POSIX_MALLOC_THRESHOLD 3
+#define PCRE_CONFIG_MATCH_LIMIT 4
+#define PCRE_CONFIG_STACKRECURSE 5
+#define PCRE_CONFIG_UNICODE_PROPERTIES 6
+#define PCRE_CONFIG_MATCH_LIMIT_RECURSION 7
+#define PCRE_CONFIG_BSR 8
+
+/* Bit flags for the pcre_extra structure. Do not re-arrange or redefine
+these bits, just add new ones on the end, in order to remain compatible. */
+
+#define PCRE_EXTRA_STUDY_DATA 0x0001
+#define PCRE_EXTRA_MATCH_LIMIT 0x0002
+#define PCRE_EXTRA_CALLOUT_DATA 0x0004
+#define PCRE_EXTRA_TABLES 0x0008
+#define PCRE_EXTRA_MATCH_LIMIT_RECURSION 0x0010
+
+/* Types */
+
+struct real_pcre; /* declaration; the definition is private  */
+typedef struct real_pcre pcre;
+
+/* When PCRE is compiled as a C++ library, the subject pointer type can be
+replaced with a custom type. For conventional use, the public interface is a
+const char *. */
+
+#ifndef PCRE_SPTR
+#define PCRE_SPTR const char *
+#endif
+
+/* The structure for passing additional data to pcre_exec(). This is defined in
+such as way as to be extensible. Always add new fields at the end, in order to
+remain compatible. */
+
+typedef struct pcre_extra {
+  unsigned long int flags;       /* Bits for which fields are set */
+  void *study_data;              /* Opaque data from pcre_study() */
+  unsigned long int match_limit; /* Maximum number of calls to match() */
+  void *callout_data;            /* Data passed back in callouts */
+  const unsigned char *tables;   /* Pointer to character tables */
+  unsigned long int match_limit_recursion; /* Max recursive calls to match() */
+} pcre_extra;
+
+/* The structure for passing out data via the pcre_callout_function. We use a
+structure so that new fields can be added on the end in future versions,
+without changing the API of the function, thereby allowing old clients to work
+without modification. */
+
+typedef struct pcre_callout_block {
+  int version; /* Identifies version of block */
+  /* ------------------------ Version 0 ------------------------------- */
+  int callout_number;   /* Number compiled into pattern */
+  int *offset_vector;   /* The offset vector */
+  PCRE_SPTR subject;    /* The subject being matched */
+  int subject_length;   /* The length of the subject */
+  int start_match;      /* Offset to start of this match attempt */
+  int current_position; /* Where we currently are in the subject */
+  int capture_top;      /* Max current capture */
+  int capture_last;     /* Most recently closed capture */
+  void *callout_data;   /* Data passed in with the call */
+  /* ------------------- Added for Version 1 -------------------------- */
+  int pattern_position; /* Offset to next item in the pattern */
+  int next_item_length; /* Length of next item in the pattern */
+  /* ------------------------------------------------------------------ */
+} pcre_callout_block;
+
+/* Indirection for store get and free functions. These can be set to
+alternative malloc/free functions if required. Special ones are used in the
+non-recursive case for "frames". There is also an optional callout function
+that is triggered by the (?) regex item. For Virtual Pascal, these definitions
+have to take another form. */
+
+#ifndef VPCOMPAT
+PCRE_EXP_DECL void *(PCRE_CALL_CONVENTION *pcre_malloc)(size_t);
+PCRE_EXP_DECL void(PCRE_CALL_CONVENTION *pcre_free)(void *);
+PCRE_EXP_DECL void *(PCRE_CALL_CONVENTION *pcre_stack_malloc)(size_t);
+PCRE_EXP_DECL void(PCRE_CALL_CONVENTION *pcre_stack_free)(void *);
+PCRE_EXP_DECL int(PCRE_CALL_CONVENTION *pcre_callout)(pcre_callout_block *);
+#else  /* VPCOMPAT */
+PCRE_EXP_DECL void *PCRE_CALL_CONVENTION pcre_malloc(size_t);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_free(void *);
+PCRE_EXP_DECL void *PCRE_CALL_CONVENTION pcre_stack_malloc(size_t);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_stack_free(void *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_callout(pcre_callout_block *);
+#endif /* VPCOMPAT */
+
+/* Exported PCRE functions */
+
+PCRE_EXP_DECL pcre *PCRE_CALL_CONVENTION
+pcre_compile(const char *, int, const char **, int *, const unsigned char *);
+PCRE_EXP_DECL pcre *PCRE_CALL_CONVENTION pcre_compile2(const char *, int, int *,
+                                                       const char **, int *,
+                                                       const unsigned char *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_config(int, void *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_copy_named_substring(const pcre *, const char *, int *, int, const char *,
+                          char *, int);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_copy_substring(const char *, int *, int, int, char *, int);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_dfa_exec(const pcre *, const pcre_extra *, const char *, int, int, int,
+              int *, int, int *, int);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_exec(const pcre *,
+                                                 const pcre_extra *, PCRE_SPTR,
+                                                 int, int, int, int *, int);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_free_substring(const char *);
+PCRE_EXP_DECL void PCRE_CALL_CONVENTION pcre_free_substring_list(const char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_fullinfo(const pcre *, const pcre_extra *, int, void *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_get_named_substring(const pcre *, const char *, int *, int, const char *,
+                         const char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_get_stringnumber(const pcre *, const char *);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_get_stringtable_entries(const pcre *, const char *, char **, char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_get_substring(const char *, int *, int, int, const char **);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION
+pcre_get_substring_list(const char *, int *, int, const char ***);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_info(const pcre *, int *, int *);
+PCRE_EXP_DECL const unsigned char *PCRE_CALL_CONVENTION pcre_maketables(void);
+PCRE_EXP_DECL int PCRE_CALL_CONVENTION pcre_refcount(pcre *, int);
+PCRE_EXP_DECL pcre_extra *PCRE_CALL_CONVENTION
+pcre_study(const pcre *, int, const char **);
+PCRE_EXP_DECL const char *PCRE_CALL_CONVENTION pcre_version(void);
+
+#ifdef __cplusplus
+} /* extern "C" */
+#endif
+
+#endif /* End of pcre.h */
diff --git a/wpilibc/Athena/src/ADXL345_I2C.cpp b/wpilibc/Athena/src/ADXL345_I2C.cpp
new file mode 100644
index 0000000..000d4b8
--- /dev/null
+++ b/wpilibc/Athena/src/ADXL345_I2C.cpp
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "ADXL345_I2C.h"
+#include "I2C.h"
+#include "HAL/HAL.hpp"
+#include "LiveWindow/LiveWindow.h"
+
+const uint8_t ADXL345_I2C::kAddress;
+const uint8_t ADXL345_I2C::kPowerCtlRegister;
+const uint8_t ADXL345_I2C::kDataFormatRegister;
+const uint8_t ADXL345_I2C::kDataRegister;
+constexpr double ADXL345_I2C::kGsPerLSB;
+
+/**
+ * Constructor.
+ *
+ * @param port The I2C port the accelerometer is attached to
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL345_I2C::ADXL345_I2C(Port port, Range range) : I2C(port, kAddress) {
+  // Turn on the measurements
+  Write(kPowerCtlRegister, kPowerCtl_Measure);
+  // Specify the data format to read
+  SetRange(range);
+
+  HALReport(HALUsageReporting::kResourceType_ADXL345,
+            HALUsageReporting::kADXL345_I2C, 0);
+  LiveWindow::GetInstance()->AddSensor("ADXL345_I2C", port, this);
+}
+
+/** {@inheritdoc} */
+void ADXL345_I2C::SetRange(Range range) {
+  Write(kDataFormatRegister, kDataFormat_FullRes | (uint8_t)range);
+}
+
+/** {@inheritdoc} */
+double ADXL345_I2C::GetX() { return GetAcceleration(kAxis_X); }
+
+/** {@inheritdoc} */
+double ADXL345_I2C::GetY() { return GetAcceleration(kAxis_Y); }
+
+/** {@inheritdoc} */
+double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); }
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL345 in Gs.
+ */
+double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) {
+  int16_t rawAccel = 0;
+  Read(kDataRegister + (uint8_t)axis, sizeof(rawAccel), (uint8_t *)&rawAccel);
+  return rawAccel * kGsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return An object containing the acceleration measured on each axis of the
+ * ADXL345 in Gs.
+ */
+ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() {
+  AllAxes data = AllAxes();
+  int16_t rawData[3];
+  Read(kDataRegister, sizeof(rawData), (uint8_t *)rawData);
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+  return data;
+}
+
+std::string ADXL345_I2C::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void ADXL345_I2C::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void ADXL345_I2C::UpdateTable() {
+  m_table->PutNumber("X", GetX());
+  m_table->PutNumber("Y", GetY());
+  m_table->PutNumber("Z", GetZ());
+}
+
+std::shared_ptr<ITable> ADXL345_I2C::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/ADXL345_SPI.cpp b/wpilibc/Athena/src/ADXL345_SPI.cpp
new file mode 100644
index 0000000..7fb3b71
--- /dev/null
+++ b/wpilibc/Athena/src/ADXL345_SPI.cpp
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "ADXL345_SPI.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "LiveWindow/LiveWindow.h"
+
+const uint8_t ADXL345_SPI::kPowerCtlRegister;
+const uint8_t ADXL345_SPI::kDataFormatRegister;
+const uint8_t ADXL345_SPI::kDataRegister;
+constexpr double ADXL345_SPI::kGsPerLSB;
+
+/**
+ * Constructor.
+ *
+ * @param port The SPI port the accelerometer is attached to
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range) : SPI(port) {
+  SetClockRate(500000);
+  SetMSBFirst();
+  SetSampleDataOnFalling();
+  SetClockActiveLow();
+  SetChipSelectActiveHigh();
+
+  uint8_t commands[2];
+  // Turn on the measurements
+  commands[0] = kPowerCtlRegister;
+  commands[1] = kPowerCtl_Measure;
+  Transaction(commands, commands, 2);
+
+  SetRange(range);
+
+  HALReport(HALUsageReporting::kResourceType_ADXL345,
+            HALUsageReporting::kADXL345_SPI);
+
+  LiveWindow::GetInstance()->AddSensor("ADXL345_SPI", port, this);
+}
+
+/** {@inheritdoc} */
+void ADXL345_SPI::SetRange(Range range) {
+  uint8_t commands[2];
+
+  // Specify the data format to read
+  commands[0] = kDataFormatRegister;
+  commands[1] = kDataFormat_FullRes | (uint8_t)(range & 0x03);
+  Transaction(commands, commands, 2);
+}
+
+/** {@inheritdoc} */
+double ADXL345_SPI::GetX() { return GetAcceleration(kAxis_X); }
+
+/** {@inheritdoc} */
+double ADXL345_SPI::GetY() { return GetAcceleration(kAxis_Y); }
+
+/** {@inheritdoc} */
+double ADXL345_SPI::GetZ() { return GetAcceleration(kAxis_Z); }
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL345 in Gs.
+ */
+double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) {
+  uint8_t buffer[3];
+  uint8_t command[3] = {0, 0, 0};
+  command[0] =
+      (kAddress_Read | kAddress_MultiByte | kDataRegister) + (uint8_t)axis;
+  Transaction(command, buffer, 3);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[2] << 8 | buffer[1];
+  return rawAccel * kGsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return An object containing the acceleration measured on each axis of the
+ * ADXL345 in Gs.
+ */
+ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() {
+  AllAxes data = AllAxes();
+  uint8_t dataBuffer[7] = {0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister);
+  Transaction(dataBuffer, dataBuffer, 7);
+
+  for (int32_t i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 2] << 8 | dataBuffer[i * 2 + 1];
+  }
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+
+  return data;
+}
+
+std::string ADXL345_SPI::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void ADXL345_SPI::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void ADXL345_SPI::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("X", GetX());
+    m_table->PutNumber("Y", GetY());
+    m_table->PutNumber("Z", GetZ());
+  }
+}
+
+std::shared_ptr<ITable> ADXL345_SPI::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/ADXL362.cpp b/wpilibc/Athena/src/ADXL362.cpp
new file mode 100644
index 0000000..3c70b9b
--- /dev/null
+++ b/wpilibc/Athena/src/ADXL362.cpp
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "ADXL362.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "DriverStation.h"
+#include "LiveWindow/LiveWindow.h"
+
+static uint8_t kRegWrite = 0x0A;
+static uint8_t kRegRead = 0x0B;
+
+static uint8_t kPartIdRegister = 0x02;
+static uint8_t kDataRegister = 0x0E;
+static uint8_t kFilterCtlRegister = 0x2C;
+static uint8_t kPowerCtlRegister = 0x2D;
+
+//static uint8_t kFilterCtl_Range2G = 0x00;
+//static uint8_t kFilterCtl_Range4G = 0x40;
+//static uint8_t kFilterCtl_Range8G = 0x80;
+static uint8_t kFilterCtl_ODR_100Hz = 0x03;
+
+static uint8_t kPowerCtl_UltraLowNoise = 0x20;
+//static uint8_t kPowerCtl_AutoSleep = 0x04;
+static uint8_t kPowerCtl_Measure = 0x02;
+
+/**
+ * Constructor.  Uses the onboard CS1.
+ *
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL362::ADXL362(Range range) : ADXL362(SPI::Port::kOnboardCS1, range) {}
+
+/**
+ * Constructor.
+ *
+ * @param port The SPI port the accelerometer is attached to
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL362::ADXL362(SPI::Port port, Range range) : m_spi(port) {
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnFalling();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveLow();
+
+  // Validate the part ID
+  uint8_t commands[3];
+  commands[0] = kRegRead;
+  commands[1] = kPartIdRegister;
+  commands[2] = 0;
+  m_spi.Transaction(commands, commands, 3);
+  if (commands[2] != 0xF2) {
+    DriverStation::ReportError("could not find ADXL362");
+    m_gsPerLSB = 0.0;
+    return;
+  }
+
+  SetRange(range);
+
+  // Turn on the measurements
+  commands[0] = kRegWrite;
+  commands[1] = kPowerCtlRegister;
+  commands[2] = kPowerCtl_Measure | kPowerCtl_UltraLowNoise;
+  m_spi.Write(commands, 3);
+
+  HALReport(HALUsageReporting::kResourceType_ADXL362, port);
+
+  LiveWindow::GetInstance()->AddSensor("ADXL362", port, this);
+}
+
+/** {@inheritdoc} */
+void ADXL362::SetRange(Range range) {
+  if (m_gsPerLSB == 0.0) return;
+
+  uint8_t commands[3];
+
+  switch (range) {
+    case kRange_2G:
+      m_gsPerLSB = 0.001;
+      break;
+    case kRange_4G:
+      m_gsPerLSB = 0.002;
+      break;
+    case kRange_8G:
+    case kRange_16G:  // 16G not supported; treat as 8G
+      m_gsPerLSB = 0.004;
+      break;
+  }
+
+  // Specify the data format to read
+  commands[0] = kRegWrite;
+  commands[1] = kFilterCtlRegister;
+  commands[2] = kFilterCtl_ODR_100Hz | (uint8_t)((range & 0x03) << 6);
+  m_spi.Write(commands, 3);
+}
+
+/** {@inheritdoc} */
+double ADXL362::GetX() { return GetAcceleration(kAxis_X); }
+
+/** {@inheritdoc} */
+double ADXL362::GetY() { return GetAcceleration(kAxis_Y); }
+
+/** {@inheritdoc} */
+double ADXL362::GetZ() { return GetAcceleration(kAxis_Z); }
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL362 in Gs.
+ */
+double ADXL362::GetAcceleration(ADXL362::Axes axis) {
+  if (m_gsPerLSB == 0.0) return 0.0;
+
+  uint8_t buffer[4];
+  uint8_t command[4] = {0, 0, 0, 0};
+  command[0] = kRegRead;
+  command[1] = kDataRegister + (uint8_t)axis;
+  m_spi.Transaction(command, buffer, 4);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[3] << 8 | buffer[2];
+  return rawAccel * m_gsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return An object containing the acceleration measured on each axis of the
+ * ADXL362 in Gs.
+ */
+ADXL362::AllAxes ADXL362::GetAccelerations() {
+  AllAxes data = AllAxes();
+  if (m_gsPerLSB == 0.0) {
+    data.XAxis = data.YAxis = data.ZAxis = 0.0;
+    return data;
+  }
+
+  uint8_t dataBuffer[8] = {0, 0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = kRegRead;
+  dataBuffer[1] = kDataRegister;
+  m_spi.Transaction(dataBuffer, dataBuffer, 8);
+
+  for (int32_t i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 3] << 8 | dataBuffer[i * 2 + 2];
+  }
+
+  data.XAxis = rawData[0] * m_gsPerLSB;
+  data.YAxis = rawData[1] * m_gsPerLSB;
+  data.ZAxis = rawData[2] * m_gsPerLSB;
+
+  return data;
+}
+
+std::string ADXL362::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void ADXL362::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void ADXL362::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("X", GetX());
+    m_table->PutNumber("Y", GetY());
+    m_table->PutNumber("Z", GetZ());
+  }
+}
+
+std::shared_ptr<ITable> ADXL362::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/ADXRS450_Gyro.cpp b/wpilibc/Athena/src/ADXRS450_Gyro.cpp
new file mode 100644
index 0000000..6b111cf
--- /dev/null
+++ b/wpilibc/Athena/src/ADXRS450_Gyro.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. 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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "ADXRS450_Gyro.h"
+#include "DriverStation.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Timer.h"
+
+static constexpr double kSamplePeriod = 0.001;
+static constexpr double kCalibrationSampleTime = 5.0;
+static constexpr double kDegreePerSecondPerLSB = 0.0125;
+
+static constexpr uint8_t kRateRegister = 0x00;
+static constexpr uint8_t kTemRegister = 0x02;
+static constexpr uint8_t kLoCSTRegister = 0x04;
+static constexpr uint8_t kHiCSTRegister = 0x06;
+static constexpr uint8_t kQuadRegister = 0x08;
+static constexpr uint8_t kFaultRegister = 0x0A;
+static constexpr uint8_t kPIDRegister = 0x0C;
+static constexpr uint8_t kSNHighRegister = 0x0E;
+static constexpr uint8_t kSNLowRegister = 0x10;
+
+/**
+ * Initialize the gyro.
+ * Calibrate the gyro by running for a number of samples and computing the
+ * center value.
+ * Then use the center value as the Accumulator center value for subsequent
+ * measurements.
+ * It's important to make sure that the robot is not moving while the centering
+ * calculations are in progress, this is typically done when the robot is first
+ * turned on while it's sitting at rest before the competition starts.
+ */
+void ADXRS450_Gyro::Calibrate() {
+  Wait(0.1);
+
+  m_spi.SetAccumulatorCenter(0);
+  m_spi.ResetAccumulator();
+
+  Wait(kCalibrationSampleTime);
+
+  m_spi.SetAccumulatorCenter((int32_t)m_spi.GetAccumulatorAverage());
+  m_spi.ResetAccumulator();
+}
+
+/**
+ * Gyro constructor on onboard CS0.
+ */
+ADXRS450_Gyro::ADXRS450_Gyro() : ADXRS450_Gyro(SPI::kOnboardCS0) {}
+
+/**
+ * Gyro constructor on the specified SPI port.
+ *
+ * @param port The SPI port the gyro is attached to.
+ */
+ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port) : m_spi(port) {
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnRising();
+  m_spi.SetClockActiveHigh();
+  m_spi.SetChipSelectActiveLow();
+
+  // Validate the part ID
+  if ((ReadRegister(kPIDRegister) & 0xff00) != 0x5200) {
+    DriverStation::ReportError("could not find ADXRS450 gyro");
+    return;
+  }
+
+  m_spi.InitAccumulator(kSamplePeriod, 0x20000000u, 4, 0x0c000000u, 0x04000000u,
+                        10u, 16u, true, true);
+
+  Calibrate();
+
+  HALReport(HALUsageReporting::kResourceType_ADXRS450, port);
+  LiveWindow::GetInstance()->AddSensor("ADXRS450_Gyro", port, this);
+}
+
+static bool CalcParity(uint32_t v) {
+  bool parity = false;
+  while (v != 0) {
+    parity = !parity;
+    v = v & (v - 1);
+  }
+  return parity;
+}
+
+static inline uint32_t BytesToIntBE(uint8_t* buf) {
+  uint32_t result = ((uint32_t)buf[0]) << 24;
+  result |= ((uint32_t)buf[1]) << 16;
+  result |= ((uint32_t)buf[2]) << 8;
+  result |= (uint32_t)buf[3];
+  return result;
+}
+
+uint16_t ADXRS450_Gyro::ReadRegister(uint8_t reg) {
+  uint32_t cmd = 0x80000000 | (((uint32_t)reg) << 17);
+  if (!CalcParity(cmd)) cmd |= 1u;
+
+  // big endian
+  uint8_t buf[4] = {(uint8_t)((cmd >> 24) & 0xff),
+                    (uint8_t)((cmd >> 16) & 0xff),
+                    (uint8_t)((cmd >> 8) & 0xff),
+                    (uint8_t)(cmd & 0xff)};
+
+  m_spi.Write(buf, 4);
+  m_spi.Read(false, buf, 4);
+  if ((buf[0] & 0xe0) == 0) return 0;  // error, return 0
+  return (uint16_t)((BytesToIntBE(buf) >> 5) & 0xffff);
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to a heading of zero. This can be used if there is
+ * significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+ */
+void ADXRS450_Gyro::Reset() {
+  m_spi.ResetAccumulator();
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the
+ * oversampling rate, the
+ * gyro type and the A/D calibration values.
+ * The angle is continuous, that is it will continue from 360->361 degrees. This
+ * allows algorithms that wouldn't
+ * want to see a discontinuity in the gyro output as it sweeps from 360 to 0 on
+ * the second time around.
+ *
+ * @return the current heading of the robot in degrees. This heading is based on
+ * integration
+ * of the returned rate from the gyro.
+ */
+float ADXRS450_Gyro::GetAngle() const {
+  return (float)(m_spi.GetAccumulatorValue() * kDegreePerSecondPerLSB *
+                 kSamplePeriod);
+}
+
+/**
+ * Return the rate of rotation of the gyro
+ *
+ * The rate is based on the most recent reading of the gyro analog value
+ *
+ * @return the current rate in degrees per second
+ */
+double ADXRS450_Gyro::GetRate() const {
+  return (double)m_spi.GetAccumulatorLastValue() * kDegreePerSecondPerLSB;
+}
+
+std::string ADXRS450_Gyro::GetSmartDashboardType() const {
+  return "ADXRS450_Gyro";
+}
diff --git a/wpilibc/Athena/src/AnalogAccelerometer.cpp b/wpilibc/Athena/src/AnalogAccelerometer.cpp
new file mode 100644
index 0000000..5cf41d9
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogAccelerometer.cpp
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogAccelerometer.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Common function for initializing the accelerometer.
+ */
+void AnalogAccelerometer::InitAccelerometer() {
+  HALReport(HALUsageReporting::kResourceType_Accelerometer,
+            m_analogInput->GetChannel());
+  LiveWindow::GetInstance()->AddSensor("Accelerometer",
+                                       m_analogInput->GetChannel(), this);
+}
+
+/**
+ * Create a new instance of an accelerometer.
+ * The constructor allocates desired analog input.
+ * @param channel The channel number for the analog input the accelerometer is
+ * connected to
+ */
+AnalogAccelerometer::AnalogAccelerometer(int32_t channel) {
+  m_analogInput = std::make_shared<AnalogInput>(channel);
+  InitAccelerometer();
+}
+
+/**
+ * Create a new instance of Accelerometer from an existing AnalogInput.
+ * Make a new instance of accelerometer given an AnalogInput. This is
+ * particularly useful if the port is going to be read as an analog channel as
+ * well as through the Accelerometer class.
+ * @param channel The existing AnalogInput object for the analog input the
+ * accelerometer is connected to
+ */
+AnalogAccelerometer::AnalogAccelerometer(AnalogInput *channel)
+    : m_analogInput(channel, NullDeleter<AnalogInput>()) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+/**
+ * Create a new instance of Accelerometer from an existing AnalogInput.
+ * Make a new instance of accelerometer given an AnalogInput. This is
+ * particularly useful if the port is going to be read as an analog channel as
+ * well as through the Accelerometer class.
+ * @param channel The existing AnalogInput object for the analog input the
+ * accelerometer is connected to
+ */
+AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
+    : m_analogInput(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+/**
+ * Return the acceleration in Gs.
+ *
+ * The acceleration is returned units of Gs.
+ *
+ * @return The current acceleration of the sensor in Gs.
+ */
+float AnalogAccelerometer::GetAcceleration() const {
+  return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
+}
+
+/**
+ * Set the accelerometer sensitivity.
+ *
+ * This sets the sensitivity of the accelerometer used for calculating the
+ * acceleration.
+ * The sensitivity varies by accelerometer model. There are constants defined
+ * for various models.
+ *
+ * @param sensitivity The sensitivity of accelerometer in Volts per G.
+ */
+void AnalogAccelerometer::SetSensitivity(float sensitivity) {
+  m_voltsPerG = sensitivity;
+}
+
+/**
+ * Set the voltage that corresponds to 0 G.
+ *
+ * The zero G voltage varies by accelerometer model. There are constants defined
+ * for various models.
+ *
+ * @param zero The zero G voltage.
+ */
+void AnalogAccelerometer::SetZero(float zero) { m_zeroGVoltage = zero; }
+
+/**
+ * Get the Acceleration for the PID Source parent.
+ *
+ * @return The current acceleration in Gs.
+ */
+double AnalogAccelerometer::PIDGet() { return GetAcceleration(); }
+
+void AnalogAccelerometer::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetAcceleration());
+  }
+}
+
+void AnalogAccelerometer::StartLiveWindowMode() {}
+
+void AnalogAccelerometer::StopLiveWindowMode() {}
+
+std::string AnalogAccelerometer::GetSmartDashboardType() const {
+  return "Accelerometer";
+}
+
+void AnalogAccelerometer::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> AnalogAccelerometer::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/AnalogGyro.cpp b/wpilibc/Athena/src/AnalogGyro.cpp
new file mode 100644
index 0000000..54093ec
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogGyro.cpp
@@ -0,0 +1,255 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogGyro.h"
+#include "AnalogInput.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+#include <climits>
+const uint32_t AnalogGyro::kOversampleBits;
+const uint32_t AnalogGyro::kAverageBits;
+constexpr float AnalogGyro::kSamplesPerSecond;
+constexpr float AnalogGyro::kCalibrationSampleTime;
+constexpr float AnalogGyro::kDefaultVoltsPerDegreePerSecond;
+
+/**
+ * Gyro constructor using the Analog Input channel number.
+ *
+ * @param channel The analog channel the gyro is connected to. Gyros
+                      can only be used on on-board Analog Inputs 0-1.
+ */
+AnalogGyro::AnalogGyro(int32_t channel) :
+    AnalogGyro(std::make_shared<AnalogInput>(channel)) {}
+
+/**
+ * Gyro constructor with a precreated AnalogInput object.
+ * Use this constructor when the analog channel needs to be shared.
+ * This object will not clean up the AnalogInput object when using this
+ * constructor.
+ * Gyros can only be used on on-board channels 0-1.
+ * @param channel A pointer to the AnalogInput object that the gyro is connected
+ * to.
+ */
+AnalogGyro::AnalogGyro(AnalogInput *channel)
+    : AnalogGyro(
+          std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {}
+
+/**
+ * Gyro constructor with a precreated AnalogInput object.
+ * Use this constructor when the analog channel needs to be shared.
+ * This object will not clean up the AnalogInput object when using this
+ * constructor
+ * @param channel A pointer to the AnalogInput object that the gyro is
+ * connected to.
+ */
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    Calibrate();
+  }
+}
+
+/**
+ * Gyro constructor using the Analog Input channel number with parameters for
+ * presetting the center and offset values. Bypasses calibration.
+ *
+ * @param channel The analog channel the gyro is connected to. Gyros
+ *        can only be used on on-board Analog Inputs 0-1.
+ * @param center Preset uncalibrated value to use as the accumulator center value.
+ * @param offset Preset uncalibrated value to use as the gyro offset.
+ */
+AnalogGyro::AnalogGyro(int32_t channel, uint32_t center, float offset) {
+  m_analog = std::make_shared<AnalogInput>(channel);
+  InitGyro();
+  m_center = center;
+  m_offset = offset;
+  m_analog->SetAccumulatorCenter(m_center);
+  m_analog->ResetAccumulator();
+}
+
+/**
+ * Gyro constructor with a precreated AnalogInput object and calibrated parameters.
+ * Use this constructor when the analog channel needs to be shared.
+ * This object will not clean up the AnalogInput object when using this
+ * constructor
+ * @param channel A pointer to the AnalogInput object that the gyro is
+ * connected to.
+ */
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, uint32_t center, float offset) : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    m_center = center;
+    m_offset = offset;
+    m_analog->SetAccumulatorCenter(m_center);
+    m_analog->ResetAccumulator();
+  }
+}
+
+/**
+ * Reset the gyro.
+ * Resets the gyro to a heading of zero. This can be used if there is
+ * significant
+ * drift in the gyro and it needs to be recalibrated after it has been running.
+ */
+void AnalogGyro::Reset() {
+  if (StatusIsFatal()) return;
+  m_analog->ResetAccumulator();
+}
+
+/**
+ * Initialize the gyro.  Calibration is handled by Calibrate().
+ */
+void AnalogGyro::InitGyro() {
+  if (StatusIsFatal()) return;
+
+  if (!m_analog->IsAccumulatorChannel()) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                               " channel (must be accumulator channel)");
+    m_analog = nullptr;
+    return;
+  }
+
+  m_voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond;
+  m_analog->SetAverageBits(kAverageBits);
+  m_analog->SetOversampleBits(kOversampleBits);
+  float sampleRate =
+      kSamplesPerSecond * (1 << (kAverageBits + kOversampleBits));
+  m_analog->SetSampleRate(sampleRate);
+  Wait(0.1);
+
+  SetDeadband(0.0f);
+
+  SetPIDSourceType(PIDSourceType::kDisplacement);
+
+  HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel());
+  LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetChannel(), this);
+}
+
+/**
+ * {@inheritDoc}
+ */
+void AnalogGyro::Calibrate() {
+  if (StatusIsFatal()) return;
+
+  m_analog->InitAccumulator();
+
+  Wait(kCalibrationSampleTime);
+
+  int64_t value;
+  uint32_t count;
+  m_analog->GetAccumulatorOutput(value, count);
+
+  m_center = (uint32_t)((float)value / (float)count + .5);
+
+  m_offset = ((float)value / (float)count) - (float)m_center;
+  m_analog->SetAccumulatorCenter(m_center);
+  m_analog->ResetAccumulator();
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the
+ * oversampling rate, the
+ * gyro type and the A/D calibration values.
+ * The angle is continuous, that is it will continue from 360->361 degrees. This
+ * allows algorithms that wouldn't
+ * want to see a discontinuity in the gyro output as it sweeps from 360 to 0 on
+ * the second time around.
+ *
+ * @return the current heading of the robot in degrees. This heading is based on
+ * integration
+ * of the returned rate from the gyro.
+ */
+float AnalogGyro::GetAngle() const {
+  if (StatusIsFatal()) return 0.f;
+
+  int64_t rawValue;
+  uint32_t count;
+  m_analog->GetAccumulatorOutput(rawValue, count);
+
+  int64_t value = rawValue - (int64_t)((float)count * m_offset);
+
+  double scaledValue = value * 1e-9 * (double)m_analog->GetLSBWeight() *
+                       (double)(1 << m_analog->GetAverageBits()) /
+                       (m_analog->GetSampleRate() * m_voltsPerDegreePerSecond);
+
+  return (float)scaledValue;
+}
+
+/**
+ * Return the rate of rotation of the gyro
+ *
+ * The rate is based on the most recent reading of the gyro analog value
+ *
+ * @return the current rate in degrees per second
+ */
+double AnalogGyro::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+
+  return (m_analog->GetAverageValue() - ((double)m_center + m_offset)) * 1e-9 *
+         m_analog->GetLSBWeight() /
+         ((1 << m_analog->GetOversampleBits()) * m_voltsPerDegreePerSecond);
+}
+
+/**
+ * Return the gyro offset value. If run after calibration,
+ * the offset value can be used as a preset later.
+ *
+ * @return the current offset value
+ */
+float AnalogGyro::GetOffset() const {
+  return m_offset;
+}
+
+/**
+ * Return the gyro center value. If run after calibration,
+ * the center value can be used as a preset later.
+ *
+ * @return the current center value
+ */
+uint32_t AnalogGyro::GetCenter() const {
+  return m_center;
+}
+
+/**
+ * Set the gyro sensitivity.
+ * This takes the number of volts/degree/second sensitivity of the gyro and uses
+ * it in subsequent
+ * calculations to allow the code to work with multiple gyros. This value is
+ * typically found in
+ * the gyro datasheet.
+ *
+ * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
+ */
+void AnalogGyro::SetSensitivity(float voltsPerDegreePerSecond) {
+  m_voltsPerDegreePerSecond = voltsPerDegreePerSecond;
+}
+
+/**
+ * Set the size of the neutral zone.  Any voltage from the gyro less than this
+ * amount from the center is considered stationary.  Setting a deadband will
+ * decrease the amount of drift when the gyro isn't rotating, but will make it
+ * less accurate.
+ *
+ * @param volts The size of the deadband in volts
+ */
+void AnalogGyro::SetDeadband(float volts) {
+  if (StatusIsFatal()) return;
+
+  int32_t deadband = volts * 1e9 / m_analog->GetLSBWeight() *
+                     (1 << m_analog->GetOversampleBits());
+  m_analog->SetAccumulatorDeadband(deadband);
+}
+
+std::string AnalogGyro::GetSmartDashboardType() const { return "AnalogGyro"; }
diff --git a/wpilibc/Athena/src/AnalogInput.cpp b/wpilibc/Athena/src/AnalogInput.cpp
new file mode 100644
index 0000000..dc8e872
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogInput.cpp
@@ -0,0 +1,426 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogInput.h"
+#include "Resource.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+#include "HAL/Port.h"
+
+#include <sstream>
+
+static std::unique_ptr<Resource> inputs;
+
+const uint8_t AnalogInput::kAccumulatorModuleNumber;
+const uint32_t AnalogInput::kAccumulatorNumChannels;
+const uint32_t AnalogInput::kAccumulatorChannels[] = {0, 1};
+
+/**
+ * Construct an analog input.
+ *
+ * @param channel The channel number on the roboRIO to represent. 0-3 are
+ * on-board 4-7 are on the MXP port.
+ */
+AnalogInput::AnalogInput(uint32_t channel) {
+  std::stringstream buf;
+  buf << "Analog Input " << channel;
+  Resource::CreateResourceObject(inputs, kAnalogInputs);
+
+  if (!checkAnalogInputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  if (inputs->Allocate(channel, buf.str()) ==
+      std::numeric_limits<uint32_t>::max()) {
+    CloneError(*inputs);
+    return;
+  }
+
+  m_channel = channel;
+
+  void* port = getPort(channel);
+  int32_t status = 0;
+  m_port = initializeAnalogInputPort(port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  freePort(port);
+
+  LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this);
+  HALReport(HALUsageReporting::kResourceType_AnalogChannel, channel);
+}
+
+/**
+ * Channel destructor.
+ */
+AnalogInput::~AnalogInput() {
+  freeAnalogInputPort(m_port);
+  inputs->Free(m_channel);
+}
+
+/**
+ * Get a sample straight from this channel.
+ * The sample is a 12-bit value representing the 0V to 5V range of the A/D
+ * converter in the module.
+ * The units are in A/D converter codes.  Use GetVoltage() to get the analog
+ * value in calibrated units.
+ * @return A sample straight from this channel.
+ */
+int16_t AnalogInput::GetValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int16_t value = getAnalogValue(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for this
+ * channel.
+ * The sample is 12-bit + the bits configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged
+ * 2**bits number of samples.
+ * This is not a sliding window.  The sample will not change until
+ * 2**(OversampleBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ * @return A sample from the oversample and average engine for this channel.
+ */
+int32_t AnalogInput::GetAverageValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int32_t value = getAnalogAverageValue(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * Get a scaled sample straight from this channel.
+ * The value is scaled to units of Volts using the calibrated scaling data from
+ * GetLSBWeight() and GetOffset().
+ * @return A scaled sample straight from this channel.
+ */
+float AnalogInput::GetVoltage() const {
+  if (StatusIsFatal()) return 0.0f;
+  int32_t status = 0;
+  float voltage = getAnalogVoltage(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return voltage;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for
+ * this channel.
+ * The value is scaled to units of Volts using the calibrated scaling data from
+ * GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will
+ * update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update
+ * more slowly.
+ * @return A scaled sample from the output of the oversample and average engine
+ * for this channel.
+ */
+float AnalogInput::GetAverageVoltage() const {
+  if (StatusIsFatal()) return 0.0f;
+  int32_t status = 0;
+  float voltage = getAnalogAverageVoltage(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return voltage;
+}
+
+/**
+ * Get the factory scaling least significant bit weight constant.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @return Least significant bit weight.
+ */
+uint32_t AnalogInput::GetLSBWeight() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int32_t lsbWeight = getAnalogLSBWeight(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return lsbWeight;
+}
+
+/**
+ * Get the factory scaling offset constant.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @return Offset constant.
+ */
+int32_t AnalogInput::GetOffset() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int32_t offset = getAnalogOffset(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return offset;
+}
+
+/**
+ * Get the channel number.
+ * @return The channel number.
+ */
+uint32_t AnalogInput::GetChannel() const {
+  if (StatusIsFatal()) return 0;
+  return m_channel;
+}
+
+/**
+ * Set the number of averaging bits.
+ * This sets the number of averaging bits. The actual number of averaged samples
+ * is 2^bits.
+ * Use averaging to improve the stability of your measurement at the expense of
+ * sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param bits Number of bits of averaging.
+ */
+void AnalogInput::SetAverageBits(uint32_t bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAnalogAverageBits(m_port, bits, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the number of averaging bits previously configured.
+ * This gets the number of averaging bits from the FPGA. The actual number of
+ * averaged samples is 2^bits.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @return Number of bits of averaging previously configured.
+ */
+uint32_t AnalogInput::GetAverageBits() const {
+  int32_t status = 0;
+  int32_t averageBits = getAnalogAverageBits(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return averageBits;
+}
+
+/**
+ * Set the number of oversample bits.
+ * This sets the number of oversample bits. The actual number of oversampled
+ * values is 2^bits.
+ * Use oversampling to improve the resolution of your measurements at the
+ * expense of sampling rate.
+ * The oversampling is done automatically in the FPGA.
+ *
+ * @param bits Number of bits of oversampling.
+ */
+void AnalogInput::SetOversampleBits(uint32_t bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAnalogOversampleBits(m_port, bits, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the number of oversample bits previously configured.
+ * This gets the number of oversample bits from the FPGA. The actual number of
+ * oversampled values is
+ * 2^bits. The oversampling is done automatically in the FPGA.
+ *
+ * @return Number of bits of oversampling previously configured.
+ */
+uint32_t AnalogInput::GetOversampleBits() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int32_t oversampleBits = getAnalogOversampleBits(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return oversampleBits;
+}
+
+/**
+ * Is the channel attached to an accumulator.
+ *
+ * @return The analog input is attached to an accumulator.
+ */
+bool AnalogInput::IsAccumulatorChannel() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool isAccum = isAccumulatorChannel(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return isAccum;
+}
+
+/**
+ * Initialize the accumulator.
+ */
+void AnalogInput::InitAccumulator() {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = 0;
+  int32_t status = 0;
+  initAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set an initial value for the accumulator.
+ *
+ * This will be added to all values returned to the user.
+ * @param initialValue The value that the accumulator should start from when
+ * reset.
+ */
+void AnalogInput::SetAccumulatorInitialValue(int64_t initialValue) {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = initialValue;
+}
+
+/**
+ * Resets the accumulator to the initial value.
+ */
+void AnalogInput::ResetAccumulator() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  resetAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  if (!StatusIsFatal()) {
+    // Wait until the next sample, so the next call to GetAccumulator*()
+    // won't have old values.
+    const float sampleTime = 1.0f / GetSampleRate();
+    const float overSamples = 1 << GetOversampleBits();
+    const float averageSamples = 1 << GetAverageBits();
+    Wait(sampleTime * overSamples * averageSamples);
+  }
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each A/D value before it is added to the
+ * accumulator. This
+ * is used for the center value of devices like gyros and accelerometers to
+ * take the device offset into account when integrating.
+ *
+ * This center value is based on the output of the oversampled and averaged
+ * source from the accumulator
+ * channel. Because of this, any non-zero oversample bits will affect the size
+ * of the value for this field.
+ */
+void AnalogInput::SetAccumulatorCenter(int32_t center) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAccumulatorCenter(m_port, center, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the accumulator's deadband.
+ * @param
+ */
+void AnalogInput::SetAccumulatorDeadband(int32_t deadband) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAccumulatorDeadband(m_port, deadband, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * Read the value that has been accumulating.
+ * The accumulator is attached after the oversample and average engine.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t AnalogInput::GetAccumulatorValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t value = getAccumulatorValue(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value + m_accumulatorOffset;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last
+ * Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+uint32_t AnalogInput::GetAccumulatorCount() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  uint32_t count = getAccumulatorCount(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return count;
+}
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count from the FPGA atomically.
+ * This can be used for averaging.
+ *
+ * @param value Reference to the 64-bit accumulated output.
+ * @param count Reference to the number of accumulation cycles.
+ */
+void AnalogInput::GetAccumulatorOutput(int64_t &value, uint32_t &count) const {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  getAccumulatorOutput(m_port, &value, &count, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  value += m_accumulatorOffset;
+}
+
+/**
+ * Set the sample rate per channel for all analog channels.
+ * The maximum rate is 500kS/s divided by the number of channels in use.
+ * This is 62500 samples/s per channel.
+ * @param samplesPerSecond The number of samples per second.
+ */
+void AnalogInput::SetSampleRate(float samplesPerSecond) {
+  int32_t status = 0;
+  setAnalogSampleRate(samplesPerSecond, &status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the current sample rate for all channels
+ *
+ * @return Sample rate.
+ */
+float AnalogInput::GetSampleRate() {
+  int32_t status = 0;
+  float sampleRate = getAnalogSampleRate(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return sampleRate;
+}
+
+/**
+ * Get the Average value for the PID Source base object.
+ *
+ * @return The average voltage.
+ */
+double AnalogInput::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  return GetAverageVoltage();
+}
+
+void AnalogInput::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetAverageVoltage());
+  }
+}
+
+void AnalogInput::StartLiveWindowMode() {}
+
+void AnalogInput::StopLiveWindowMode() {}
+
+std::string AnalogInput::GetSmartDashboardType() const {
+  return "Analog Input";
+}
+
+void AnalogInput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> AnalogInput::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/AnalogOutput.cpp b/wpilibc/Athena/src/AnalogOutput.cpp
new file mode 100644
index 0000000..74a1f9c
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogOutput.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* 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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogOutput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+#include "HAL/Port.h"
+
+#include <limits>
+#include <sstream>
+
+static std::unique_ptr<Resource> outputs;
+
+/**
+ * Construct an analog output on the given channel.
+ * All analog outputs are located on the MXP port.
+ * @param The channel number on the roboRIO to represent.
+ */
+AnalogOutput::AnalogOutput(uint32_t channel) {
+  Resource::CreateResourceObject(outputs, kAnalogOutputs);
+
+  std::stringstream buf;
+  buf << "analog input " << channel;
+
+  if (!checkAnalogOutputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    m_channel = std::numeric_limits<uint32_t>::max();
+    m_port = nullptr;
+    return;
+  }
+
+  if (outputs->Allocate(channel, buf.str()) ==
+      std::numeric_limits<uint32_t>::max()) {
+    CloneError(*outputs);
+    m_channel = std::numeric_limits<uint32_t>::max();
+    m_port = nullptr;
+    return;
+  }
+
+  m_channel = channel;
+
+  void* port = getPort(m_channel);
+  int32_t status = 0;
+  m_port = initializeAnalogOutputPort(port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  freePort(port);
+
+  LiveWindow::GetInstance()->AddActuator("AnalogOutput", m_channel, this);
+  HALReport(HALUsageReporting::kResourceType_AnalogOutput, m_channel);
+}
+
+/**
+ * Destructor. Frees analog output resource
+ */
+AnalogOutput::~AnalogOutput() {
+  freeAnalogOutputPort(m_port);
+  outputs->Free(m_channel);
+}
+
+/**
+ * Set the value of the analog output
+ *
+ * @param voltage The output value in Volts, from 0.0 to +5.0
+ */
+void AnalogOutput::SetVoltage(float voltage) {
+  int32_t status = 0;
+  setAnalogOutput(m_port, voltage, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the voltage of the analog output
+ *
+ * @return The value in Volts, from 0.0 to +5.0
+ */
+float AnalogOutput::GetVoltage() const {
+  int32_t status = 0;
+  float voltage = getAnalogOutput(m_port, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  return voltage;
+}
+
+void AnalogOutput::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetVoltage());
+  }
+}
+
+void AnalogOutput::StartLiveWindowMode() {}
+
+void AnalogOutput::StopLiveWindowMode() {}
+
+std::string AnalogOutput::GetSmartDashboardType() const {
+  return "Analog Output";
+}
+
+void AnalogOutput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> AnalogOutput::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/AnalogPotentiometer.cpp b/wpilibc/Athena/src/AnalogPotentiometer.cpp
new file mode 100644
index 0000000..1372d84
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogPotentiometer.cpp
@@ -0,0 +1,87 @@
+#include "AnalogPotentiometer.h"
+#include "ControllerPower.h"
+
+/**
+ * Construct an Analog Potentiometer object from a channel number.
+ * @param channel The channel number on the roboRIO to represent. 0-3 are
+ * on-board 4-7 are on the MXP port.
+ * @param fullRange The angular value (in desired units) representing the full
+ * 0-5V range of the input.
+ * @param offset The angular value (in desired units) representing the angular
+ * output at 0V.
+ */
+AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
+                                         double offset)
+    : m_analog_input(std::make_unique<AnalogInput>(channel)),
+      m_fullRange(fullRange),
+      m_offset(offset) {}
+
+/**
+ * Construct an Analog Potentiometer object from an existing Analog Input
+ * pointer.
+ * @param channel The existing Analog Input pointer
+ * @param fullRange The angular value (in desired units) representing the full
+ * 0-5V range of the input.
+ * @param offset The angular value (in desired units) representing the angular
+ * output at 0V.
+ */
+AnalogPotentiometer::AnalogPotentiometer(AnalogInput *input, double fullRange,
+                                         double offset)
+    : m_analog_input(input, NullDeleter<AnalogInput>()),
+      m_fullRange(fullRange),
+      m_offset(offset) {}
+
+/**
+ * Construct an Analog Potentiometer object from an existing Analog Input
+ * pointer.
+ * @param channel The existing Analog Input pointer
+ * @param fullRange The angular value (in desired units) representing the full
+ * 0-5V range of the input.
+ * @param offset The angular value (in desired units) representing the angular
+ * output at 0V.
+ */
+AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                                         double fullRange, double offset)
+    : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {}
+
+/**
+ * Get the current reading of the potentiometer.
+ *
+ * @return The current position of the potentiometer (in the units used for
+ * fullRaneg and offset).
+ */
+double AnalogPotentiometer::Get() const {
+  return (m_analog_input->GetVoltage() / ControllerPower::GetVoltage5V()) *
+             m_fullRange +
+         m_offset;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current reading.
+ */
+double AnalogPotentiometer::PIDGet() { return Get(); }
+
+/**
+ * @return the Smart Dashboard Type
+ */
+std::string AnalogPotentiometer::GetSmartDashboardType() const {
+  return "Analog Input";
+}
+
+/**
+ * Live Window code, only does anything if live window is activated.
+ */
+void AnalogPotentiometer::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void AnalogPotentiometer::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+std::shared_ptr<ITable> AnalogPotentiometer::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/AnalogTrigger.cpp b/wpilibc/Athena/src/AnalogTrigger.cpp
new file mode 100644
index 0000000..b49d6a0
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogTrigger.cpp
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogTrigger.h"
+
+#include "AnalogInput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "HAL/Port.h"
+
+#include <memory>
+
+/**
+ * Constructor for an analog trigger given a channel number.
+ *
+ * @param channel The channel number on the roboRIO to represent. 0-3 are
+ * on-board 4-7 are on the MXP port.
+ */
+AnalogTrigger::AnalogTrigger(int32_t channel) {
+  void* port = getPort(channel);
+  int32_t status = 0;
+  uint32_t index = 0;
+  m_trigger = initializeAnalogTrigger(port, &index, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  freePort(port);
+  m_index = index;
+
+  HALReport(HALUsageReporting::kResourceType_AnalogTrigger, channel);
+}
+
+/**
+ * Construct an analog trigger given an analog input.
+ * This should be used in the case of sharing an analog channel between the
+ * trigger and an analog input object.
+ * @param channel The pointer to the existing AnalogInput object
+ */
+AnalogTrigger::AnalogTrigger(AnalogInput *input) :
+    AnalogTrigger(input->GetChannel()) {
+}
+
+AnalogTrigger::~AnalogTrigger() {
+  int32_t status = 0;
+  cleanAnalogTrigger(m_trigger, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ * The limits are given in ADC codes.  If oversampling is used, the units must
+ * be scaled
+ * appropriately.
+ * @param lower The lower limit of the trigger in ADC codes (12-bit values).
+ * @param upper The upper limit of the trigger in ADC codes (12-bit values).
+ */
+void AnalogTrigger::SetLimitsRaw(int32_t lower, int32_t upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ * The limits are given as floating point voltage values.
+ * @param lower The lower limit of the trigger in Volts.
+ * @param upper The upper limit of the trigger in Volts.
+ */
+void AnalogTrigger::SetLimitsVoltage(float lower, float upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAnalogTriggerLimitsVoltage(m_trigger, lower, upper, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Configure the analog trigger to use the averaged vs. raw values.
+ * If the value is true, then the averaged value is selected for the analog
+ * trigger, otherwise
+ * the immediate value is used.
+ * @param useAveragedValue If true, use the Averaged value, otherwise use the
+ * instantaneous reading
+ */
+void AnalogTrigger::SetAveraged(bool useAveragedValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAnalogTriggerAveraged(m_trigger, useAveragedValue, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Configure the analog trigger to use a filtered value.
+ * The analog trigger will operate with a 3 point average rejection filter. This
+ * is designed to
+ * help with 360 degree pot applications for the period where the pot crosses
+ * through zero.
+ * @param useFilteredValue If true, use the 3 point rejection filter, otherwise
+ * use the unfiltered value
+ */
+void AnalogTrigger::SetFiltered(bool useFilteredValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setAnalogTriggerFiltered(m_trigger, useFilteredValue, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Return the index of the analog trigger.
+ * This is the FPGA index of this analog trigger instance.
+ * @return The index of the analog trigger.
+ */
+uint32_t AnalogTrigger::GetIndex() const {
+  if (StatusIsFatal()) return std::numeric_limits<uint32_t>::max();
+  return m_index;
+}
+
+/**
+ * Return the InWindow output of the analog trigger.
+ * True if the analog input is between the upper and lower limits.
+ * @return True if the analog input is between the upper and lower limits.
+ */
+bool AnalogTrigger::GetInWindow() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = getAnalogTriggerInWindow(m_trigger, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return result;
+}
+
+/**
+ * Return the TriggerState output of the analog trigger.
+ * True if above upper limit.
+ * False if below lower limit.
+ * If in Hysteresis, maintain previous state.
+ * @return True if above upper limit. False if below lower limit. If in
+ * Hysteresis, maintain previous state.
+ */
+bool AnalogTrigger::GetTriggerState() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = getAnalogTriggerTriggerState(m_trigger, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return result;
+}
+
+/**
+ * Creates an AnalogTriggerOutput object.
+ * Gets an output object that can be used for routing.
+ * Caller is responsible for deleting the AnalogTriggerOutput object.
+ * @param type An enum of the type of output object to create.
+ * @return A pointer to a new AnalogTriggerOutput object.
+ */
+std::shared_ptr<AnalogTriggerOutput> AnalogTrigger::CreateOutput(
+    AnalogTriggerType type) const {
+  if (StatusIsFatal()) return nullptr;
+  return std::shared_ptr<AnalogTriggerOutput>(
+      new AnalogTriggerOutput(*this, type), NullDeleter<AnalogTriggerOutput>());
+}
diff --git a/wpilibc/Athena/src/AnalogTriggerOutput.cpp b/wpilibc/Athena/src/AnalogTriggerOutput.cpp
new file mode 100644
index 0000000..8254275
--- /dev/null
+++ b/wpilibc/Athena/src/AnalogTriggerOutput.cpp
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogTriggerOutput.h"
+#include "AnalogTrigger.h"
+#include "WPIErrors.h"
+
+/**
+ * Create an object that represents one of the four outputs from an analog
+ * trigger.
+ *
+ * Because this class derives from DigitalSource, it can be passed into routing
+ * functions
+ * for Counter, Encoder, etc.
+ *
+ * @param trigger A pointer to the trigger for which this is an output.
+ * @param outputType An enum that specifies the output on the trigger to
+ * represent.
+ */
+AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger &trigger,
+                                         AnalogTriggerType outputType)
+    : m_trigger(trigger), m_outputType(outputType) {
+  HALReport(HALUsageReporting::kResourceType_AnalogTriggerOutput,
+            trigger.GetIndex(), outputType);
+}
+
+AnalogTriggerOutput::~AnalogTriggerOutput() {
+  if (m_interrupt != nullptr) {
+    int32_t status = 0;
+    cleanInterrupts(m_interrupt, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    m_interrupt = nullptr;
+    m_interrupts->Free(m_interruptIndex);
+  }
+}
+
+/**
+ * Get the state of the analog trigger output.
+ * @return The state of the analog trigger output.
+ */
+bool AnalogTriggerOutput::Get() const {
+  int32_t status = 0;
+  bool result =
+      getAnalogTriggerOutput(m_trigger.m_trigger, m_outputType, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return result;
+}
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+uint32_t AnalogTriggerOutput::GetChannelForRouting() const {
+  return (m_trigger.m_index << 2) + m_outputType;
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+uint32_t AnalogTriggerOutput::GetModuleForRouting() const { return 0; }
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+bool AnalogTriggerOutput::GetAnalogTriggerForRouting() const { return true; }
diff --git a/wpilibc/Athena/src/BuiltInAccelerometer.cpp b/wpilibc/Athena/src/BuiltInAccelerometer.cpp
new file mode 100644
index 0000000..a504524
--- /dev/null
+++ b/wpilibc/Athena/src/BuiltInAccelerometer.cpp
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "BuiltInAccelerometer.h"
+#include "HAL/HAL.hpp"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Constructor.
+ * @param range The range the accelerometer will measure
+ */
+BuiltInAccelerometer::BuiltInAccelerometer(Range range) {
+  SetRange(range);
+
+  HALReport(HALUsageReporting::kResourceType_Accelerometer, 0, 0,
+            "Built-in accelerometer");
+  LiveWindow::GetInstance()->AddSensor((std::string) "BuiltInAccel", 0, this);
+}
+
+/** {@inheritdoc} */
+void BuiltInAccelerometer::SetRange(Range range) {
+  if (range == kRange_16G) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange, "16G range not supported (use k2G, k4G, or k8G)");
+  }
+
+  setAccelerometerActive(false);
+  setAccelerometerRange((AccelerometerRange)range);
+  setAccelerometerActive(true);
+}
+
+/**
+ * @return The acceleration of the RoboRIO along the X axis in g-forces
+ */
+double BuiltInAccelerometer::GetX() { return getAccelerometerX(); }
+
+/**
+ * @return The acceleration of the RoboRIO along the Y axis in g-forces
+ */
+double BuiltInAccelerometer::GetY() { return getAccelerometerY(); }
+
+/**
+ * @return The acceleration of the RoboRIO along the Z axis in g-forces
+ */
+double BuiltInAccelerometer::GetZ() { return getAccelerometerZ(); }
+
+std::string BuiltInAccelerometer::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void BuiltInAccelerometer::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void BuiltInAccelerometer::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("X", GetX());
+    m_table->PutNumber("Y", GetY());
+    m_table->PutNumber("Z", GetZ());
+  }
+}
+
+std::shared_ptr<ITable> BuiltInAccelerometer::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/CANJaguar.cpp b/wpilibc/Athena/src/CANJaguar.cpp
new file mode 100644
index 0000000..fc71e84
--- /dev/null
+++ b/wpilibc/Athena/src/CANJaguar.cpp
@@ -0,0 +1,2013 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2009. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "CANJaguar.h"
+#include "Timer.h"
+#define tNIRIO_i32 int
+#include "NetworkCommunication/CANSessionMux.h"
+#include "WPIErrors.h"
+#include <cstdio>
+#include <cassert>
+#include "LiveWindow/LiveWindow.h"
+
+/* we are on ARM-LE now, not Freescale so no need to swap */
+#define swap16(x) (x)
+#define swap32(x) (x)
+
+/* Compare floats for equality as fixed point numbers */
+#define FXP8_EQ(a, b) ((int16_t)((a)*256.0) == (int16_t)((b)*256.0))
+#define FXP16_EQ(a, b) ((int32_t)((a)*65536.0) == (int32_t)((b)*65536.0))
+
+const int32_t CANJaguar::kControllerRate;
+constexpr double CANJaguar::kApproxBusVoltage;
+
+static const int32_t kSendMessagePeriod = 20;
+static const uint32_t kFullMessageIDMask =
+    (CAN_MSGID_API_M | CAN_MSGID_MFR_M | CAN_MSGID_DTYPE_M);
+
+static const int32_t kReceiveStatusAttempts = 50;
+
+static std::unique_ptr<Resource> allocated;
+
+static int32_t sendMessageHelper(uint32_t messageID, const uint8_t *data,
+                                 uint8_t dataSize, int32_t period) {
+  static const uint32_t kTrustedMessages[] = {
+      LM_API_VOLT_T_EN,  LM_API_VOLT_T_SET,  LM_API_SPD_T_EN, LM_API_SPD_T_SET,
+      LM_API_VCOMP_T_EN, LM_API_VCOMP_T_SET, LM_API_POS_T_EN, LM_API_POS_T_SET,
+      LM_API_ICTRL_T_EN, LM_API_ICTRL_T_SET};
+
+  int32_t status = 0;
+
+  for (auto& kTrustedMessage : kTrustedMessages) {
+    if ((kFullMessageIDMask & messageID) == kTrustedMessage) {
+      uint8_t dataBuffer[8];
+      dataBuffer[0] = 0;
+      dataBuffer[1] = 0;
+
+      // Make sure the data will still fit after adjusting for the token.
+      assert(dataSize <= 6);
+
+      for (uint8_t j = 0; j < dataSize; j++) {
+        dataBuffer[j + 2] = data[j];
+      }
+
+      FRC_NetworkCommunication_CANSessionMux_sendMessage(
+          messageID, dataBuffer, dataSize + 2, period, &status);
+
+      return status;
+    }
+  }
+
+  FRC_NetworkCommunication_CANSessionMux_sendMessage(messageID, data, dataSize,
+                                                     period, &status);
+
+  return status;
+}
+
+/**
+ * Common initialization code called by all constructors.
+ */
+void CANJaguar::InitCANJaguar() {
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+
+  bool receivedFirmwareVersion = false;
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  // Request firmware and hardware version only once
+  requestMessage(CAN_IS_FRAME_REMOTE | CAN_MSGID_API_FIRMVER);
+  requestMessage(LM_API_HWVER);
+
+  // Wait until we've gotten all of the status data at least once.
+  for (int i = 0; i < kReceiveStatusAttempts; i++) {
+    Wait(0.001);
+
+    setupPeriodicStatus();
+    updatePeriodicStatus();
+
+    if (!receivedFirmwareVersion &&
+        getMessage(CAN_MSGID_API_FIRMVER, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      m_firmwareVersion = unpackint32_t(dataBuffer);
+      receivedFirmwareVersion = true;
+    }
+
+    if (m_receivedStatusMessage0 && m_receivedStatusMessage1 &&
+        m_receivedStatusMessage2 && receivedFirmwareVersion) {
+      break;
+    }
+  }
+
+  if (!m_receivedStatusMessage0 || !m_receivedStatusMessage1 ||
+      !m_receivedStatusMessage2 || !receivedFirmwareVersion) {
+    wpi_setWPIErrorWithContext(JaguarMessageNotFound, "Status data not found");
+  }
+
+  if (getMessage(LM_API_HWVER, CAN_MSGID_FULL_M, dataBuffer, &dataSize))
+    m_hardwareVersion = dataBuffer[0];
+
+  if (m_deviceNumber < 1 || m_deviceNumber > 63) {
+    std::stringstream buf;
+    buf << "device number \"" << m_deviceNumber
+        << "\" must be between 1 and 63";
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, buf.str());
+    return;
+  }
+
+  if (StatusIsFatal()) return;
+
+  // 3330 was the first shipping RDK firmware version for the Jaguar
+  if (m_firmwareVersion >= 3330 || m_firmwareVersion < 108) {
+    std::stringstream buf;
+    if (m_firmwareVersion < 3330) {
+      buf << "Jag #" << m_deviceNumber << " firmware (" << m_firmwareVersion
+          << ") is too old (must be at least version 108 "
+             "of the FIRST approved firmware)";
+    } else {
+      buf << "Jag #" << m_deviceNumber << " firmware (" << m_firmwareVersion
+          << ") is not FIRST approved (must be at least "
+             "version 108 of the FIRST approved firmware)";
+    }
+    wpi_setWPIErrorWithContext(JaguarVersionError, buf.str());
+    return;
+  }
+
+  switch (m_controlMode) {
+    case kPercentVbus:
+    case kVoltage:
+      // No additional configuration required... start enabled.
+      EnableControl();
+      break;
+    default:
+      break;
+  }
+  HALReport(HALUsageReporting::kResourceType_CANJaguar, m_deviceNumber,
+            m_controlMode);
+  LiveWindow::GetInstance()->AddActuator("CANJaguar", m_deviceNumber, this);
+}
+
+/**
+ * Constructor for the CANJaguar device.<br>
+ * By default the device is configured in Percent mode.
+ * The control mode can be changed by calling one of the control modes listed
+ * below.
+ *
+ * @param deviceNumber The address of the Jaguar on the CAN bus.
+ * @see CANJaguar#SetCurrentMode(double, double, double)
+ * @see CANJaguar#SetCurrentMode(PotentiometerTag, double, double, double)
+ * @see CANJaguar#SetCurrentMode(EncoderTag, int, double, double, double)
+ * @see CANJaguar#SetCurrentMode(QuadEncoderTag, int, double, double, double)
+ * @see CANJaguar#SetPercentMode()
+ * @see CANJaguar#SetPercentMode(PotentiometerTag)
+ * @see CANJaguar#SetPercentMode(EncoderTag, int)
+ * @see CANJaguar#SetPercentMode(QuadEncoderTag, int)
+ * @see CANJaguar#SetPositionMode(PotentiometerTag, double, double, double)
+ * @see CANJaguar#SetPositionMode(QuadEncoderTag, int, double, double, double)
+ * @see CANJaguar#SetSpeedMode(EncoderTag, int, double, double, double)
+ * @see CANJaguar#SetSpeedMode(QuadEncoderTag, int, double, double, double)
+ * @see CANJaguar#SetVoltageMode()
+ * @see CANJaguar#SetVoltageMode(PotentiometerTag)
+ * @see CANJaguar#SetVoltageMode(EncoderTag, int)
+ * @see CANJaguar#SetVoltageMode(QuadEncoderTag, int)
+ */
+CANJaguar::CANJaguar(uint8_t deviceNumber)
+    : m_deviceNumber(deviceNumber) {
+  std::stringstream buf;
+  buf << "CANJaguar device number " << m_deviceNumber;
+  Resource::CreateResourceObject(allocated, 63);
+
+  if (allocated->Allocate(m_deviceNumber - 1, buf.str()) ==
+      std::numeric_limits<uint32_t>::max()) {
+    CloneError(*allocated);
+    return;
+  }
+
+  SetPercentMode();
+  InitCANJaguar();
+  ConfigMaxOutputVoltage(kApproxBusVoltage);
+}
+
+CANJaguar::~CANJaguar() {
+  allocated->Free(m_deviceNumber - 1);
+
+  int32_t status;
+
+  // Disable periodic setpoints
+  if (m_controlMode == kPercentVbus)
+    FRC_NetworkCommunication_CANSessionMux_sendMessage(
+        m_deviceNumber | LM_API_VOLT_T_SET, nullptr, 0,
+        CAN_SEND_PERIOD_STOP_REPEATING, &status);
+  else if (m_controlMode == kSpeed)
+    FRC_NetworkCommunication_CANSessionMux_sendMessage(
+        m_deviceNumber | LM_API_SPD_T_SET, nullptr, 0,
+        CAN_SEND_PERIOD_STOP_REPEATING, &status);
+  else if (m_controlMode == kPosition)
+    FRC_NetworkCommunication_CANSessionMux_sendMessage(
+        m_deviceNumber | LM_API_POS_T_SET, nullptr, 0,
+        CAN_SEND_PERIOD_STOP_REPEATING, &status);
+  else if (m_controlMode == kCurrent)
+    FRC_NetworkCommunication_CANSessionMux_sendMessage(
+        m_deviceNumber | LM_API_ICTRL_T_SET, nullptr, 0,
+        CAN_SEND_PERIOD_STOP_REPEATING, &status);
+  else if (m_controlMode == kVoltage)
+    FRC_NetworkCommunication_CANSessionMux_sendMessage(
+        m_deviceNumber | LM_API_VCOMP_T_SET, nullptr, 0,
+        CAN_SEND_PERIOD_STOP_REPEATING, &status);
+
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * @return The CAN ID passed in the constructor
+ */
+uint8_t CANJaguar::getDeviceNumber() const { return m_deviceNumber; }
+
+/**
+ * Sets the output set-point value.
+ *
+ * The scale and the units depend on the mode the Jaguar is in.<br>
+ * In percentVbus Mode, the outputValue is from -1.0 to 1.0 (same as PWM
+ * Jaguar).<br>
+ * In voltage Mode, the outputValue is in volts. <br>
+ * In current Mode, the outputValue is in amps. <br>
+ * In speed Mode, the outputValue is in rotations/minute.<br>
+ * In position Mode, the outputValue is in rotations.
+ *
+ * @param outputValue The set-point to sent to the motor controller.
+ * @param syncGroup The update group to add this Set() to, pending
+ * UpdateSyncGroup().  If 0, update immediately.
+ */
+void CANJaguar::Set(float outputValue, uint8_t syncGroup) {
+  uint32_t messageID;
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  if (m_safetyHelper && !m_safetyHelper->IsAlive() && m_controlEnabled) {
+    EnableControl();
+  }
+
+  if (m_controlEnabled) {
+    switch (m_controlMode) {
+      case kPercentVbus: {
+        messageID = LM_API_VOLT_T_SET;
+        if (outputValue > 1.0) outputValue = 1.0;
+        if (outputValue < -1.0) outputValue = -1.0;
+        dataSize = packPercentage(dataBuffer,
+                                  (m_isInverted ? -outputValue : outputValue));
+      } break;
+      case kSpeed: {
+        messageID = LM_API_SPD_T_SET;
+        dataSize = packFXP16_16(dataBuffer,
+                                (m_isInverted ? -outputValue : outputValue));
+      } break;
+      case kPosition: {
+        messageID = LM_API_POS_T_SET;
+        dataSize = packFXP16_16(dataBuffer, outputValue);
+      } break;
+      case kCurrent: {
+        messageID = LM_API_ICTRL_T_SET;
+        dataSize = packFXP8_8(dataBuffer, outputValue);
+      } break;
+      case kVoltage: {
+        messageID = LM_API_VCOMP_T_SET;
+        dataSize =
+            packFXP8_8(dataBuffer, (m_isInverted ? -outputValue : outputValue));
+      } break;
+      default:
+        wpi_setWPIErrorWithContext(IncompatibleMode,
+                                   "The Jaguar only supports Current, Voltage, "
+                                   "Position, Speed, and Percent (Throttle) "
+                                   "modes.");
+        return;
+    }
+    if (syncGroup != 0) {
+      dataBuffer[dataSize] = syncGroup;
+      dataSize++;
+    }
+
+    sendMessage(messageID, dataBuffer, dataSize, kSendMessagePeriod);
+
+    if (m_safetyHelper) m_safetyHelper->Feed();
+  }
+
+  m_value = outputValue;
+
+  verify();
+}
+
+/**
+ * Get the recently set outputValue setpoint.
+ *
+ * The scale and the units depend on the mode the Jaguar is in.<br>
+ * In percentVbus Mode, the outputValue is from -1.0 to 1.0 (same as PWM
+ * Jaguar).<br>
+ * In voltage Mode, the outputValue is in volts.<br>
+ * In current Mode, the outputValue is in amps.<br>
+ * In speed Mode, the outputValue is in rotations/minute.<br>
+ * In position Mode, the outputValue is in rotations.<br>
+ *
+ * @return The most recently set outputValue setpoint.
+ */
+float CANJaguar::Get() const { return m_value; }
+
+/**
+* Common interface for disabling a motor.
+*
+* @deprecated Call {@link #DisableControl()} instead.
+*/
+void CANJaguar::Disable() { DisableControl(); }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @deprecated Call Set instead.
+ *
+ * @param output Write out the PercentVbus value as was computed by the
+ * PIDController
+ */
+void CANJaguar::PIDWrite(float output) {
+  if (m_controlMode == kPercentVbus) {
+    Set(output);
+  } else {
+    wpi_setWPIErrorWithContext(IncompatibleMode,
+                               "PID only supported in PercentVbus mode");
+  }
+}
+
+uint8_t CANJaguar::packPercentage(uint8_t *buffer, double value) {
+  int16_t intValue = (int16_t)(value * 32767.0);
+  *((int16_t *)buffer) = swap16(intValue);
+  return sizeof(int16_t);
+}
+
+uint8_t CANJaguar::packFXP8_8(uint8_t *buffer, double value) {
+  int16_t intValue = (int16_t)(value * 256.0);
+  *((int16_t *)buffer) = swap16(intValue);
+  return sizeof(int16_t);
+}
+
+uint8_t CANJaguar::packFXP16_16(uint8_t *buffer, double value) {
+  int32_t intValue = (int32_t)(value * 65536.0);
+  *((int32_t *)buffer) = swap32(intValue);
+  return sizeof(int32_t);
+}
+
+uint8_t CANJaguar::packint16_t(uint8_t *buffer, int16_t value) {
+  *((int16_t *)buffer) = swap16(value);
+  return sizeof(int16_t);
+}
+
+uint8_t CANJaguar::packint32_t(uint8_t *buffer, int32_t value) {
+  *((int32_t *)buffer) = swap32(value);
+  return sizeof(int32_t);
+}
+
+double CANJaguar::unpackPercentage(uint8_t *buffer) const {
+  int16_t value = *((int16_t *)buffer);
+  value = swap16(value);
+  return value / 32767.0;
+}
+
+double CANJaguar::unpackFXP8_8(uint8_t *buffer) const {
+  int16_t value = *((int16_t *)buffer);
+  value = swap16(value);
+  return value / 256.0;
+}
+
+double CANJaguar::unpackFXP16_16(uint8_t *buffer) const {
+  int32_t value = *((int32_t *)buffer);
+  value = swap32(value);
+  return value / 65536.0;
+}
+
+int16_t CANJaguar::unpackint16_t(uint8_t *buffer) const {
+  int16_t value = *((int16_t *)buffer);
+  return swap16(value);
+}
+
+int32_t CANJaguar::unpackint32_t(uint8_t *buffer) const {
+  int32_t value = *((int32_t *)buffer);
+  return swap32(value);
+}
+
+/**
+ * Send a message to the Jaguar.
+ *
+ * @param messageID The messageID to be used on the CAN bus (device number is
+ * added internally)
+ * @param data The up to 8 bytes of data to be sent with the message
+ * @param dataSize Specify how much of the data in "data" to send
+ * @param periodic If positive, tell Network Communications to send the message
+ * 	every "period" milliseconds.
+ */
+void CANJaguar::sendMessage(uint32_t messageID, const uint8_t *data,
+                            uint8_t dataSize, int32_t period) {
+  int32_t localStatus =
+      sendMessageHelper(messageID | m_deviceNumber, data, dataSize, period);
+
+  if (localStatus < 0) {
+    wpi_setErrorWithContext(localStatus, "sendMessage");
+  }
+}
+
+/**
+ * Request a message from the Jaguar, but don't wait for it to arrive.
+ *
+ * @param messageID The message to request
+ * @param periodic If positive, tell Network Communications to send the message
+ * 	every "period" milliseconds.
+ */
+void CANJaguar::requestMessage(uint32_t messageID, int32_t period) {
+  sendMessageHelper(messageID | m_deviceNumber, nullptr, 0, period);
+}
+
+/**
+ * Get a previously requested message.
+ *
+ * Jaguar always generates a message with the same message ID when replying.
+ *
+ * @param messageID The messageID to read from the CAN bus (device number is
+ * added internally)
+ * @param data The up to 8 bytes of data that was received with the message
+ * @param dataSize Indicates how much data was received
+ *
+ * @return true if the message was found.  Otherwise, no new message is
+ * available.
+ */
+bool CANJaguar::getMessage(uint32_t messageID, uint32_t messageMask,
+                           uint8_t *data, uint8_t *dataSize) const {
+  uint32_t targetedMessageID = messageID | m_deviceNumber;
+  int32_t status = 0;
+  uint32_t timeStamp;
+
+  // Caller may have set bit31 for remote frame transmission so clear invalid
+  // bits[31-29]
+  targetedMessageID &= CAN_MSGID_FULL_M;
+
+  // Get the data.
+  FRC_NetworkCommunication_CANSessionMux_receiveMessage(
+      &targetedMessageID, messageMask, data, dataSize, &timeStamp, &status);
+
+  // Do we already have the most recent value?
+  if (status == ERR_CANSessionMux_MessageNotFound)
+    return false;
+  else
+    wpi_setErrorWithContext(status, "receiveMessage");
+
+  return true;
+}
+
+/**
+ * Enables periodic status updates from the Jaguar.
+ */
+void CANJaguar::setupPeriodicStatus() {
+  uint8_t data[8];
+  uint8_t dataSize;
+
+  // Message 0 returns bus voltage, output voltage, output current, and
+  // temperature.
+  static const uint8_t kMessage0Data[] = {
+      LM_PSTAT_VOLTBUS_B0, LM_PSTAT_VOLTBUS_B1, LM_PSTAT_VOLTOUT_B0,
+      LM_PSTAT_VOLTOUT_B1, LM_PSTAT_CURRENT_B0, LM_PSTAT_CURRENT_B1,
+      LM_PSTAT_TEMP_B0,    LM_PSTAT_TEMP_B1};
+
+  // Message 1 returns position and speed
+  static const uint8_t kMessage1Data[] = {
+      LM_PSTAT_POS_B0, LM_PSTAT_POS_B1, LM_PSTAT_POS_B2, LM_PSTAT_POS_B3,
+      LM_PSTAT_SPD_B0, LM_PSTAT_SPD_B1, LM_PSTAT_SPD_B2, LM_PSTAT_SPD_B3};
+
+  // Message 2 returns limits and faults
+  static const uint8_t kMessage2Data[] = {LM_PSTAT_LIMIT_CLR, LM_PSTAT_FAULT,
+                                          LM_PSTAT_END};
+
+  dataSize = packint16_t(data, kSendMessagePeriod);
+  sendMessage(LM_API_PSTAT_PER_EN_S0, data, dataSize);
+  sendMessage(LM_API_PSTAT_PER_EN_S1, data, dataSize);
+  sendMessage(LM_API_PSTAT_PER_EN_S2, data, dataSize);
+
+  dataSize = 8;
+  sendMessage(LM_API_PSTAT_CFG_S0, kMessage0Data, dataSize);
+  sendMessage(LM_API_PSTAT_CFG_S1, kMessage1Data, dataSize);
+  sendMessage(LM_API_PSTAT_CFG_S2, kMessage2Data, dataSize);
+}
+
+/**
+ * Check for new periodic status updates and unpack them into local variables
+ */
+void CANJaguar::updatePeriodicStatus() const {
+  uint8_t data[8];
+  uint8_t dataSize;
+
+  // Check if a new bus voltage/output voltage/current/temperature message
+  // has arrived and unpack the values into the cached member variables
+  if (getMessage(LM_API_PSTAT_DATA_S0, CAN_MSGID_FULL_M, data, &dataSize)) {
+    m_mutex.lock();
+    m_busVoltage = unpackFXP8_8(data);
+    m_outputVoltage = unpackPercentage(data + 2) * m_busVoltage;
+    m_outputCurrent = unpackFXP8_8(data + 4);
+    m_temperature = unpackFXP8_8(data + 6);
+    m_mutex.unlock();
+
+    m_receivedStatusMessage0 = true;
+  }
+
+  // Check if a new position/speed message has arrived and do the same
+  if (getMessage(LM_API_PSTAT_DATA_S1, CAN_MSGID_FULL_M, data, &dataSize)) {
+    m_mutex.lock();
+    m_position = unpackFXP16_16(data);
+    m_speed = unpackFXP16_16(data + 4);
+    m_mutex.unlock();
+
+    m_receivedStatusMessage1 = true;
+  }
+
+  // Check if a new limits/faults message has arrived and do the same
+  if (getMessage(LM_API_PSTAT_DATA_S2, CAN_MSGID_FULL_M, data, &dataSize)) {
+    m_mutex.lock();
+    m_limits = data[0];
+    m_faults = data[1];
+    m_mutex.unlock();
+
+    m_receivedStatusMessage2 = true;
+  }
+}
+
+/**
+ * Check all unverified params and make sure they're equal to their local
+ * cached versions. If a value isn't available, it gets requested.  If a value
+ * doesn't match up, it gets set again.
+ */
+void CANJaguar::verify() {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  // If the Jaguar lost power, everything should be considered unverified.
+  if (getMessage(LM_API_STATUS_POWER, CAN_MSGID_FULL_M, dataBuffer,
+                 &dataSize)) {
+    bool powerCycled = (bool)dataBuffer[0];
+
+    if (powerCycled) {
+      // Clear the power cycled bit
+      dataBuffer[0] = 1;
+      sendMessage(LM_API_STATUS_POWER, dataBuffer, sizeof(uint8_t));
+
+      // Mark everything as unverified
+      m_controlModeVerified = false;
+      m_speedRefVerified = false;
+      m_posRefVerified = false;
+      m_neutralModeVerified = false;
+      m_encoderCodesPerRevVerified = false;
+      m_potentiometerTurnsVerified = false;
+      m_forwardLimitVerified = false;
+      m_reverseLimitVerified = false;
+      m_limitModeVerified = false;
+      m_maxOutputVoltageVerified = false;
+      m_faultTimeVerified = false;
+
+      if (m_controlMode == kPercentVbus || m_controlMode == kVoltage) {
+        m_voltageRampRateVerified = false;
+      } else {
+        m_pVerified = false;
+        m_iVerified = false;
+        m_dVerified = false;
+      }
+
+      // Verify periodic status messages again
+      m_receivedStatusMessage0 = false;
+      m_receivedStatusMessage1 = false;
+      m_receivedStatusMessage2 = false;
+
+      // Remove any old values from netcomms. Otherwise, parameters are
+      // incorrectly marked as verified based on stale messages.
+      getMessage(LM_API_SPD_REF, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_POS_REF, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_SPD_PC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_POS_PC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_ICTRL_PC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_SPD_IC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_POS_IC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_ICTRL_IC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_SPD_DC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_POS_DC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_ICTRL_DC, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_CFG_BRAKE_COAST, CAN_MSGID_FULL_M, dataBuffer,
+                 &dataSize);
+      getMessage(LM_API_CFG_ENC_LINES, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_CFG_POT_TURNS, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_CFG_LIMIT_MODE, CAN_MSGID_FULL_M, dataBuffer,
+                 &dataSize);
+      getMessage(LM_API_CFG_LIMIT_FWD, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_CFG_LIMIT_REV, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_CFG_MAX_VOUT, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_VOLT_SET_RAMP, CAN_MSGID_FULL_M, dataBuffer, &dataSize);
+      getMessage(LM_API_VCOMP_COMP_RAMP, CAN_MSGID_FULL_M, dataBuffer,
+                 &dataSize);
+      getMessage(LM_API_CFG_FAULT_TIME, CAN_MSGID_FULL_M, dataBuffer,
+                 &dataSize);
+    }
+  } else {
+    requestMessage(LM_API_STATUS_POWER);
+  }
+
+  // Verify that any recently set parameters are correct
+  if (!m_controlModeVerified && m_controlEnabled) {
+    if (getMessage(LM_API_STATUS_CMODE, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      ControlMode mode = (ControlMode)dataBuffer[0];
+
+      if (m_controlMode == mode)
+        m_controlModeVerified = true;
+      else
+        // Enable control again to resend the control mode
+        EnableControl();
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_STATUS_CMODE);
+    }
+  }
+
+  if (!m_speedRefVerified) {
+    if (getMessage(LM_API_SPD_REF, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) {
+      uint8_t speedRef = dataBuffer[0];
+
+      if (m_speedReference == speedRef)
+        m_speedRefVerified = true;
+      else
+        // It's wrong - set it again
+        SetSpeedReference(m_speedReference);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_SPD_REF);
+    }
+  }
+
+  if (!m_posRefVerified) {
+    if (getMessage(LM_API_POS_REF, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) {
+      uint8_t posRef = dataBuffer[0];
+
+      if (m_positionReference == posRef)
+        m_posRefVerified = true;
+      else
+        // It's wrong - set it again
+        SetPositionReference(m_positionReference);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_POS_REF);
+    }
+  }
+
+  if (!m_pVerified) {
+    uint32_t message = 0;
+
+    if (m_controlMode == kSpeed)
+      message = LM_API_SPD_PC;
+    else if (m_controlMode == kPosition)
+      message = LM_API_POS_PC;
+    else if (m_controlMode == kCurrent)
+      message = LM_API_ICTRL_PC;
+    else {
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "PID constants only apply in Speed, Position, and Current mode");
+      return;
+    }
+
+    if (getMessage(message, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) {
+      double p = unpackFXP16_16(dataBuffer);
+
+      if (FXP16_EQ(m_p, p))
+        m_pVerified = true;
+      else
+        // It's wrong - set it again
+        SetP(m_p);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(message);
+    }
+  }
+
+  if (!m_iVerified) {
+    uint32_t message = 0;
+
+    if (m_controlMode == kSpeed)
+      message = LM_API_SPD_IC;
+    else if (m_controlMode == kPosition)
+      message = LM_API_POS_IC;
+    else if (m_controlMode == kCurrent)
+      message = LM_API_ICTRL_IC;
+    else {
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "PID constants only apply in Speed, Position, and Current mode");
+      return;
+    }
+
+    if (getMessage(message, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) {
+      double i = unpackFXP16_16(dataBuffer);
+
+      if (FXP16_EQ(m_i, i))
+        m_iVerified = true;
+      else
+        // It's wrong - set it again
+        SetI(m_i);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(message);
+    }
+  }
+
+  if (!m_dVerified) {
+    uint32_t message = 0;
+
+    if (m_controlMode == kSpeed)
+      message = LM_API_SPD_DC;
+    else if (m_controlMode == kPosition)
+      message = LM_API_POS_DC;
+    else if (m_controlMode == kCurrent)
+      message = LM_API_ICTRL_DC;
+    else {
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "PID constants only apply in Speed, Position, and Current mode");
+      return;
+    }
+
+    if (getMessage(message, CAN_MSGID_FULL_M, dataBuffer, &dataSize)) {
+      double d = unpackFXP16_16(dataBuffer);
+
+      if (FXP16_EQ(m_d, d))
+        m_dVerified = true;
+      else
+        // It's wrong - set it again
+        SetD(m_d);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(message);
+    }
+  }
+
+  if (!m_neutralModeVerified) {
+    if (getMessage(LM_API_CFG_BRAKE_COAST, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      NeutralMode mode = (NeutralMode)dataBuffer[0];
+
+      if (mode == m_neutralMode)
+        m_neutralModeVerified = true;
+      else
+        // It's wrong - set it again
+        ConfigNeutralMode(m_neutralMode);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_BRAKE_COAST);
+    }
+  }
+
+  if (!m_encoderCodesPerRevVerified) {
+    if (getMessage(LM_API_CFG_ENC_LINES, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      uint16_t codes = unpackint16_t(dataBuffer);
+
+      if (codes == m_encoderCodesPerRev)
+        m_encoderCodesPerRevVerified = true;
+      else
+        // It's wrong - set it again
+        ConfigEncoderCodesPerRev(m_encoderCodesPerRev);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_ENC_LINES);
+    }
+  }
+
+  if (!m_potentiometerTurnsVerified) {
+    if (getMessage(LM_API_CFG_POT_TURNS, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      uint16_t turns = unpackint16_t(dataBuffer);
+
+      if (turns == m_potentiometerTurns)
+        m_potentiometerTurnsVerified = true;
+      else
+        // It's wrong - set it again
+        ConfigPotentiometerTurns(m_potentiometerTurns);
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_POT_TURNS);
+    }
+  }
+
+  if (!m_limitModeVerified) {
+    if (getMessage(LM_API_CFG_LIMIT_MODE, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      LimitMode mode = (LimitMode)dataBuffer[0];
+
+      if (mode == m_limitMode)
+        m_limitModeVerified = true;
+      else {
+        // It's wrong - set it again
+        ConfigLimitMode(m_limitMode);
+      }
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_LIMIT_MODE);
+    }
+  }
+
+  if (!m_forwardLimitVerified) {
+    if (getMessage(LM_API_CFG_LIMIT_FWD, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      double limit = unpackFXP16_16(dataBuffer);
+
+      if (FXP16_EQ(limit, m_forwardLimit))
+        m_forwardLimitVerified = true;
+      else {
+        // It's wrong - set it again
+        ConfigForwardLimit(m_forwardLimit);
+      }
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_LIMIT_FWD);
+    }
+  }
+
+  if (!m_reverseLimitVerified) {
+    if (getMessage(LM_API_CFG_LIMIT_REV, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      double limit = unpackFXP16_16(dataBuffer);
+
+      if (FXP16_EQ(limit, m_reverseLimit))
+        m_reverseLimitVerified = true;
+      else {
+        // It's wrong - set it again
+        ConfigReverseLimit(m_reverseLimit);
+      }
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_LIMIT_REV);
+    }
+  }
+
+  if (!m_maxOutputVoltageVerified) {
+    if (getMessage(LM_API_CFG_MAX_VOUT, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      double voltage = unpackFXP8_8(dataBuffer);
+
+      // The returned max output voltage is sometimes slightly higher or
+      // lower than what was sent.  This should not trigger resending
+      // the message.
+      if (std::abs(voltage - m_maxOutputVoltage) < 0.1)
+        m_maxOutputVoltageVerified = true;
+      else {
+        // It's wrong - set it again
+        ConfigMaxOutputVoltage(m_maxOutputVoltage);
+      }
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_MAX_VOUT);
+    }
+  }
+
+  if (!m_voltageRampRateVerified) {
+    if (m_controlMode == kPercentVbus) {
+      if (getMessage(LM_API_VOLT_SET_RAMP, CAN_MSGID_FULL_M, dataBuffer,
+                     &dataSize)) {
+        double rate = unpackPercentage(dataBuffer);
+
+        if (FXP16_EQ(rate, m_voltageRampRate))
+          m_voltageRampRateVerified = true;
+        else {
+          // It's wrong - set it again
+          SetVoltageRampRate(m_voltageRampRate);
+        }
+      } else {
+        // Verification is needed but not available - request it again.
+        requestMessage(LM_API_VOLT_SET_RAMP);
+      }
+    } else if (m_controlMode == kVoltage) {
+      if (getMessage(LM_API_VCOMP_COMP_RAMP, CAN_MSGID_FULL_M, dataBuffer,
+                     &dataSize)) {
+        double rate = unpackFXP8_8(dataBuffer);
+
+        if (FXP8_EQ(rate, m_voltageRampRate))
+          m_voltageRampRateVerified = true;
+        else {
+          // It's wrong - set it again
+          SetVoltageRampRate(m_voltageRampRate);
+        }
+      } else {
+        // Verification is needed but not available - request it again.
+        requestMessage(LM_API_VCOMP_COMP_RAMP);
+      }
+    }
+  }
+
+  if (!m_faultTimeVerified) {
+    if (getMessage(LM_API_CFG_FAULT_TIME, CAN_MSGID_FULL_M, dataBuffer,
+                   &dataSize)) {
+      uint16_t faultTime = unpackint16_t(dataBuffer);
+
+      if ((uint16_t)(m_faultTime * 1000.0) == faultTime)
+        m_faultTimeVerified = true;
+      else {
+        // It's wrong - set it again
+        ConfigFaultTime(m_faultTime);
+      }
+    } else {
+      // Verification is needed but not available - request it again.
+      requestMessage(LM_API_CFG_FAULT_TIME);
+    }
+  }
+
+  if (!m_receivedStatusMessage0 || !m_receivedStatusMessage1 ||
+      !m_receivedStatusMessage2) {
+    // If the periodic status messages haven't been verified as received,
+    // request periodic status messages again and attempt to unpack any
+    // available ones.
+    setupPeriodicStatus();
+    GetTemperature();
+    GetPosition();
+    GetFaults();
+  }
+}
+
+/**
+ * Set the reference source device for speed controller mode.
+ *
+ * Choose encoder as the source of speed feedback when in speed control mode.
+ *
+ * @param reference Specify a speed reference.
+ */
+void CANJaguar::SetSpeedReference(uint8_t reference) {
+  uint8_t dataBuffer[8];
+
+  // Send the speed reference parameter
+  dataBuffer[0] = reference;
+  sendMessage(LM_API_SPD_REF, dataBuffer, sizeof(uint8_t));
+
+  m_speedReference = reference;
+  m_speedRefVerified = false;
+}
+
+/**
+ * Get the reference source device for speed controller mode.
+ *
+ * @return A speed reference indicating the currently selected reference device
+ * for speed controller mode.
+ */
+uint8_t CANJaguar::GetSpeedReference() const { return m_speedReference; }
+
+/**
+ * Set the reference source device for position controller mode.
+ *
+ * Choose between using and encoder and using a potentiometer
+ * as the source of position feedback when in position control mode.
+ *
+ * @param reference Specify a PositionReference.
+ */
+void CANJaguar::SetPositionReference(uint8_t reference) {
+  uint8_t dataBuffer[8];
+
+  // Send the position reference parameter
+  dataBuffer[0] = reference;
+  sendMessage(LM_API_POS_REF, dataBuffer, sizeof(uint8_t));
+
+  m_positionReference = reference;
+  m_posRefVerified = false;
+}
+
+/**
+ * Get the reference source device for position controller mode.
+ *
+ * @return A PositionReference indicating the currently selected reference
+ * device for position controller mode.
+ */
+uint8_t CANJaguar::GetPositionReference() const { return m_positionReference; }
+
+/**
+ * Set the P, I, and D constants for the closed loop modes.
+ *
+ * @param p The proportional gain of the Jaguar's PID controller.
+ * @param i The integral gain of the Jaguar's PID controller.
+ * @param d The differential gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetPID(double p, double i, double d) {
+  SetP(p);
+  SetI(i);
+  SetD(d);
+}
+
+/**
+ * Set the P constant for the closed loop modes.
+ *
+ * @param p The proportional gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetP(double p) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  switch (m_controlMode) {
+    case kPercentVbus:
+    case kVoltage:
+    case kFollower:
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "PID constants only apply in Speed, Position, and Current mode");
+      break;
+    case kSpeed:
+      dataSize = packFXP16_16(dataBuffer, p);
+      sendMessage(LM_API_SPD_PC, dataBuffer, dataSize);
+      break;
+    case kPosition:
+      dataSize = packFXP16_16(dataBuffer, p);
+      sendMessage(LM_API_POS_PC, dataBuffer, dataSize);
+      break;
+    case kCurrent:
+      dataSize = packFXP16_16(dataBuffer, p);
+      sendMessage(LM_API_ICTRL_PC, dataBuffer, dataSize);
+      break;
+  }
+
+  m_p = p;
+  m_pVerified = false;
+}
+
+/**
+ * Set the I constant for the closed loop modes.
+ *
+ * @param i The integral gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetI(double i) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  switch (m_controlMode) {
+    case kPercentVbus:
+    case kVoltage:
+    case kFollower:
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "PID constants only apply in Speed, Position, and Current mode");
+      break;
+    case kSpeed:
+      dataSize = packFXP16_16(dataBuffer, i);
+      sendMessage(LM_API_SPD_IC, dataBuffer, dataSize);
+      break;
+    case kPosition:
+      dataSize = packFXP16_16(dataBuffer, i);
+      sendMessage(LM_API_POS_IC, dataBuffer, dataSize);
+      break;
+    case kCurrent:
+      dataSize = packFXP16_16(dataBuffer, i);
+      sendMessage(LM_API_ICTRL_IC, dataBuffer, dataSize);
+      break;
+  }
+
+  m_i = i;
+  m_iVerified = false;
+}
+
+/**
+ * Set the D constant for the closed loop modes.
+ *
+ * @param d The derivative gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetD(double d) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  switch (m_controlMode) {
+    case kPercentVbus:
+    case kVoltage:
+    case kFollower:
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "PID constants only apply in Speed, Position, and Current mode");
+      break;
+    case kSpeed:
+      dataSize = packFXP16_16(dataBuffer, d);
+      sendMessage(LM_API_SPD_DC, dataBuffer, dataSize);
+      break;
+    case kPosition:
+      dataSize = packFXP16_16(dataBuffer, d);
+      sendMessage(LM_API_POS_DC, dataBuffer, dataSize);
+      break;
+    case kCurrent:
+      dataSize = packFXP16_16(dataBuffer, d);
+      sendMessage(LM_API_ICTRL_DC, dataBuffer, dataSize);
+      break;
+  }
+
+  m_d = d;
+  m_dVerified = false;
+}
+
+/**
+ * Get the Proportional gain of the controller.
+ *
+ * @return The proportional gain.
+ */
+double CANJaguar::GetP() const {
+  if (m_controlMode == kPercentVbus || m_controlMode == kVoltage) {
+    wpi_setWPIErrorWithContext(
+        IncompatibleMode,
+        "PID constants only apply in Speed, Position, and Current mode");
+    return 0.0;
+  }
+
+  return m_p;
+}
+
+/**
+ * Get the Intregral gain of the controller.
+ *
+ * @return The integral gain.
+ */
+double CANJaguar::GetI() const {
+  if (m_controlMode == kPercentVbus || m_controlMode == kVoltage) {
+    wpi_setWPIErrorWithContext(
+        IncompatibleMode,
+        "PID constants only apply in Speed, Position, and Current mode");
+    return 0.0;
+  }
+
+  return m_i;
+}
+
+/**
+ * Get the Differential gain of the controller.
+ *
+ * @return The differential gain.
+ */
+double CANJaguar::GetD() const {
+  if (m_controlMode == kPercentVbus || m_controlMode == kVoltage) {
+    wpi_setWPIErrorWithContext(
+        IncompatibleMode,
+        "PID constants only apply in Speed, Position, and Current mode");
+    return 0.0;
+  }
+
+  return m_d;
+}
+
+/**
+ * Enable the closed loop controller.
+ *
+ * Start actually controlling the output based on the feedback.
+ * If starting a position controller with an encoder reference,
+ * use the encoderInitialPosition parameter to initialize the
+ * encoder state.
+ *
+ * @param encoderInitialPosition Encoder position to set if position with
+ * encoder reference.  Ignored otherwise.
+ */
+void CANJaguar::EnableControl(double encoderInitialPosition) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize = 0;
+
+  switch (m_controlMode) {
+    case kPercentVbus:
+      sendMessage(LM_API_VOLT_T_EN, dataBuffer, dataSize);
+      break;
+    case kSpeed:
+      sendMessage(LM_API_SPD_T_EN, dataBuffer, dataSize);
+      break;
+    case kPosition:
+      dataSize = packFXP16_16(dataBuffer, encoderInitialPosition);
+      sendMessage(LM_API_POS_T_EN, dataBuffer, dataSize);
+      break;
+    case kCurrent:
+      sendMessage(LM_API_ICTRL_T_EN, dataBuffer, dataSize);
+      break;
+    case kVoltage:
+      sendMessage(LM_API_VCOMP_T_EN, dataBuffer, dataSize);
+      break;
+    default:
+      wpi_setWPIErrorWithContext(IncompatibleMode,
+                                 "The Jaguar only supports Current, Voltage, "
+                                 "Position, Speed, and Percent (Throttle) "
+                                 "modes.");
+      return;
+  }
+
+  m_controlEnabled = true;
+  m_controlModeVerified = false;
+}
+
+/**
+ * Disable the closed loop controller.
+ *
+ * Stop driving the output based on the feedback.
+ */
+void CANJaguar::DisableControl() {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize = 0;
+
+  // Disable all control
+  sendMessage(LM_API_VOLT_DIS, dataBuffer, dataSize);
+  sendMessage(LM_API_SPD_DIS, dataBuffer, dataSize);
+  sendMessage(LM_API_POS_DIS, dataBuffer, dataSize);
+  sendMessage(LM_API_ICTRL_DIS, dataBuffer, dataSize);
+  sendMessage(LM_API_VCOMP_DIS, dataBuffer, dataSize);
+
+  // Stop all periodic setpoints
+  sendMessage(LM_API_VOLT_T_SET, dataBuffer, dataSize,
+              CAN_SEND_PERIOD_STOP_REPEATING);
+  sendMessage(LM_API_SPD_T_SET, dataBuffer, dataSize,
+              CAN_SEND_PERIOD_STOP_REPEATING);
+  sendMessage(LM_API_POS_T_SET, dataBuffer, dataSize,
+              CAN_SEND_PERIOD_STOP_REPEATING);
+  sendMessage(LM_API_ICTRL_T_SET, dataBuffer, dataSize,
+              CAN_SEND_PERIOD_STOP_REPEATING);
+  sendMessage(LM_API_VCOMP_T_SET, dataBuffer, dataSize,
+              CAN_SEND_PERIOD_STOP_REPEATING);
+
+  m_controlEnabled = false;
+}
+
+/**
+ * Enable controlling the motor voltage as a percentage of the bus voltage
+ * without any position or speed feedback.<br>
+ * After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+ * CANJaguar#EnableControl(double)} to enable the device.
+ */
+void CANJaguar::SetPercentMode() {
+  SetControlMode(kPercentVbus);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_NONE);
+}
+
+/**
+ * Enable controlling the motor voltage as a percentage of the bus voltage,
+ * and enable speed sensing from a non-quadrature encoder.<br>
+ * After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+ * CANJaguar#EnableControl(double)} to enable the device.
+ *
+ * @param tag The constant CANJaguar::Encoder
+ * @param codesPerRev The counts per revolution on the encoder
+ */
+void CANJaguar::SetPercentMode(CANJaguar::EncoderStruct, uint16_t codesPerRev) {
+  SetControlMode(kPercentVbus);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+}
+
+/**
+ * Enable controlling the motor voltage as a percentage of the bus voltage,
+ * and enable speed sensing from a non-quadrature encoder.<br>
+ * After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+ * CANJaguar#EnableControl(double)} to enable the device.
+ *
+ * @param tag The constant CANJaguar::QuadEncoder
+ * @param codesPerRev The counts per revolution on the encoder
+ */
+void CANJaguar::SetPercentMode(CANJaguar::QuadEncoderStruct,
+                               uint16_t codesPerRev) {
+  SetControlMode(kPercentVbus);
+  SetPositionReference(LM_REF_ENCODER);
+  SetSpeedReference(LM_REF_QUAD_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+}
+
+/**
+* Enable controlling the motor voltage as a percentage of the bus voltage,
+* and enable position sensing from a potentiometer and no speed feedback.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param potentiometer The constant CANJaguar::Potentiometer
+*/
+void CANJaguar::SetPercentMode(CANJaguar::PotentiometerStruct) {
+  SetControlMode(kPercentVbus);
+  SetPositionReference(LM_REF_POT);
+  SetSpeedReference(LM_REF_NONE);
+  ConfigPotentiometerTurns(1);
+}
+
+/**
+ * Enable controlling the motor current with a PID loop.<br>
+ * After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+ * CANJaguar#EnableControl(double)} to enable the device.
+ *
+ * @param p The proportional gain of the Jaguar's PID controller.
+ * @param i The integral gain of the Jaguar's PID controller.
+ * @param d The differential gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetCurrentMode(double p, double i, double d) {
+  SetControlMode(kCurrent);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_NONE);
+  SetPID(p, i, d);
+}
+
+/**
+* Enable controlling the motor current with a PID loop, and enable speed
+* sensing from a non-quadrature encoder.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param encoder The constant CANJaguar::Encoder
+* @param p The proportional gain of the Jaguar's PID controller.
+* @param i The integral gain of the Jaguar's PID controller.
+* @param d The differential gain of the Jaguar's PID controller.
+*/
+void CANJaguar::SetCurrentMode(CANJaguar::EncoderStruct, uint16_t codesPerRev,
+                               double p, double i, double d) {
+  SetControlMode(kCurrent);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_NONE);
+  ConfigEncoderCodesPerRev(codesPerRev);
+  SetPID(p, i, d);
+}
+
+/**
+* Enable controlling the motor current with a PID loop, and enable speed and
+* position sensing from a quadrature encoder.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param endoer The constant CANJaguar::QuadEncoder
+* @param p The proportional gain of the Jaguar's PID controller.
+* @param i The integral gain of the Jaguar's PID controller.
+* @param d The differential gain of the Jaguar's PID controller.
+*/
+void CANJaguar::SetCurrentMode(CANJaguar::QuadEncoderStruct,
+                               uint16_t codesPerRev, double p, double i,
+                               double d) {
+  SetControlMode(kCurrent);
+  SetPositionReference(LM_REF_ENCODER);
+  SetSpeedReference(LM_REF_QUAD_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+  SetPID(p, i, d);
+}
+
+/**
+* Enable controlling the motor current with a PID loop, and enable position
+* sensing from a potentiometer.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param potentiometer The constant CANJaguar::Potentiometer
+* @param p The proportional gain of the Jaguar's PID controller.
+* @param i The integral gain of the Jaguar's PID controller.
+* @param d The differential gain of the Jaguar's PID controller.
+*/
+void CANJaguar::SetCurrentMode(CANJaguar::PotentiometerStruct, double p,
+                               double i, double d) {
+  SetControlMode(kCurrent);
+  SetPositionReference(LM_REF_POT);
+  SetSpeedReference(LM_REF_NONE);
+  ConfigPotentiometerTurns(1);
+  SetPID(p, i, d);
+}
+
+/**
+ * Enable controlling the speed with a feedback loop from a non-quadrature
+ * encoder.<br>
+ * After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+ * CANJaguar#EnableControl(double)} to enable the device.
+ *
+ * @param encoder The constant CANJaguar::Encoder
+ * @param codesPerRev The counts per revolution on the encoder.
+ * @param p The proportional gain of the Jaguar's PID controller.
+ * @param i The integral gain of the Jaguar's PID controller.
+ * @param d The differential gain of the Jaguar's PID controller.
+ */
+void CANJaguar::SetSpeedMode(CANJaguar::EncoderStruct, uint16_t codesPerRev,
+                             double p, double i, double d) {
+  SetControlMode(kSpeed);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+  SetPID(p, i, d);
+}
+
+/**
+* Enable controlling the speed with a feedback loop from a quadrature
+* encoder.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param encoder The constant CANJaguar::QuadEncoder
+* @param codesPerRev The counts per revolution on the encoder.
+* @param p The proportional gain of the Jaguar's PID controller.
+* @param i The integral gain of the Jaguar's PID controller.
+* @param d The differential gain of the Jaguar's PID controller.
+*/
+void CANJaguar::SetSpeedMode(CANJaguar::QuadEncoderStruct, uint16_t codesPerRev,
+                             double p, double i, double d) {
+  SetControlMode(kSpeed);
+  SetPositionReference(LM_REF_ENCODER);
+  SetSpeedReference(LM_REF_QUAD_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+  SetPID(p, i, d);
+}
+
+/**
+ * Enable controlling the position with a feedback loop using an encoder.<br>
+ * After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+ * CANJaguar#EnableControl(double)} to enable the device.
+ *
+ * @param encoder The constant CANJaguar::QuadEncoder
+ * @param codesPerRev The counts per revolution on the encoder.
+ * @param p The proportional gain of the Jaguar's PID controller.
+ * @param i The integral gain of the Jaguar's PID controller.
+ * @param d The differential gain of the Jaguar's PID controller.
+ *
+ */
+void CANJaguar::SetPositionMode(CANJaguar::QuadEncoderStruct,
+                                uint16_t codesPerRev, double p, double i,
+                                double d) {
+  SetControlMode(kPosition);
+  SetPositionReference(LM_REF_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+  SetPID(p, i, d);
+}
+
+/**
+* Enable controlling the position with a feedback loop using a
+* potentiometer.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+* @param p The proportional gain of the Jaguar's PID controller.
+* @param i The integral gain of the Jaguar's PID controller.
+* @param d The differential gain of the Jaguar's PID controller.
+*/
+void CANJaguar::SetPositionMode(CANJaguar::PotentiometerStruct, double p,
+                                double i, double d) {
+  SetControlMode(kPosition);
+  SetPositionReference(LM_REF_POT);
+  ConfigPotentiometerTurns(1);
+  SetPID(p, i, d);
+}
+
+/**
+* Enable controlling the motor voltage without any position or speed
+* feedback.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*/
+void CANJaguar::SetVoltageMode() {
+  SetControlMode(kVoltage);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_NONE);
+}
+
+/**
+* Enable controlling the motor voltage with speed feedback from a
+* non-quadrature encoder and no position feedback.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param encoder The constant CANJaguar::Encoder
+* @param codesPerRev The counts per revolution on the encoder
+*/
+void CANJaguar::SetVoltageMode(CANJaguar::EncoderStruct, uint16_t codesPerRev) {
+  SetControlMode(kVoltage);
+  SetPositionReference(LM_REF_NONE);
+  SetSpeedReference(LM_REF_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+}
+
+/**
+* Enable controlling the motor voltage with position and speed feedback from a
+* quadrature encoder.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param encoder The constant CANJaguar::QuadEncoder
+* @param codesPerRev The counts per revolution on the encoder
+*/
+void CANJaguar::SetVoltageMode(CANJaguar::QuadEncoderStruct,
+                               uint16_t codesPerRev) {
+  SetControlMode(kVoltage);
+  SetPositionReference(LM_REF_ENCODER);
+  SetSpeedReference(LM_REF_QUAD_ENCODER);
+  ConfigEncoderCodesPerRev(codesPerRev);
+}
+
+/**
+* Enable controlling the motor voltage with position feedback from a
+* potentiometer and no speed feedback.<br>
+* After calling this you must call {@link CANJaguar#EnableControl()} or {@link
+* CANJaguar#EnableControl(double)} to enable the device.
+*
+* @param potentiometer The constant CANJaguar::Potentiometer
+*/
+void CANJaguar::SetVoltageMode(CANJaguar::PotentiometerStruct) {
+  SetControlMode(kVoltage);
+  SetPositionReference(LM_REF_POT);
+  SetSpeedReference(LM_REF_NONE);
+  ConfigPotentiometerTurns(1);
+}
+
+/**
+ * Used internally. In order to set the control mode see the methods listed
+ * below.
+ * Change the control mode of this Jaguar object.
+ *
+ * After changing modes, configure any PID constants or other settings needed
+ * and then EnableControl() to actually change the mode on the Jaguar.
+ *
+ * @param controlMode The new mode.
+ */
+void CANJaguar::SetControlMode(ControlMode controlMode) {
+  // Disable the previous mode
+  DisableControl();
+
+  if (controlMode == kFollower)
+    wpi_setWPIErrorWithContext(IncompatibleMode,
+                               "The Jaguar only supports Current, Voltage, "
+                               "Position, Speed, and Percent (Throttle) "
+                               "modes.");
+
+  // Update the local mode
+  m_controlMode = controlMode;
+  m_controlModeVerified = false;
+
+  HALReport(HALUsageReporting::kResourceType_CANJaguar, m_deviceNumber,
+            m_controlMode);
+}
+
+/**
+ * Get the active control mode from the Jaguar.
+ *
+ * Ask the Jag what mode it is in.
+ *
+ * @return ControlMode that the Jag is in.
+ */
+CANJaguar::ControlMode CANJaguar::GetControlMode() const {
+  return m_controlMode;
+}
+
+/**
+ * Get the voltage at the battery input terminals of the Jaguar.
+ *
+ * @return The bus voltage in volts.
+ */
+float CANJaguar::GetBusVoltage() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_busVoltage;
+}
+
+/**
+ * Get the voltage being output from the motor terminals of the Jaguar.
+ *
+ * @return The output voltage in volts.
+ */
+float CANJaguar::GetOutputVoltage() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_outputVoltage;
+}
+
+/**
+ * Get the current through the motor terminals of the Jaguar.
+ *
+ * @return The output current in amps.
+ */
+float CANJaguar::GetOutputCurrent() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_outputCurrent;
+}
+
+/**
+ * Get the internal temperature of the Jaguar.
+ *
+ * @return The temperature of the Jaguar in degrees Celsius.
+ */
+float CANJaguar::GetTemperature() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_temperature;
+}
+
+/**
+ * Get the position of the encoder or potentiometer.
+ *
+ * @return The position of the motor in rotations based on the configured
+ * feedback.
+ * @see CANJaguar#ConfigPotentiometerTurns(int)
+ * @see CANJaguar#ConfigEncoderCodesPerRev(int)
+ */
+double CANJaguar::GetPosition() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_position;
+}
+
+/**
+ * Get the speed of the encoder.
+ *
+ * @return The speed of the motor in RPM based on the configured feedback.
+ */
+double CANJaguar::GetSpeed() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_speed;
+}
+
+/**
+ * Get the status of the forward limit switch.
+ *
+ * @return The motor is allowed to turn in the forward direction when true.
+ */
+bool CANJaguar::GetForwardLimitOK() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_limits & kForwardLimit;
+}
+
+/**
+ * Get the status of the reverse limit switch.
+ *
+ * @return The motor is allowed to turn in the reverse direction when true.
+ */
+bool CANJaguar::GetReverseLimitOK() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_limits & kReverseLimit;
+}
+
+/**
+ * Get the status of any faults the Jaguar has detected.
+ *
+ * @return A bit-mask of faults defined by the "Faults" enum.
+ * @see #kCurrentFault
+ * @see #kBusVoltageFault
+ * @see #kTemperatureFault
+ * @see #kGateDriverFault
+ */
+uint16_t CANJaguar::GetFaults() const {
+  updatePeriodicStatus();
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+
+  return m_faults;
+}
+
+/**
+ * Set the maximum voltage change rate.
+ *
+ * When in PercentVbus or Voltage output mode, the rate at which the voltage
+ * changes can
+ * be limited to reduce current spikes.  Set this to 0.0 to disable rate
+ * limiting.
+ *
+ * @param rampRate The maximum rate of voltage change in Percent Voltage mode in
+ * V/s.
+ */
+void CANJaguar::SetVoltageRampRate(double rampRate) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+  uint32_t message;
+
+  switch (m_controlMode) {
+    case kPercentVbus:
+      dataSize = packPercentage(
+          dataBuffer, rampRate / (m_maxOutputVoltage * kControllerRate));
+      message = LM_API_VOLT_SET_RAMP;
+      break;
+    case kVoltage:
+      dataSize = packFXP8_8(dataBuffer, rampRate / kControllerRate);
+      message = LM_API_VCOMP_COMP_RAMP;
+      break;
+    default:
+      wpi_setWPIErrorWithContext(
+          IncompatibleMode,
+          "SetVoltageRampRate only applies in Voltage and Percent mode");
+      return;
+  }
+
+  sendMessage(message, dataBuffer, dataSize);
+
+  m_voltageRampRate = rampRate;
+  m_voltageRampRateVerified = false;
+}
+
+/**
+ * Get the version of the firmware running on the Jaguar.
+ *
+ * @return The firmware version.  0 if the device did not respond.
+ */
+uint32_t CANJaguar::GetFirmwareVersion() const { return m_firmwareVersion; }
+
+/**
+ * Get the version of the Jaguar hardware.
+ *
+ * @return The hardware version. 1: Jaguar,  2: Black Jaguar
+ */
+uint8_t CANJaguar::GetHardwareVersion() const { return m_hardwareVersion; }
+
+/**
+ * Configure what the controller does to the H-Bridge when neutral (not driving
+ * the output).
+ *
+ * This allows you to override the jumper configuration for brake or coast.
+ *
+ * @param mode Select to use the jumper setting or to override it to coast or
+ * brake.
+ */
+void CANJaguar::ConfigNeutralMode(NeutralMode mode) {
+  uint8_t dataBuffer[8];
+
+  // Set the neutral mode
+  sendMessage(LM_API_CFG_BRAKE_COAST, dataBuffer, sizeof(uint8_t));
+
+  m_neutralMode = mode;
+  m_neutralModeVerified = false;
+}
+
+/**
+ * Configure how many codes per revolution are generated by your encoder.
+ *
+ * @param codesPerRev The number of counts per revolution in 1X mode.
+ */
+void CANJaguar::ConfigEncoderCodesPerRev(uint16_t codesPerRev) {
+  uint8_t dataBuffer[8];
+
+  // Set the codes per revolution mode
+  packint16_t(dataBuffer, codesPerRev);
+  sendMessage(LM_API_CFG_ENC_LINES, dataBuffer, sizeof(uint16_t));
+
+  m_encoderCodesPerRev = codesPerRev;
+  m_encoderCodesPerRevVerified = false;
+}
+
+/**
+ * Configure the number of turns on the potentiometer.
+ *
+ * There is no special support for continuous turn potentiometers.
+ * Only integer numbers of turns are supported.
+ *
+ * @param turns The number of turns of the potentiometer.
+ */
+void CANJaguar::ConfigPotentiometerTurns(uint16_t turns) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  // Set the pot turns
+  dataSize = packint16_t(dataBuffer, turns);
+  sendMessage(LM_API_CFG_POT_TURNS, dataBuffer, dataSize);
+
+  m_potentiometerTurns = turns;
+  m_potentiometerTurnsVerified = false;
+}
+
+/**
+ * Configure Soft Position Limits when in Position Controller mode.
+ *
+ * When controlling position, you can add additional limits on top of the limit
+ switch inputs
+ * that are based on the position feedback.  If the position limit is reached or
+ the
+ * switch is opened, that direction will be disabled.
+ *
+
+ * @param forwardLimitPosition The position that if exceeded will disable the
+ forward direction.
+ * @param reverseLimitPosition The position that if exceeded will disable the
+ reverse direction.
+ */
+void CANJaguar::ConfigSoftPositionLimits(double forwardLimitPosition,
+                                         double reverseLimitPosition) {
+  ConfigLimitMode(kLimitMode_SoftPositionLimits);
+  ConfigForwardLimit(forwardLimitPosition);
+  ConfigReverseLimit(reverseLimitPosition);
+}
+
+/**
+ * Disable Soft Position Limits if previously enabled.
+ *
+ * Soft Position Limits are disabled by default.
+ */
+void CANJaguar::DisableSoftPositionLimits() {
+  ConfigLimitMode(kLimitMode_SwitchInputsOnly);
+}
+
+/**
+ * Set the limit mode for position control mode.
+ *
+ * Use ConfigSoftPositionLimits or DisableSoftPositionLimits to set this
+ * automatically.
+ */
+void CANJaguar::ConfigLimitMode(LimitMode mode) {
+  uint8_t dataBuffer[8];
+
+  dataBuffer[0] = mode;
+  sendMessage(LM_API_CFG_LIMIT_MODE, dataBuffer, sizeof(uint8_t));
+
+  m_limitMode = mode;
+  m_limitModeVerified = false;
+}
+
+/**
+* Set the position that if exceeded will disable the forward direction.
+*
+* Use ConfigSoftPositionLimits to set this and the limit mode automatically.
+*/
+void CANJaguar::ConfigForwardLimit(double forwardLimitPosition) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  dataSize = packFXP16_16(dataBuffer, forwardLimitPosition);
+  dataBuffer[dataSize++] = 1;
+  sendMessage(LM_API_CFG_LIMIT_FWD, dataBuffer, dataSize);
+
+  m_forwardLimit = forwardLimitPosition;
+  m_forwardLimitVerified = false;
+}
+
+/**
+* Set the position that if exceeded will disable the reverse direction.
+*
+* Use ConfigSoftPositionLimits to set this and the limit mode automatically.
+*/
+void CANJaguar::ConfigReverseLimit(double reverseLimitPosition) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  dataSize = packFXP16_16(dataBuffer, reverseLimitPosition);
+  dataBuffer[dataSize++] = 0;
+  sendMessage(LM_API_CFG_LIMIT_REV, dataBuffer, dataSize);
+
+  m_reverseLimit = reverseLimitPosition;
+  m_reverseLimitVerified = false;
+}
+
+/**
+ * Configure the maximum voltage that the Jaguar will ever output.
+ *
+ * This can be used to limit the maximum output voltage in all modes so that
+ * motors which cannot withstand full bus voltage can be used safely.
+ *
+ * @param voltage The maximum voltage output by the Jaguar.
+ */
+void CANJaguar::ConfigMaxOutputVoltage(double voltage) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  dataSize = packFXP8_8(dataBuffer, voltage);
+  sendMessage(LM_API_CFG_MAX_VOUT, dataBuffer, dataSize);
+
+  m_maxOutputVoltage = voltage;
+  m_maxOutputVoltageVerified = false;
+}
+
+/**
+ * Configure how long the Jaguar waits in the case of a fault before resuming
+ * operation.
+ *
+ * Faults include over temerature, over current, and bus under voltage.
+ * The default is 3.0 seconds, but can be reduced to as low as 0.5 seconds.
+ *
+ * @param faultTime The time to wait before resuming operation, in seconds.
+ */
+void CANJaguar::ConfigFaultTime(float faultTime) {
+  uint8_t dataBuffer[8];
+  uint8_t dataSize;
+
+  if (faultTime < 0.5)
+    faultTime = 0.5;
+  else if (faultTime > 3.0)
+    faultTime = 3.0;
+
+  // Message takes ms
+  dataSize = packint16_t(dataBuffer, (int16_t)(faultTime * 1000.0));
+  sendMessage(LM_API_CFG_FAULT_TIME, dataBuffer, dataSize);
+
+  m_faultTime = faultTime;
+  m_faultTimeVerified = false;
+}
+
+/**
+ * Update all the motors that have pending sets in the syncGroup.
+ *
+ * @param syncGroup A bitmask of groups to generate synchronous output.
+ */
+void CANJaguar::UpdateSyncGroup(uint8_t syncGroup) {
+  sendMessageHelper(CAN_MSGID_API_SYNC, &syncGroup, sizeof(syncGroup),
+                    CAN_SEND_PERIOD_NO_REPEAT);
+}
+
+void CANJaguar::SetExpiration(float timeout) {
+  if (m_safetyHelper) m_safetyHelper->SetExpiration(timeout);
+}
+
+float CANJaguar::GetExpiration() const {
+  if (!m_safetyHelper) return 0.0;
+  return m_safetyHelper->GetExpiration();
+}
+
+bool CANJaguar::IsAlive() const {
+  if (!m_safetyHelper) return false;
+  return m_safetyHelper->IsAlive();
+}
+
+bool CANJaguar::IsSafetyEnabled() const {
+  if (!m_safetyHelper) return false;
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void CANJaguar::SetSafetyEnabled(bool enabled) {
+  if (m_safetyHelper) m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void CANJaguar::GetDescription(std::ostringstream& desc) const {
+  desc << "CANJaguar ID " << m_deviceNumber;
+}
+
+uint8_t CANJaguar::GetDeviceID() const { return m_deviceNumber; }
+
+/**
+ * Common interface for stopping the motor
+ * Part of the MotorSafety interface
+ *
+ * @deprecated Call DisableControl instead.
+ */
+void CANJaguar::StopMotor() { DisableControl(); }
+
+/**
+* Common interface for inverting direction of a speed controller.
+* Only works in PercentVbus, speed, and Voltage modes.
+* @param isInverted The state of inversion, true is inverted
+*/
+void CANJaguar::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool CANJaguar::GetInverted() const { return m_isInverted; }
+
+void CANJaguar::ValueChanged(ITable* source, llvm::StringRef key,
+                             std::shared_ptr<nt::Value> value, bool isNew) {
+  if(key == "Mode" && value->IsDouble()) SetControlMode(static_cast<CANSpeedController::ControlMode>(value->GetDouble()));
+  if(IsModePID(m_controlMode) && value->IsDouble()) {
+    if(key == "p") SetP(value->GetDouble());
+    if(key == "i") SetI(value->GetDouble());
+    if(key == "d") SetD(value->GetDouble());
+  }
+  if(key == "Enabled" && value->IsBoolean()) {
+      if (value->GetBoolean()) {
+        EnableControl();
+      } else {
+        DisableControl();
+      }
+  }
+  if(key == "Value" && value->IsDouble()) Set(value->GetDouble());
+}
+
+bool CANJaguar::IsModePID(CANSpeedController::ControlMode mode) const {
+  return mode == kCurrent || mode == kSpeed || mode == kPosition;
+}
+
+void CANJaguar::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutString("~TYPE~", "CANSpeedController");
+    m_table->PutString("Type", "CANJaguar");
+    m_table->PutString("Mode", GetModeName(m_controlMode));
+    if (IsModePID(m_controlMode)) {
+        m_table->PutNumber("p", GetP());
+        m_table->PutNumber("i", GetI());
+        m_table->PutNumber("d", GetD());
+    }
+    m_table->PutBoolean("Enabled", m_controlEnabled);
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+void CANJaguar::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener(this, true);
+  }
+}
+
+void CANJaguar::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string CANJaguar::GetSmartDashboardType() const {
+  return "CANSpeedController";
+}
+
+void CANJaguar::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> CANJaguar::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/CANTalon.cpp b/wpilibc/Athena/src/CANTalon.cpp
new file mode 100644
index 0000000..f937212
--- /dev/null
+++ b/wpilibc/Athena/src/CANTalon.cpp
@@ -0,0 +1,1750 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "CANTalon.h"
+#include "WPIErrors.h"
+#include <unistd.h>  // usleep
+#include <sstream>
+/**
+ * Number of adc engineering units per 0 to 3.3V sweep.
+ * This is necessary for scaling Analog Position in rotations/RPM.
+ */
+const double kNativeAdcUnitsPerRotation = 1024.0;
+/**
+ * Number of pulse width engineering units per full rotation.
+ * This is necessary for scaling Pulse Width Decoded Position in rotations/RPM.
+ */
+const double kNativePwdUnitsPerRotation = 4096.0;
+/**
+ * Number of minutes per 100ms unit.  Useful for scaling velocities
+ * measured by Talon's 100ms timebase to rotations per minute.
+ */
+const double kMinutesPer100msUnit = 1.0/600.0;
+
+/**
+ * Constructor for the CANTalon device.
+ * @param deviceNumber The CAN ID of the Talon SRX
+ */
+CANTalon::CANTalon(int deviceNumber)
+    : m_deviceNumber(deviceNumber),
+      m_impl(new CanTalonSRX(deviceNumber)),
+      m_safetyHelper(new MotorSafetyHelper(this)) {
+  ApplyControlMode(m_controlMode);
+  m_impl->SetProfileSlotSelect(m_profile);
+  m_isInverted = false;
+}
+/**
+ * Constructor for the CANTalon device.
+ * @param deviceNumber The CAN ID of the Talon SRX
+ * @param controlPeriodMs The period in ms to send the CAN control frame.
+ *                        Period is bounded to [1ms,95ms].
+ */
+CANTalon::CANTalon(int deviceNumber, int controlPeriodMs)
+    : m_deviceNumber(deviceNumber),
+      m_impl(new CanTalonSRX(deviceNumber,controlPeriodMs)),
+      m_safetyHelper(new MotorSafetyHelper(this)) {
+  ApplyControlMode(m_controlMode);
+  m_impl->SetProfileSlotSelect(m_profile);
+}
+
+CANTalon::~CANTalon() {
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+  if (m_hasBeenMoved) return;
+  Disable();
+}
+
+/**
+* Write out the PID value as seen in the PIDOutput base object.
+*
+* @deprecated Call Set instead.
+*
+* @param output Write out the PercentVbus value as was computed by the
+* PIDController
+*/
+void CANTalon::PIDWrite(float output) {
+  if (GetControlMode() == kPercentVbus) {
+    Set(output);
+  } else {
+    wpi_setWPIErrorWithContext(IncompatibleMode,
+                               "PID only supported in PercentVbus mode");
+  }
+}
+
+/**
+ * Retrieve the current sensor value. Equivalent to Get().
+ *
+ * @return The current sensor value of the Talon.
+ */
+double CANTalon::PIDGet() { return Get(); }
+
+/**
+ * Gets the current status of the Talon (usually a sensor value).
+ *
+ * In Current mode: returns output current.
+ * In Speed mode: returns current speed.
+ * In Position mode: returns current sensor position.
+ * In PercentVbus and Follower modes: returns current applied throttle.
+ *
+ * @return The current sensor value of the Talon.
+ */
+float CANTalon::Get() const {
+  int value;
+  switch (m_controlMode) {
+    case kVoltage:
+      return GetOutputVoltage();
+    case kCurrent:
+      return GetOutputCurrent();
+    case kSpeed:
+      m_impl->GetSensorVelocity(value);
+      return ScaleNativeUnitsToRpm(m_feedbackDevice, value);
+    case kPosition:
+      m_impl->GetSensorPosition(value);
+      return ScaleNativeUnitsToRotations(m_feedbackDevice, value);
+    case kPercentVbus:
+    case kFollower:
+    default:
+      m_impl->GetAppliedThrottle(value);
+      return (float)value / 1023.0;
+  }
+}
+
+/**
+ * Sets the appropriate output on the talon, depending on the mode.
+ *
+ * In PercentVbus, the output is between -1.0 and 1.0, with 0.0 as stopped.
+ * In Voltage mode, output value is in volts.
+ * In Current mode, output value is in amperes.
+ * In Speed mode, output value is in position change / 10ms.
+ * In Position mode, output value is in encoder ticks or an analog value,
+ *   depending on the sensor.
+ * In Follower mode, the output value is the integer device ID of the talon to
+ * duplicate.
+ *
+ * @param outputValue The setpoint value, as described above.
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+void CANTalon::Set(float value, uint8_t syncGroup) {
+  /* feed safety helper since caller just updated our output */
+  m_safetyHelper->Feed();
+  if (m_controlEnabled) {
+    m_setPoint = value;  /* cache set point for GetSetpoint() */
+    CTR_Code status = CTR_OKAY;
+    switch (m_controlMode) {
+      case CANSpeedController::kPercentVbus: {
+        m_impl->Set(m_isInverted ? -value : value);
+        status = CTR_OKAY;
+      } break;
+      case CANSpeedController::kFollower: {
+        status = m_impl->SetDemand((int)value);
+      } break;
+      case CANSpeedController::kVoltage: {
+        // Voltage is an 8.8 fixed point number.
+        int volts = int((m_isInverted ? -value : value) * 256);
+        status = m_impl->SetDemand(volts);
+      } break;
+      case CANSpeedController::kSpeed:
+        /* if the caller has provided scaling info, apply it */
+        status = m_impl->SetDemand(ScaleVelocityToNativeUnits(m_feedbackDevice, m_isInverted ? -value : value));
+        break;
+      case CANSpeedController::kPosition:
+        status = m_impl->SetDemand(ScaleRotationsToNativeUnits(m_feedbackDevice, value));
+        break;
+      case CANSpeedController::kCurrent: {
+        double milliamperes = (m_isInverted ? -value : value) * 1000.0; /* mA*/
+        status = m_impl->SetDemand(milliamperes);
+      } break;
+      default:
+        wpi_setWPIErrorWithContext(
+            IncompatibleMode,
+            "The CAN Talon does not support this control mode.");
+        break;
+    }
+    if (status != CTR_OKAY) {
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    }
+
+    status = m_impl->SetModeSelect(m_sendMode);
+
+    if (status != CTR_OKAY) {
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    }
+  }
+}
+
+/**
+ * Sets the setpoint to value. Equivalent to Set().
+ */
+void CANTalon::SetSetpoint(float value) { Set(value); }
+
+/**
+ * Resets the integral term and disables the controller.
+ */
+void CANTalon::Reset() {
+  ClearIaccum();
+  Disable();
+}
+
+/**
+ * Disables control of the talon, causing the motor to brake or coast
+ * depending on its mode (see the Talon SRX Software Reference manual
+ * for more information).
+ */
+void CANTalon::Disable() {
+  m_impl->SetModeSelect((int)CANTalon::kDisabled);
+  m_controlEnabled = false;
+}
+
+/**
+ * Enables control of the Talon, allowing the motor to move.
+ */
+void CANTalon::EnableControl() {
+  SetControlMode(m_controlMode);
+  m_controlEnabled = true;
+}
+
+/**
+ * Enables control of the Talon, allowing the motor to move.
+ */
+void CANTalon::Enable() { EnableControl(); }
+
+/**
+ * @return Whether the Talon is currently enabled.
+ */
+bool CANTalon::IsControlEnabled() const { return m_controlEnabled; }
+
+/**
+ * @return Whether the Talon is currently enabled.
+ */
+bool CANTalon::IsEnabled() const { return IsControlEnabled(); }
+
+/**
+ * @param p Proportional constant to use in PID loop.
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+void CANTalon::SetP(double p) {
+  CTR_Code status = m_impl->SetPgain(m_profile, p);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Set the integration constant of the currently selected profile.
+ *
+ * @param i Integration constant for the currently selected PID profile.
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+void CANTalon::SetI(double i) {
+  CTR_Code status = m_impl->SetIgain(m_profile, i);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Set the derivative constant of the currently selected profile.
+ *
+ * @param d Derivative constant for the currently selected PID profile.
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+void CANTalon::SetD(double d) {
+  CTR_Code status = m_impl->SetDgain(m_profile, d);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Set the feedforward value of the currently selected profile.
+ *
+ * @param f Feedforward constant for the currently selected PID profile.
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+void CANTalon::SetF(double f) {
+  CTR_Code status = m_impl->SetFgain(m_profile, f);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Set the Izone to a nonzero value to auto clear the integral accumulator
+ *     when the absolute value of CloseLoopError exceeds Izone.
+ *
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+void CANTalon::SetIzone(unsigned iz) {
+  CTR_Code status = m_impl->SetIzone(m_profile, iz);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * SRX has two available slots for PID.
+ * @param slotIdx one or zero depending on which slot caller wants.
+ */
+void CANTalon::SelectProfileSlot(int slotIdx) {
+  m_profile = (slotIdx == 0) ? 0 : 1; /* only get two slots for now */
+  CTR_Code status = m_impl->SetProfileSlotSelect(m_profile);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Sets control values for closed loop control.
+ *
+ * @param p Proportional constant.
+ * @param i Integration constant.
+ * @param d Differential constant.
+ * This function does not modify F-gain.  Considerable passing a zero for f
+ * using
+ * the four-parameter function.
+ */
+void CANTalon::SetPID(double p, double i, double d) {
+  SetP(p);
+  SetI(i);
+  SetD(d);
+}
+/**
+ * Sets control values for closed loop control.
+ *
+ * @param p Proportional constant.
+ * @param i Integration constant.
+ * @param d Differential constant.
+ * @param f Feedforward constant.
+ */
+void CANTalon::SetPID(double p, double i, double d, double f) {
+  SetP(p);
+  SetI(i);
+  SetD(d);
+  SetF(f);
+}
+/**
+ * Select the feedback device to use in closed-loop
+ */
+void CANTalon::SetFeedbackDevice(FeedbackDevice feedbackDevice) {
+  /* save the selection so that future setters/getters know which scalars to apply */
+  m_feedbackDevice = feedbackDevice;
+  /* pass feedback to actual CAN frame */
+  CTR_Code status = m_impl->SetFeedbackDeviceSelect((int)feedbackDevice);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Select the feedback device to use in closed-loop
+ */
+void CANTalon::SetStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs) {
+  CTR_Code status = m_impl->SetStatusFrameRate((int)stateFrame, periodMs);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Get the current proportional constant.
+ *
+ * @return double proportional constant for current profile.
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+double CANTalon::GetP() const {
+  CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_P
+                                         : CanTalonSRX::eProfileParamSlot0_P;
+  // Update the info in m_impl.
+  CTR_Code status = m_impl->RequestParam(param);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
+  double p;
+  status = m_impl->GetPgain(m_profile, p);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return p;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+double CANTalon::GetI() const {
+  CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_I
+                                         : CanTalonSRX::eProfileParamSlot0_I;
+  // Update the info in m_impl.
+  CTR_Code status = m_impl->RequestParam(param);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
+
+  double i;
+  status = m_impl->GetIgain(m_profile, i);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return i;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+double CANTalon::GetD() const {
+  CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_D
+                                         : CanTalonSRX::eProfileParamSlot0_D;
+  // Update the info in m_impl.
+  CTR_Code status = m_impl->RequestParam(param);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
+
+  double d;
+  status = m_impl->GetDgain(m_profile, d);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return d;
+}
+/**
+ *
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+double CANTalon::GetF() const {
+  CanTalonSRX::param_t param = m_profile ? CanTalonSRX::eProfileParamSlot1_F
+                                         : CanTalonSRX::eProfileParamSlot0_F;
+  // Update the info in m_impl.
+  CTR_Code status = m_impl->RequestParam(param);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+
+  usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
+  double f;
+  status = m_impl->GetFgain(m_profile, f);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return f;
+}
+/**
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+int CANTalon::GetIzone() const {
+  CanTalonSRX::param_t param = m_profile
+                                   ? CanTalonSRX::eProfileParamSlot1_IZone
+                                   : CanTalonSRX::eProfileParamSlot0_IZone;
+  // Update the info in m_impl.
+  CTR_Code status = m_impl->RequestParam(param);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  usleep(kDelayForSolicitedSignalsUs);
+
+  int iz;
+  status = m_impl->GetIzone(m_profile, iz);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return iz;
+}
+
+/**
+ * @return the current setpoint; ie, whatever was last passed to Set().
+ */
+double CANTalon::GetSetpoint() const { return m_setPoint; }
+
+/**
+ * Returns the voltage coming in from the battery.
+ *
+ * @return The input voltage in volts.
+ */
+float CANTalon::GetBusVoltage() const {
+  double voltage;
+  CTR_Code status = m_impl->GetBatteryV(voltage);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return voltage;
+}
+
+/**
+ * @return The voltage being output by the Talon, in Volts.
+ */
+float CANTalon::GetOutputVoltage() const {
+  int throttle11;
+  CTR_Code status = m_impl->GetAppliedThrottle(throttle11);
+  float voltage = GetBusVoltage() * (float(throttle11) / 1023.0);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return voltage;
+}
+
+/**
+ *  Returns the current going through the Talon, in Amperes.
+ */
+float CANTalon::GetOutputCurrent() const {
+  double current;
+
+  CTR_Code status = m_impl->GetCurrent(current);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+
+  return current;
+}
+
+/**
+ *  Returns temperature of Talon, in degrees Celsius.
+ */
+float CANTalon::GetTemperature() const {
+  double temp;
+
+  CTR_Code status = m_impl->GetTemp(temp);
+  if (temp != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return temp;
+}
+/**
+ * Set the position value of the selected sensor.  This is useful for zero-ing
+ * quadrature encoders.
+ * Continuous sensors (like analog encoderes) can also partially be set (the
+ * portion of the postion based on overflows).
+ */
+void CANTalon::SetPosition(double pos) {
+  int32_t nativePos = ScaleRotationsToNativeUnits(m_feedbackDevice, pos);
+  CTR_Code status = m_impl->SetSensorPosition(nativePos);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ *
+ * @return The position of the sensor currently providing feedback.
+ *       When using analog sensors, 0 units corresponds to 0V, 1023
+ * units corresponds to 3.3V
+ *       When using an analog encoder (wrapping around 1023 => 0 is
+ * possible) the units are still 3.3V per 1023 units.
+ *       When using quadrature, each unit is a quadrature edge (4X)
+ * mode.
+ */
+double CANTalon::GetPosition() const {
+  int32_t position;
+  CTR_Code status = m_impl->GetSensorPosition(position);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return ScaleNativeUnitsToRotations(m_feedbackDevice, position);
+}
+/**
+ * If sensor and motor are out of phase, sensor can be inverted
+ * (position and velocity multiplied by -1).
+ * @see GetPosition and @see GetSpeed.
+ */
+void CANTalon::SetSensorDirection(bool reverseSensor) {
+  CTR_Code status = m_impl->SetRevFeedbackSensor(reverseSensor ? 1 : 0);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Flips the sign (multiplies by negative one) the throttle values going into
+ * the motor on the talon in closed loop modes.  Typically the application
+ * should use SetSensorDirection to keep sensor and motor in phase.
+ * @see SetSensorDirection
+ * However this routine is helpful for reversing the motor direction
+ * when Talon is in slave mode, or when using a single-direction position
+ * sensor in a closed-loop mode.
+ *
+ * @param reverseOutput True if motor output should be flipped; False if not.
+ */
+void CANTalon::SetClosedLoopOutputDirection(bool reverseOutput) {
+  CTR_Code status = m_impl->SetRevMotDuringCloseLoopEn(reverseOutput ? 1 : 0);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Returns the current error in the controller.
+ *
+ * @return the difference between the setpoint and the sensor value.
+ */
+int CANTalon::GetClosedLoopError() const {
+  int error;
+  /* retrieve the closed loop error in native units */
+  CTR_Code status = m_impl->GetCloseLoopErr(error);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return error;
+}
+/**
+ * Set the allowable closed loop error.
+ * @param allowableCloseLoopError allowable closed loop error for selected profile.
+ *       mA for Curent closed loop.
+ *       Talon Native Units for position and velocity.
+ */
+void CANTalon::SetAllowableClosedLoopErr(uint32_t allowableCloseLoopError)
+{
+  /* grab param enum */
+  CanTalonSRX::param_t param;
+  if (m_profile == 1) {
+    param = CanTalonSRX::eProfileParamSlot1_AllowableClosedLoopErr;
+  } else {
+    param = CanTalonSRX::eProfileParamSlot0_AllowableClosedLoopErr;
+  }
+  /* send allowable close loop er in native units */
+  ConfigSetParameter(param, allowableCloseLoopError);
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ *
+ * @returns The speed of the sensor currently providing feedback.
+ *
+ * The speed units will be in the sensor's native ticks per 100ms.
+ *
+ * For analog sensors, 3.3V corresponds to 1023 units.
+ *     So a speed of 200 equates to ~0.645 dV per 100ms or 6.451 dV per
+ * second.
+ *     If this is an analog encoder, that likely means 1.9548 rotations
+ * per sec.
+ * For quadrature encoders, each unit corresponds a quadrature edge (4X).
+ *     So a 250 count encoder will produce 1000 edge events per
+ * rotation.
+ *     An example speed of 200 would then equate to 20% of a rotation
+ * per 100ms,
+ *     or 10 rotations per second.
+ */
+double CANTalon::GetSpeed() const {
+  int32_t speed;
+  CTR_Code status = m_impl->GetSensorVelocity(speed);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return ScaleNativeUnitsToRpm(m_feedbackDevice, speed);
+}
+
+/**
+ * Get the position of whatever is in the analog pin of the Talon, regardless of
+ * whether it is actually being used for feedback.
+ *
+ * @returns The 24bit analog value.  The bottom ten bits is the ADC (0 - 1023)
+ *          on the analog pin of the Talon.
+ *          The upper 14 bits tracks the overflows and
+ * underflows (continuous sensor).
+ */
+int CANTalon::GetAnalogIn() const {
+  int position;
+  CTR_Code status = m_impl->GetAnalogInWithOv(position);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return position;
+}
+
+void CANTalon::SetAnalogPosition(int newPosition) {
+  CTR_Code status = m_impl->SetParam(CanTalonSRX::eAinPosition, newPosition);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Get the position of whatever is in the analog pin of the Talon, regardless of
+ * whether it is actually being used for feedback.
+ *
+ * @returns The ADC (0 - 1023) on analog pin of the Talon.
+ */
+int CANTalon::GetAnalogInRaw() const { return GetAnalogIn() & 0x3FF; }
+/**
+ * Get the position of whatever is in the analog pin of the Talon, regardless of
+ * whether it is actually being used for feedback.
+ *
+ * @returns The value (0 - 1023) on the analog pin of the Talon.
+ */
+int CANTalon::GetAnalogInVel() const {
+  int vel;
+  CTR_Code status = m_impl->GetAnalogInVel(vel);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return vel;
+}
+
+/**
+ * Get the position of whatever is in the analog pin of the Talon, regardless of
+ * whether it is actually being used for feedback.
+ *
+ * @returns The value (0 - 1023) on the analog pin of the Talon.
+ */
+int CANTalon::GetEncPosition() const {
+  int position;
+  CTR_Code status = m_impl->GetEncPosition(position);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return position;
+}
+void CANTalon::SetEncPosition(int newPosition) {
+  CTR_Code status = m_impl->SetParam(CanTalonSRX::eEncPosition, newPosition);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Get the position of whatever is in the analog pin of the Talon, regardless of
+ * whether it is actually being used for feedback.
+ *
+ * @returns The value (0 - 1023) on the analog pin of the Talon.
+ */
+int CANTalon::GetEncVel() const {
+  int vel;
+  CTR_Code status = m_impl->GetEncVel(vel);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return vel;
+}
+int CANTalon::GetPulseWidthPosition() const {
+  int param;
+  CTR_Code status = m_impl->GetPulseWidthPosition(param);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return param;
+}
+void CANTalon::SetPulseWidthPosition(int newPosition)
+{
+  CTR_Code status = m_impl->SetParam(CanTalonSRX::ePwdPosition, newPosition);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+int CANTalon::GetPulseWidthVelocity()const
+{
+  int param;
+  CTR_Code status = m_impl->GetPulseWidthVelocity(param);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return param;
+}
+int CANTalon::GetPulseWidthRiseToFallUs()const
+{
+  int param;
+  CTR_Code status = m_impl->GetPulseWidthRiseToFallUs(param);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return param;
+}
+int CANTalon::GetPulseWidthRiseToRiseUs()const
+{
+  int param;
+  CTR_Code status = m_impl->GetPulseWidthRiseToRiseUs(param);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return param;
+}
+/**
+ * @param which feedback sensor to check it if is connected.
+ * @return status of caller's specified sensor type.
+ */
+CANTalon::FeedbackDeviceStatus CANTalon::IsSensorPresent(FeedbackDevice feedbackDevice)const
+{
+  FeedbackDeviceStatus retval = FeedbackStatusUnknown;
+  int param;
+  /* detecting sensor health depends on which sensor caller cares about */
+  switch (feedbackDevice) {
+    case QuadEncoder:
+    case AnalogPot:
+    case AnalogEncoder:
+    case EncRising:
+    case EncFalling:
+      /* no real good way to tell if these sensor
+        are actually present so return status unknown. */
+      break;
+    case PulseWidth:
+    case CtreMagEncoder_Relative:
+    case CtreMagEncoder_Absolute:
+      /* all of these require pulse width signal to be present. */
+      CTR_Code status = m_impl->IsPulseWidthSensorPresent(param);
+      if (status != CTR_OKAY) {
+        /* we're not getting status info, signal unknown status */
+      } else {
+        /* param is updated */
+        if (param) {
+          /* pulse signal is present, sensor must be working since it always
+            generates a pulse waveform.*/
+          retval = FeedbackStatusPresent;
+        } else {
+          /* no pulse present, sensor disconnected */
+          retval = FeedbackStatusNotPresent;
+        }
+      }
+      break;
+  }
+  return retval;
+}
+/**
+ * @return IO level of QUADA pin.
+ */
+int CANTalon::GetPinStateQuadA() const {
+  int retval;
+  CTR_Code status = m_impl->GetQuadApin(retval);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return retval;
+}
+/**
+ * @return IO level of QUADB pin.
+ */
+int CANTalon::GetPinStateQuadB() const {
+  int retval;
+  CTR_Code status = m_impl->GetQuadBpin(retval);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return retval;
+}
+/**
+ * @return IO level of QUAD Index pin.
+ */
+int CANTalon::GetPinStateQuadIdx() const {
+  int retval;
+  CTR_Code status = m_impl->GetQuadIdxpin(retval);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return retval;
+}
+/**
+ * @return '1' iff forward limit switch is closed, 0 iff switch is open.
+ * This function works regardless if limit switch feature is enabled.
+ */
+int CANTalon::IsFwdLimitSwitchClosed() const {
+  int retval;
+  CTR_Code status = m_impl->GetLimitSwitchClosedFor(
+      retval); /* rename this func, '1' => open, '0' => closed */
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return retval ? 0 : 1;
+}
+/**
+ * @return '1' iff reverse limit switch is closed, 0 iff switch is open.
+ * This function works regardless if limit switch feature is enabled.
+ */
+int CANTalon::IsRevLimitSwitchClosed() const {
+  int retval;
+  CTR_Code status = m_impl->GetLimitSwitchClosedRev(
+      retval); /* rename this func, '1' => open, '0' => closed */
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return retval ? 0 : 1;
+}
+/*
+ * Simple accessor for tracked rise eventso index pin.
+ * @return number of rising edges on idx pin.
+ */
+int CANTalon::GetNumberOfQuadIdxRises() const {
+  int rises;
+  CTR_Code status = m_impl->GetEncIndexRiseEvents(
+      rises); /* rename this func, '1' => open, '0' => closed */
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return rises;
+}
+/*
+ * @param rises integral value to set into index-rises register.  Great way to
+ * zero the index count.
+ */
+void CANTalon::SetNumberOfQuadIdxRises(int rises) {
+  CTR_Code status = m_impl->SetParam(
+      CanTalonSRX::eEncIndexRiseEvents,
+      rises); /* rename this func, '1' => open, '0' => closed */
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+bool CANTalon::GetForwardLimitOK() const {
+  int limSwit = 0;
+  int softLim = 0;
+  CTR_Code status = CTR_OKAY;
+  status = m_impl->GetFault_ForSoftLim(softLim);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  status = m_impl->GetFault_ForLim(limSwit);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  /* If either fault is asserted, signal caller we are disabled (with false?) */
+  return (softLim | limSwit) ? false : true;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+bool CANTalon::GetReverseLimitOK() const {
+  int limSwit = 0;
+  int softLim = 0;
+  CTR_Code status = CTR_OKAY;
+  status = m_impl->GetFault_RevSoftLim(softLim);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  status = m_impl->GetFault_RevLim(limSwit);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  /* If either fault is asserted, signal caller we are disabled (with false?) */
+  return (softLim | limSwit) ? false : true;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+uint16_t CANTalon::GetFaults() const {
+  uint16_t retval = 0;
+  int val;
+  CTR_Code status = CTR_OKAY;
+
+  /* temperature */
+  val = 0;
+  status = m_impl->GetFault_OverTemp(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kTemperatureFault : 0;
+
+  /* voltage */
+  val = 0;
+  status = m_impl->GetFault_UnderVoltage(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kBusVoltageFault : 0;
+
+  /* fwd-limit-switch */
+  val = 0;
+  status = m_impl->GetFault_ForLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kFwdLimitSwitch : 0;
+
+  /* rev-limit-switch */
+  val = 0;
+  status = m_impl->GetFault_RevLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kRevLimitSwitch : 0;
+
+  /* fwd-soft-limit */
+  val = 0;
+  status = m_impl->GetFault_ForSoftLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kFwdSoftLimit : 0;
+
+  /* rev-soft-limit */
+  val = 0;
+  status = m_impl->GetFault_RevSoftLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kRevSoftLimit : 0;
+
+  return retval;
+}
+uint16_t CANTalon::GetStickyFaults() const {
+  uint16_t retval = 0;
+  int val;
+  CTR_Code status = CTR_OKAY;
+
+  /* temperature */
+  val = 0;
+  status = m_impl->GetStckyFault_OverTemp(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kTemperatureFault : 0;
+
+  /* voltage */
+  val = 0;
+  status = m_impl->GetStckyFault_UnderVoltage(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kBusVoltageFault : 0;
+
+  /* fwd-limit-switch */
+  val = 0;
+  status = m_impl->GetStckyFault_ForLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kFwdLimitSwitch : 0;
+
+  /* rev-limit-switch */
+  val = 0;
+  status = m_impl->GetStckyFault_RevLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kRevLimitSwitch : 0;
+
+  /* fwd-soft-limit */
+  val = 0;
+  status = m_impl->GetStckyFault_ForSoftLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kFwdSoftLimit : 0;
+
+  /* rev-soft-limit */
+  val = 0;
+  status = m_impl->GetStckyFault_RevSoftLim(val);
+  if (status != CTR_OKAY)
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  retval |= (val) ? CANSpeedController::kRevSoftLimit : 0;
+
+  return retval;
+}
+void CANTalon::ClearStickyFaults() {
+  CTR_Code status = m_impl->ClearStickyFaults();
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the maximum voltage change rate.  This ramp rate is in affect regardless
+ * of which control mode
+ * the TALON is in.
+ *
+ * When in PercentVbus or Voltage output mode, the rate at which the voltage
+ * changes can
+ * be limited to reduce current spikes.  Set this to 0.0 to disable rate
+ * limiting.
+ *
+ * @param rampRate The maximum rate of voltage change in Percent Voltage mode in
+ * V/s.
+ */
+void CANTalon::SetVoltageRampRate(double rampRate) {
+  /* Caller is expressing ramp as Voltage per sec, assuming 12V is full.
+          Talon's throttle ramp is in dThrot/d10ms.  1023 is full fwd, -1023 is
+     full rev. */
+  double rampRatedThrotPer10ms = (rampRate * 1023.0 / 12.0) / 100;
+  CTR_Code status = m_impl->SetRampThrottle((int)rampRatedThrotPer10ms);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+void CANTalon::SetVoltageCompensationRampRate(double rampRate) {
+  /* when in voltage compensation mode, the voltage compensation rate
+    directly caps the change in target voltage */
+  CTR_Code status = CTR_OKAY;
+  status = m_impl->SetVoltageCompensationRate(rampRate / 1000);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Sets a voltage change rate that applies only when a close loop contorl mode
+ * is enabled.
+ * This allows close loop specific ramp behavior.
+ *
+ * @param rampRate The maximum rate of voltage change in Percent Voltage mode in
+ * V/s.
+ */
+void CANTalon::SetCloseLoopRampRate(double rampRate) {
+  CTR_Code status = m_impl->SetCloseLoopRampRate(
+      m_profile, rampRate * 1023.0 / 12.0 / 1000.0);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * @return The version of the firmware running on the Talon
+ */
+uint32_t CANTalon::GetFirmwareVersion() const {
+  int firmwareVersion;
+  CTR_Code status = m_impl->RequestParam(CanTalonSRX::eFirmVers);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  usleep(kDelayForSolicitedSignalsUs);
+  status =
+      m_impl->GetParamResponseInt32(CanTalonSRX::eFirmVers, firmwareVersion);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+
+  /* only sent once on boot */
+  // CTR_Code status = m_impl->GetFirmVers(firmwareVersion);
+  // if (status != CTR_OKAY) {
+  //  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  //}
+
+  return firmwareVersion;
+}
+/**
+ * @return The accumulator for I gain.
+ */
+int CANTalon::GetIaccum() const {
+  CTR_Code status = m_impl->RequestParam(CanTalonSRX::ePidIaccum);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  usleep(kDelayForSolicitedSignalsUs); /* small yield for getting response */
+  int iaccum;
+  status = m_impl->GetParamResponseInt32(CanTalonSRX::ePidIaccum, iaccum);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return iaccum;
+}
+/**
+ * Clear the accumulator for I gain.
+ */
+void CANTalon::ClearIaccum() {
+  CTR_Code status = m_impl->SetParam(CanTalonSRX::ePidIaccum, 0);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigNeutralMode(NeutralMode mode) {
+  CTR_Code status = CTR_OKAY;
+  switch (mode) {
+    default:
+    case kNeutralMode_Jumper: /* use default setting in flash based on
+                                 webdash/BrakeCal button selection */
+      status = m_impl->SetOverrideBrakeType(
+          CanTalonSRX::kBrakeOverride_UseDefaultsFromFlash);
+      break;
+    case kNeutralMode_Brake:
+      status = m_impl->SetOverrideBrakeType(
+          CanTalonSRX::kBrakeOverride_OverrideBrake);
+      break;
+    case kNeutralMode_Coast:
+      status = m_impl->SetOverrideBrakeType(
+          CanTalonSRX::kBrakeOverride_OverrideCoast);
+      break;
+  }
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * @return nonzero if brake is enabled during neutral.  Zero if coast is enabled
+ * during neutral.
+ */
+int CANTalon::GetBrakeEnableDuringNeutral() const {
+  int brakeEn = 0;
+  CTR_Code status = m_impl->GetBrakeIsEnabled(brakeEn);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return brakeEn;
+}
+/**
+ * Configure how many codes per revolution are generated by your encoder.
+ *
+ * @param codesPerRev The number of counts per revolution.
+ */
+void CANTalon::ConfigEncoderCodesPerRev(uint16_t codesPerRev) {
+  /* first save the scalar so that all getters/setter work as the user expects */
+  m_codesPerRev = codesPerRev;
+  /* next send the scalar to the Talon over CAN.  This is so that the Talon can report
+    it to whoever needs it, like the webdash.  Don't bother checking the return,
+    this is only for instrumentation and is not necessary for Talon functionality. */
+  (void)m_impl->SetParam(CanTalonSRX::eNumberEncoderCPR, m_codesPerRev);
+}
+
+/**
+ * Configure the number of turns on the potentiometer.
+ *
+ * @param turns The number of turns of the potentiometer.
+ */
+void CANTalon::ConfigPotentiometerTurns(uint16_t turns) {
+  /* first save the scalar so that all getters/setter work as the user expects */
+  m_numPotTurns = turns;
+  /* next send the scalar to the Talon over CAN.  This is so that the Talon can report
+    it to whoever needs it, like the webdash.  Don't bother checking the return,
+    this is only for instrumentation and is not necessary for Talon functionality. */
+  (void)m_impl->SetParam(CanTalonSRX::eNumberPotTurns, m_numPotTurns);
+}
+
+/**
+ * @deprecated not implemented
+ */
+void CANTalon::ConfigSoftPositionLimits(double forwardLimitPosition,
+                                        double reverseLimitPosition) {
+  ConfigLimitMode(kLimitMode_SoftPositionLimits);
+  ConfigForwardLimit(forwardLimitPosition);
+  ConfigReverseLimit(reverseLimitPosition);
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::DisableSoftPositionLimits() {
+  ConfigLimitMode(kLimitMode_SwitchInputsOnly);
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * Configures the soft limit enable (wear leveled persistent memory).
+ * Also sets the limit switch overrides.
+ */
+void CANTalon::ConfigLimitMode(LimitMode mode) {
+  CTR_Code status = CTR_OKAY;
+  switch (mode) {
+    case kLimitMode_SwitchInputsOnly: /** Only use switches for limits */
+      /* turn OFF both limits. SRX has individual enables and polarity for each
+       * limit switch.*/
+      status = m_impl->SetForwardSoftEnable(false);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      status = m_impl->SetReverseSoftEnable(false);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      /* override enable the limit switches, this circumvents the webdash */
+      status = m_impl->SetOverrideLimitSwitchEn(
+          CanTalonSRX::kLimitSwitchOverride_EnableFwd_EnableRev);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      break;
+    case kLimitMode_SoftPositionLimits: /** Use both switches and soft limits */
+      /* turn on both limits. SRX has individual enables and polarity for each
+       * limit switch.*/
+      status = m_impl->SetForwardSoftEnable(true);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      status = m_impl->SetReverseSoftEnable(true);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      /* override enable the limit switches, this circumvents the webdash */
+      status = m_impl->SetOverrideLimitSwitchEn(
+          CanTalonSRX::kLimitSwitchOverride_EnableFwd_EnableRev);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      break;
+
+    case kLimitMode_SrxDisableSwitchInputs: /** disable both limit switches and
+                                               soft limits */
+      /* turn on both limits. SRX has individual enables and polarity for each
+       * limit switch.*/
+      status = m_impl->SetForwardSoftEnable(false);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      status = m_impl->SetReverseSoftEnable(false);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      /* override enable the limit switches, this circumvents the webdash */
+      status = m_impl->SetOverrideLimitSwitchEn(
+          CanTalonSRX::kLimitSwitchOverride_DisableFwd_DisableRev);
+      if (status != CTR_OKAY) {
+        wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      }
+      break;
+  }
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigForwardLimit(double forwardLimitPosition) {
+  CTR_Code status = CTR_OKAY;
+  int32_t nativeLimitPos = ScaleRotationsToNativeUnits(m_feedbackDevice, forwardLimitPosition);
+  status = m_impl->SetForwardSoftLimit(nativeLimitPos);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Change the fwd limit switch setting to normally open or closed.
+ * Talon will disable momentarilly if the Talon's current setting
+ * is dissimilar to the caller's requested setting.
+ *
+ * Since Talon saves setting to flash this should only affect
+ * a given Talon initially during robot install.
+ *
+ * @param normallyOpen true for normally open.  false for normally closed.
+ */
+void CANTalon::ConfigFwdLimitSwitchNormallyOpen(bool normallyOpen) {
+  CTR_Code status =
+      m_impl->SetParam(CanTalonSRX::eOnBoot_LimitSwitch_Forward_NormallyClosed,
+                       normallyOpen ? 0 : 1);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * Change the rev limit switch setting to normally open or closed.
+ * Talon will disable momentarilly if the Talon's current setting
+ * is dissimilar to the caller's requested setting.
+ *
+ * Since Talon saves setting to flash this should only affect
+ * a given Talon initially during robot install.
+ *
+ * @param normallyOpen true for normally open.  false for normally closed.
+ */
+void CANTalon::ConfigRevLimitSwitchNormallyOpen(bool normallyOpen) {
+  CTR_Code status =
+      m_impl->SetParam(CanTalonSRX::eOnBoot_LimitSwitch_Reverse_NormallyClosed,
+                       normallyOpen ? 0 : 1);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigReverseLimit(double reverseLimitPosition) {
+  CTR_Code status = CTR_OKAY;
+  int32_t nativeLimitPos = ScaleRotationsToNativeUnits(m_feedbackDevice, reverseLimitPosition);
+  status = m_impl->SetReverseSoftLimit(nativeLimitPos);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigMaxOutputVoltage(double voltage) {
+  /* config peak throttle when in closed-loop mode in the fwd and rev direction. */
+  ConfigPeakOutputVoltage(voltage, -voltage);
+}
+void CANTalon::ConfigPeakOutputVoltage(double forwardVoltage,double reverseVoltage) {
+  /* bounds checking */
+  if (forwardVoltage > 12)
+    forwardVoltage = 12;
+  else if (forwardVoltage < 0)
+    forwardVoltage = 0;
+  if (reverseVoltage > 0)
+    reverseVoltage = 0;
+  else if (reverseVoltage < -12)
+    reverseVoltage = -12;
+  /* config calls */
+  ConfigSetParameter(CanTalonSRX::ePeakPosOutput, 1023 * forwardVoltage / 12.0);
+  ConfigSetParameter(CanTalonSRX::ePeakNegOutput, 1023 * reverseVoltage / 12.0);
+}
+void CANTalon::ConfigNominalOutputVoltage(double forwardVoltage,double reverseVoltage) {
+  /* bounds checking */
+  if (forwardVoltage > 12)
+    forwardVoltage = 12;
+  else if (forwardVoltage < 0)
+    forwardVoltage = 0;
+  if (reverseVoltage > 0)
+    reverseVoltage = 0;
+  else if (reverseVoltage < -12)
+    reverseVoltage = -12;
+  /* config calls */
+  ConfigSetParameter(CanTalonSRX::eNominalPosOutput,1023*forwardVoltage/12.0);
+  ConfigSetParameter(CanTalonSRX::eNominalNegOutput,1023*reverseVoltage/12.0);
+}
+/**
+ * General set frame.  Since the parameter is a general integral type, this can
+ * be used for testing future features.
+ */
+void CANTalon::ConfigSetParameter(uint32_t paramEnum, double value) {
+  CTR_Code status;
+  /* config peak throttle when in closed-loop mode in the positive direction. */
+  status = m_impl->SetParam((CanTalonSRX::param_t)paramEnum,value);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * General get frame.  Since the parameter is a general integral type, this can
+ * be used for testing future features.
+ */
+bool CANTalon::GetParameter(uint32_t paramEnum, double & dvalue) const {
+  bool retval = true;
+  /* send the request frame */
+  CTR_Code status = m_impl->RequestParam((CanTalonSRX::param_t)paramEnum);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    retval = false;
+  }
+  /* small yield for getting response */
+  usleep(kDelayForSolicitedSignalsUs);
+  /* get the last received update */
+  status = m_impl->GetParamResponse((CanTalonSRX::param_t)paramEnum, dvalue);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    retval = false;
+  }
+  return retval;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigFaultTime(float faultTime) {
+  /* SRX does not have fault time.  SRX motor drive is only disabled for soft
+   * limits and limit-switch faults. */
+  wpi_setWPIErrorWithContext(IncompatibleMode, "Fault Time not supported.");
+}
+
+/**
+ * Fixup the sendMode so Set() serializes the correct demand value.
+ * Also fills the modeSelecet in the control frame to disabled.
+ * @param mode Control mode to ultimately enter once user calls Set().
+ * @see Set()
+ */
+void CANTalon::ApplyControlMode(CANSpeedController::ControlMode mode) {
+  m_controlMode = mode;
+  HALReport(HALUsageReporting::kResourceType_CANTalonSRX, m_deviceNumber + 1,
+            mode);
+  switch (mode) {
+    case kPercentVbus:
+      m_sendMode = kThrottle;
+      break;
+    case kCurrent:
+      m_sendMode = kCurrentMode;
+      break;
+    case kSpeed:
+      m_sendMode = kSpeedMode;
+      break;
+    case kPosition:
+      m_sendMode = kPositionMode;
+      break;
+    case kVoltage:
+      m_sendMode = kVoltageMode;
+      break;
+    case kFollower:
+      m_sendMode = kFollowerMode;
+      break;
+  }
+  // Keep the talon disabled until Set() is called.
+  CTR_Code status = m_impl->SetModeSelect((int)kDisabled);
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::SetControlMode(CANSpeedController::ControlMode mode) {
+  if (m_controlMode == mode) {
+    /* we already are in this mode, don't perform disable workaround */
+  } else {
+    ApplyControlMode(mode);
+  }
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+CANSpeedController::ControlMode CANTalon::GetControlMode() const {
+  return m_controlMode;
+}
+
+void CANTalon::SetExpiration(float timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+float CANTalon::GetExpiration() const {
+  return m_safetyHelper->GetExpiration();
+}
+
+bool CANTalon::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+bool CANTalon::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void CANTalon::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void CANTalon::GetDescription(std::ostringstream& desc) const {
+  desc << "CANTalon ID " <<  m_deviceNumber;
+}
+/**
+ * @param devToLookup FeedbackDevice to lookup the scalar for.  Because Talon
+ *            allows multiple sensors to be attached simultaneously, caller must
+ *            specify which sensor to lookup.
+ * @return    The number of native Talon units per rotation of the selected sensor.
+ *            Zero if the necessary sensor information is not available.
+ * @see ConfigEncoderCodesPerRev
+ * @see ConfigPotentiometerTurns
+ */
+double CANTalon::GetNativeUnitsPerRotationScalar(FeedbackDevice devToLookup)const
+{
+  bool scalingAvail = false;
+  CTR_Code status = CTR_OKAY;
+  double retval = 0;
+  switch (devToLookup) {
+    case QuadEncoder:
+    { /* When caller wants to lookup Quadrature, the QEI may be in 1x if the selected feedback is edge counter.
+       * Additionally if the quadrature source is the CTRE Mag encoder, then the CPR is known.
+       * This is nice in that the calling app does not require knowing the CPR at all.
+       * So do both checks here.
+       */
+      int32_t qeiPulsePerCount = 4; /* default to 4x */
+      switch (m_feedbackDevice) {
+        case CtreMagEncoder_Relative:
+        case CtreMagEncoder_Absolute:
+          /* we assume the quadrature signal comes from the MagEnc,
+            of which we know the CPR already */
+          retval = kNativePwdUnitsPerRotation;
+          scalingAvail = true;
+          break;
+        case EncRising: /* Talon's QEI is setup for 1x, so perform 1x math */
+        case EncFalling:
+          qeiPulsePerCount = 1;
+          break;
+        case QuadEncoder: /* Talon's QEI is 4x */
+        default: /* pulse width and everything else, assume its regular quad use. */
+          break;
+      }
+      if (scalingAvail) {
+        /* already deduced the scalar above, we're done. */
+      } else {
+        /* we couldn't deduce the scalar just based on the selection */
+        if (0 == m_codesPerRev) {
+          /* caller has never set the CPR.  Most likely caller
+            is just using engineering units so fall to the
+            bottom of this func.*/
+        } else {
+          /* Talon expects PPR units */
+          retval = qeiPulsePerCount * m_codesPerRev;
+          scalingAvail = true;
+        }
+      }
+    }  break;
+    case EncRising:
+    case EncFalling:
+      if (0 == m_codesPerRev) {
+        /* caller has never set the CPR.  Most likely caller
+          is just using engineering units so fall to the
+          bottom of this func.*/
+      } else {
+        /* Talon expects PPR units */
+        retval = 1 * m_codesPerRev;
+        scalingAvail = true;
+      }
+      break;
+    case AnalogPot:
+    case AnalogEncoder:
+      if (0 == m_numPotTurns) {
+        /* caller has never set the CPR.  Most likely caller
+          is just using engineering units so fall to the
+          bottom of this func.*/
+      } else {
+        retval = (double)kNativeAdcUnitsPerRotation / m_numPotTurns;
+        scalingAvail = true;
+      }
+      break;
+    case CtreMagEncoder_Relative:
+    case CtreMagEncoder_Absolute:
+    case PulseWidth:
+      retval = kNativePwdUnitsPerRotation;
+      scalingAvail = true;
+      break;
+  }
+  /* handle any detected errors */
+  if (status != CTR_OKAY) {
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  /* if scaling information is not possible, signal caller
+    by returning zero */
+  if (false == scalingAvail)
+    retval = 0;
+  return retval;
+}
+/**
+ * @param fullRotations   double precision value representing number of rotations of selected feedback sensor.
+ *              If user has never called the config routine for the selected sensor, then the caller
+ *              is likely passing rotations in engineering units already, in which case it is returned
+ *              as is.
+ *              @see ConfigPotentiometerTurns
+ *              @see ConfigEncoderCodesPerRev
+ * @return fullRotations in native engineering units of the Talon SRX firmware.
+ */
+int32_t CANTalon::ScaleRotationsToNativeUnits(FeedbackDevice devToLookup,double fullRotations)const
+{
+  /* first assume we don't have config info, prep the default return */
+  int32_t retval = (int32_t)fullRotations;
+  /* retrieve scaling info */
+  double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
+  /* apply scalar if its available */
+  if (scalar > 0)
+    retval = (int32_t)(fullRotations*scalar);
+  return retval;
+}
+/**
+ * @param rpm   double precision value representing number of rotations per minute of selected feedback sensor.
+ *              If user has never called the config routine for the selected sensor, then the caller
+ *              is likely passing rotations in engineering units already, in which case it is returned
+ *              as is.
+ *              @see ConfigPotentiometerTurns
+ *              @see ConfigEncoderCodesPerRev
+ * @return sensor velocity in native engineering units of the Talon SRX firmware.
+ */
+int32_t CANTalon::ScaleVelocityToNativeUnits(FeedbackDevice devToLookup,double rpm)const
+{
+  /* first assume we don't have config info, prep the default return */
+  int32_t retval = (int32_t)rpm;
+  /* retrieve scaling info */
+  double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
+  /* apply scalar if its available */
+  if (scalar > 0)
+    retval = (int32_t)(rpm * kMinutesPer100msUnit * scalar);
+  return retval;
+}
+/**
+ * @param nativePos   integral position of the feedback sensor in native Talon SRX units.
+ *              If user has never called the config routine for the selected sensor, then the return
+ *              will be in TALON SRX units as well to match the behavior in the 2015 season.
+ *              @see ConfigPotentiometerTurns
+ *              @see ConfigEncoderCodesPerRev
+ * @return double precision number of rotations, unless config was never performed.
+ */
+double CANTalon::ScaleNativeUnitsToRotations(FeedbackDevice devToLookup,int32_t nativePos)const
+{
+  /* first assume we don't have config info, prep the default return */
+  double retval = (double)nativePos;
+  /* retrieve scaling info */
+  double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
+  /* apply scalar if its available */
+  if (scalar > 0)
+    retval = ((double)nativePos) / scalar;
+  return retval;
+}
+/**
+ * @param nativeVel   integral velocity of the feedback sensor in native Talon SRX units.
+ *              If user has never called the config routine for the selected sensor, then the return
+ *              will be in TALON SRX units as well to match the behavior in the 2015 season.
+ *              @see ConfigPotentiometerTurns
+ *              @see ConfigEncoderCodesPerRev
+ * @return double precision of sensor velocity in RPM, unless config was never performed.
+ */
+double CANTalon::ScaleNativeUnitsToRpm(FeedbackDevice devToLookup, int32_t nativeVel)const
+{
+  /* first assume we don't have config info, prep the default return */
+  double retval = (double)nativeVel;
+  /* retrieve scaling info */
+  double scalar = GetNativeUnitsPerRotationScalar(devToLookup);
+  /* apply scalar if its available */
+  if (scalar > 0)
+    retval = (double)(nativeVel) / (scalar*kMinutesPer100msUnit);
+  return retval;
+}
+
+/**
+ * Enables Talon SRX to automatically zero the Sensor Position whenever an
+ * edge is detected on the index signal.
+ * @param enable     boolean input, pass true to enable feature or false to disable.
+ * @param risingEdge   boolean input, pass true to clear the position on rising edge,
+ *          pass false to clear the position on falling edge.
+ */
+void CANTalon::EnableZeroSensorPositionOnIndex(bool enable, bool risingEdge)
+{
+  if (enable) {
+    /* enable the feature, update the edge polarity first to ensure
+      it is correct before the feature is enabled. */
+    ConfigSetParameter(CanTalonSRX::eQuadIdxPolarity,risingEdge  ? 1 : 0);
+    ConfigSetParameter(CanTalonSRX::eClearPositionOnIdx,1);
+  } else {
+    /* disable the feature first, then update the edge polarity. */
+    ConfigSetParameter(CanTalonSRX::eClearPositionOnIdx,0);
+    ConfigSetParameter(CanTalonSRX::eQuadIdxPolarity,risingEdge  ? 1 : 0);
+  }
+}
+/**
+* Common interface for inverting direction of a speed controller.
+* Only works in PercentVbus, speed, and Voltage modes.
+* @param isInverted The state of inversion, true is inverted.
+*/
+void CANTalon::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool CANTalon::GetInverted() const { return m_isInverted; }
+
+/**
+ * Common interface for stopping the motor
+ * Part of the MotorSafety interface
+ *
+ * @deprecated Call Disable instead.
+*/
+void CANTalon::StopMotor() { Disable(); }
+
+void CANTalon::ValueChanged(ITable* source, llvm::StringRef key,
+                            std::shared_ptr<nt::Value> value, bool isNew) {
+  if(key == "Mode" && value->IsDouble()) SetControlMode(static_cast<CANSpeedController::ControlMode>(value->GetDouble()));
+  if(key == "p" && value->IsDouble()) SetP(value->GetDouble());
+  if(key == "i" && value->IsDouble()) SetI(value->GetDouble());
+  if(key == "d" && value->IsDouble()) SetD(value->GetDouble());
+  if(key == "f" && value->IsDouble()) SetF(value->GetDouble());
+  if(key == "Enabled" && value->IsBoolean()) {
+      if (value->GetBoolean()) {
+        Enable();
+      } else {
+        Disable();
+      }
+  }
+  if(key == "Value" && value->IsDouble()) Set(value->GetDouble());
+}
+
+bool CANTalon::IsModePID(CANSpeedController::ControlMode mode) const {
+  return mode == kCurrent || mode == kSpeed || mode == kPosition;
+}
+
+void CANTalon::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutString("~TYPE~", "CANSpeedController");
+    m_table->PutString("Type", "CANTalon");
+    m_table->PutString("Mode", GetModeName(m_controlMode));
+    m_table->PutNumber("p", GetP());
+    m_table->PutNumber("i", GetI());
+    m_table->PutNumber("d", GetD());
+    m_table->PutNumber("f", GetF());
+    m_table->PutBoolean("Enabled", IsControlEnabled());
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+void CANTalon::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener(this, true);
+  }
+}
+
+void CANTalon::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string CANTalon::GetSmartDashboardType() const {
+  return "CANSpeedController";
+}
+
+void CANTalon::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> CANTalon::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/CameraServer.cpp b/wpilibc/Athena/src/CameraServer.cpp
new file mode 100644
index 0000000..af319a4
--- /dev/null
+++ b/wpilibc/Athena/src/CameraServer.cpp
@@ -0,0 +1,260 @@
+#include "CameraServer.h"
+#include "WPIErrors.h"
+#include "Utility.h"
+
+#include <iostream>
+#include <chrono>
+#include <cstring>
+#include <sys/socket.h>
+#include <unistd.h>
+#include <netdb.h>
+
+constexpr uint8_t CameraServer::kMagicNumber[];
+
+CameraServer* CameraServer::GetInstance() {
+  static CameraServer instance;
+  return &instance;
+}
+
+CameraServer::CameraServer()
+    : m_camera(),
+      m_serverThread(&CameraServer::Serve, this),
+      m_captureThread(),
+      m_imageMutex(),
+      m_newImageVariable(),
+      m_dataPool(3),
+      m_quality(50),
+      m_autoCaptureStarted(false),
+      m_hwClient(true),
+      m_imageData(nullptr, 0, 0, false) {
+  for (int i = 0; i < 3; i++) m_dataPool.push_back(new uint8_t[kMaxImageSize]);
+}
+
+void CameraServer::FreeImageData(
+    std::tuple<uint8_t*, unsigned int, unsigned int, bool> imageData) {
+  if (std::get<3>(imageData))
+    imaqDispose(std::get<0>(imageData));
+  else if (std::get<0>(imageData) != nullptr) {
+    std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+    m_dataPool.push_back(std::get<0>(imageData));
+  }
+}
+
+void CameraServer::SetImageData(uint8_t* data, unsigned int size,
+                                unsigned int start, bool imaqData) {
+  std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+  FreeImageData(m_imageData);
+  m_imageData = std::make_tuple(data, size, start, imaqData);
+  m_newImageVariable.notify_all();
+}
+
+void CameraServer::SetImage(Image const* image) {
+  unsigned int dataSize = 0;
+  uint8_t* data =
+      (uint8_t*)imaqFlatten(image, IMAQ_FLATTEN_IMAGE, IMAQ_COMPRESSION_JPEG,
+                            10 * m_quality, &dataSize);
+
+  // If we're using a HW camera, then find the start of the data
+  bool hwClient;
+  {
+    // Make a local copy of the hwClient variable so that we can safely use it.
+    std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+    hwClient = m_hwClient;
+  }
+  unsigned int start = 0;
+  if (hwClient) {
+    while (start < dataSize - 1) {
+      if (data[start] == 0xFF && data[start + 1] == 0xD8)
+        break;
+      else
+        start++;
+    }
+  }
+  dataSize -= start;
+
+  wpi_assert(dataSize > 2);
+  SetImageData(data, dataSize, start, true);
+}
+
+void CameraServer::AutoCapture() {
+  Image* frame = imaqCreateImage(IMAQ_IMAGE_RGB, 0);
+
+  while (true) {
+    bool hwClient;
+    uint8_t* data = nullptr;
+    {
+      std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+      hwClient = m_hwClient;
+      if (hwClient) {
+        data = m_dataPool.back();
+        m_dataPool.pop_back();
+      }
+    }
+
+    if (hwClient) {
+      unsigned int size = m_camera->GetImageData(data, kMaxImageSize);
+      SetImageData(data, size);
+    } else {
+      m_camera->GetImage(frame);
+      SetImage(frame);
+    }
+  }
+}
+
+void CameraServer::StartAutomaticCapture(char const* cameraName) {
+  std::shared_ptr<USBCamera> camera =
+      std::make_shared<USBCamera>(cameraName, true);
+  camera->OpenCamera();
+  StartAutomaticCapture(camera);
+}
+
+void CameraServer::StartAutomaticCapture(std::shared_ptr<USBCamera> camera) {
+  std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+  if (m_autoCaptureStarted) return;
+
+  m_camera = camera;
+  m_camera->StartCapture();
+
+  m_captureThread = std::thread(&CameraServer::AutoCapture, this);
+  m_captureThread.detach();
+  m_autoCaptureStarted = true;
+}
+
+bool CameraServer::IsAutoCaptureStarted() {
+  std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+  return m_autoCaptureStarted;
+}
+
+void CameraServer::SetSize(unsigned int size) {
+  std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+  if (!m_camera) return;
+  if (size == kSize160x120)
+    m_camera->SetSize(160, 120);
+  else if (size == kSize320x240)
+    m_camera->SetSize(320, 240);
+  else if (size == kSize640x480)
+    m_camera->SetSize(640, 480);
+}
+
+void CameraServer::SetQuality(unsigned int quality) {
+  std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+  m_quality = quality > 100 ? 100 : quality;
+}
+
+unsigned int CameraServer::GetQuality() {
+  std::lock_guard<priority_recursive_mutex> lock(m_imageMutex);
+  return m_quality;
+}
+
+void CameraServer::Serve() {
+  int sock = socket(AF_INET, SOCK_STREAM, 0);
+
+  if (sock == -1) {
+    wpi_setErrnoError();
+    return;
+  }
+
+  int reuseAddr = 1;
+  if (setsockopt(sock, SOL_SOCKET, SO_REUSEADDR, &reuseAddr,
+                 sizeof(reuseAddr)) == -1)
+    wpi_setErrnoError();
+
+  sockaddr_in address, clientAddress;
+
+  memset(&address, 0, sizeof(address));
+  address.sin_family = AF_INET;
+  address.sin_addr.s_addr = htonl(INADDR_ANY);
+  address.sin_port = htons(kPort);
+
+  if (bind(sock, (struct sockaddr*)&address, sizeof(address)) == -1)
+    wpi_setErrnoError();
+
+  if (listen(sock, 10) == -1) wpi_setErrnoError();
+
+  while (true) {
+    socklen_t clientAddressLen = sizeof(clientAddress);
+
+    int conn =
+        accept(sock, (struct sockaddr*)&clientAddress, &clientAddressLen);
+    if (conn == -1) {
+      wpi_setErrnoError();
+      continue;
+    }
+
+    Request req;
+    if (read(conn, &req, sizeof(req)) == -1) {
+      wpi_setErrnoError();
+      close(conn);
+      continue;
+    } else {
+      req.fps = ntohl(req.fps);
+      req.compression = ntohl(req.compression);
+      req.size = ntohl(req.size);
+    }
+
+    // TODO: Support the SW Compression. The rest of the code below will work as
+    // though this
+    // check isn't here
+    if (req.compression != kHardwareCompression) {
+      wpi_setWPIErrorWithContext(IncompatibleState,
+                                 "Choose \"USB Camera HW\" on the dashboard");
+      close(conn);
+      continue;
+    }
+
+    {
+      // Wait for the camera to be setw
+      std::unique_lock<priority_recursive_mutex> lock(m_imageMutex);
+      if (!m_camera) {
+        std::cout << "Camera not yet ready, awaiting first image" << std::endl;
+        m_newImageVariable.wait(lock);
+      }
+      m_hwClient = req.compression == kHardwareCompression;
+      if (!m_hwClient)
+        SetQuality(100 - req.compression);
+      else if (m_camera)
+        m_camera->SetFPS(req.fps);
+      SetSize(req.size);
+    }
+
+    auto period = std::chrono::microseconds(1000000) / req.fps;
+    while (true) {
+      auto startTime = std::chrono::steady_clock::now();
+      std::tuple<uint8_t*, unsigned int, unsigned int, bool> imageData;
+      {
+        std::unique_lock<priority_recursive_mutex> lock(m_imageMutex);
+        m_newImageVariable.wait(lock);
+        imageData = m_imageData;
+        m_imageData = std::make_tuple<uint8_t*>(nullptr, 0, 0, false);
+      }
+
+      unsigned int size = std::get<1>(imageData);
+      unsigned int netSize = htonl(size);
+      unsigned int start = std::get<2>(imageData);
+      uint8_t* data = std::get<0>(imageData);
+
+      if (data == nullptr) continue;
+
+      if (write(conn, kMagicNumber, sizeof(kMagicNumber)) == -1) {
+        wpi_setErrnoErrorWithContext(
+            "[CameraServer] Error sending magic number");
+        FreeImageData(imageData);
+        break;
+      }
+      if (write(conn, &netSize, sizeof(netSize)) == -1) {
+        wpi_setErrnoErrorWithContext("[CameraServer] Error sending image size");
+        FreeImageData(imageData);
+        break;
+      }
+      if (write(conn, &data[start], sizeof(uint8_t) * size) == -1) {
+        wpi_setErrnoErrorWithContext("[CameraServer] Error sending image data");
+        FreeImageData(imageData);
+        break;
+      }
+      FreeImageData(imageData);
+      std::this_thread::sleep_until(startTime + period);
+    }
+    close(conn);
+  }
+  close(sock);
+}
diff --git a/wpilibc/Athena/src/Compressor.cpp b/wpilibc/Athena/src/Compressor.cpp
new file mode 100644
index 0000000..9ab89e0
--- /dev/null
+++ b/wpilibc/Athena/src/Compressor.cpp
@@ -0,0 +1,277 @@
+/*
+ * Compressor.cpp
+ */
+
+#include "Compressor.h"
+#include "WPIErrors.h"
+
+/**
+ * Constructor
+ *
+ * @param module The PCM ID to use (0-62)
+ */
+Compressor::Compressor(uint8_t pcmID) {
+  m_pcm_pointer = initializeCompressor(pcmID);
+  SetClosedLoopControl(true);
+}
+
+/**
+ *  Starts closed-loop control. Note that closed loop control is enabled by
+ * default.
+ */
+void Compressor::Start() { SetClosedLoopControl(true); }
+
+/**
+ *  Stops closed-loop control. Note that closed loop control is enabled by
+ * default.
+ */
+void Compressor::Stop() { SetClosedLoopControl(false); }
+
+/**
+ * Check if compressor output is active
+ * @return true if the compressor is on
+ */
+bool Compressor::Enabled() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressor(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Check if the pressure switch is triggered
+ * @return true if pressure is low
+ */
+bool Compressor::GetPressureSwitchValue() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getPressureSwitch(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query how much current the compressor is drawing
+ * @return The current through the compressor, in amps
+ */
+float Compressor::GetCompressorCurrent() const {
+  int32_t status = 0;
+  float value;
+
+  value = getCompressorCurrent(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Enables or disables automatically turning the compressor on when the
+ * pressure is low.
+ * @param on Set to true to enable closed loop control of the compressor. False
+ * to disable.
+ */
+void Compressor::SetClosedLoopControl(bool on) {
+  int32_t status = 0;
+
+  setClosedLoopControl(m_pcm_pointer, on, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+
+/**
+ * Returns true if the compressor will automatically turn on when the
+ * pressure is low.
+ * @return True if closed loop control of the compressor is enabled. False if
+ * disabled.
+ */
+bool Compressor::GetClosedLoopControl() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getClosedLoopControl(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output has been disabled due to high current draw.
+ * @return true if PCM is in fault state : Compressor Drive is
+ * 			disabled due to compressor current being too high.
+ */
+bool Compressor::GetCompressorCurrentTooHighFault() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressorCurrentTooHighFault(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+/**
+ * Query if the compressor output has been disabled due to high current draw
+ * (sticky).
+ * A sticky fault will not clear on device reboot, it must be cleared through
+ * code or the webdash.
+ * @return true if PCM sticky fault is set : Compressor Drive is
+ * 			disabled due to compressor current being too high.
+ */
+bool Compressor::GetCompressorCurrentTooHighStickyFault() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressorCurrentTooHighStickyFault(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+/**
+ * Query if the compressor output has been disabled due to a short circuit
+ * (sticky).
+ * A sticky fault will not clear on device reboot, it must be cleared through
+ * code or the webdash.
+ * @return true if PCM sticky fault is set : Compressor output
+ * 			appears to be shorted.
+ */
+bool Compressor::GetCompressorShortedStickyFault() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressorShortedStickyFault(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+/**
+ * Query if the compressor output has been disabled due to a short circuit.
+ * @return true if PCM is in fault state : Compressor output
+ * 			appears to be shorted.
+ */
+bool Compressor::GetCompressorShortedFault() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressorShortedFault(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+/**
+ * Query if the compressor output does not appear to be wired (sticky).
+ * A sticky fault will not clear on device reboot, it must be cleared through
+ * code or the webdash.
+ * @return true if PCM sticky fault is set : Compressor does not
+ * 			appear to be wired, i.e. compressor is
+ * 			not drawing enough current.
+ */
+bool Compressor::GetCompressorNotConnectedStickyFault() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressorNotConnectedStickyFault(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+/**
+ * Query if the compressor output does not appear to be wired.
+ * @return true if PCM is in fault state : Compressor does not
+ * 			appear to be wired, i.e. compressor is
+ * 			not drawing enough current.
+ */
+bool Compressor::GetCompressorNotConnectedFault() const {
+  int32_t status = 0;
+  bool value;
+
+  value = getCompressorNotConnectedFault(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+/**
+ * Clear ALL sticky faults inside PCM that Compressor is wired to.
+ *
+ * If a sticky fault is set, then it will be persistently cleared.  Compressor
+ * drive
+ * 		maybe momentarily disable while flags are being cleared. Care
+ * should be
+ * 		taken to not call this too frequently, otherwise normal
+ * compressor
+ * 		functionality may be prevented.
+ *
+ * If no sticky faults are set then this call will have no effect.
+ */
+void Compressor::ClearAllPCMStickyFaults() {
+  int32_t status = 0;
+
+  clearAllPCMStickyFaults(m_pcm_pointer, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+void Compressor::UpdateTable() {
+  if (m_table) {
+    m_table->PutBoolean("Enabled", Enabled());
+    m_table->PutBoolean("Pressure switch", GetPressureSwitchValue());
+  }
+}
+
+void Compressor::StartLiveWindowMode() {}
+
+void Compressor::StopLiveWindowMode() {}
+
+std::string Compressor::GetSmartDashboardType() const { return "Compressor"; }
+
+void Compressor::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Compressor::GetTable() const { return m_table; }
+
+void Compressor::ValueChanged(ITable* source, llvm::StringRef key,
+                              std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsBoolean()) return;
+  if (value->GetBoolean())
+    Start();
+  else
+    Stop();
+}
diff --git a/wpilibc/Athena/src/ControllerPower.cpp b/wpilibc/Athena/src/ControllerPower.cpp
new file mode 100644
index 0000000..ea508af
--- /dev/null
+++ b/wpilibc/Athena/src/ControllerPower.cpp
@@ -0,0 +1,176 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "ControllerPower.h"
+
+#include <stdint.h>
+#include <HAL/Power.hpp>
+#include <HAL/HAL.hpp>
+#include "ErrorBase.h"
+
+/**
+ * Get the input voltage to the robot controller
+ * @return The controller input voltage value in Volts
+ */
+double ControllerPower::GetInputVoltage() {
+  int32_t status = 0;
+  double retVal = getVinVoltage(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the input current to the robot controller
+ * @return The controller input current value in Amps
+ */
+double ControllerPower::GetInputCurrent() {
+  int32_t status = 0;
+  double retVal = getVinCurrent(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the voltage of the 6V rail
+ * @return The controller 6V rail voltage value in Volts
+ */
+double ControllerPower::GetVoltage6V() {
+  int32_t status = 0;
+  double retVal = getUserVoltage6V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the current output of the 6V rail
+ * @return The controller 6V rail output current value in Amps
+ */
+double ControllerPower::GetCurrent6V() {
+  int32_t status = 0;
+  double retVal = getUserCurrent6V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the enabled state of the 6V rail. The rail may be disabled due to a
+ * controller
+ * brownout, a short circuit on the rail, or controller over-voltage
+ * @return The controller 6V rail enabled value. True for enabled.
+ */
+bool ControllerPower::GetEnabled6V() {
+  int32_t status = 0;
+  bool retVal = getUserActive6V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the count of the total current faults on the 6V rail since the controller
+ * has booted
+ * @return The number of faults.
+ */
+int ControllerPower::GetFaultCount6V() {
+  int32_t status = 0;
+  int retVal = getUserCurrentFaults6V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the voltage of the 5V rail
+ * @return The controller 5V rail voltage value in Volts
+ */
+double ControllerPower::GetVoltage5V() {
+  int32_t status = 0;
+  double retVal = getUserVoltage5V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the current output of the 5V rail
+ * @return The controller 5V rail output current value in Amps
+ */
+double ControllerPower::GetCurrent5V() {
+  int32_t status = 0;
+  double retVal = getUserCurrent5V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the enabled state of the 5V rail. The rail may be disabled due to a
+ * controller
+ * brownout, a short circuit on the rail, or controller over-voltage
+ * @return The controller 5V rail enabled value. True for enabled.
+ */
+bool ControllerPower::GetEnabled5V() {
+  int32_t status = 0;
+  bool retVal = getUserActive5V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the count of the total current faults on the 5V rail since the controller
+ * has booted
+ * @return The number of faults
+ */
+int ControllerPower::GetFaultCount5V() {
+  int32_t status = 0;
+  int retVal = getUserCurrentFaults5V(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the voltage of the 3.3V rail
+ * @return The controller 3.3V rail voltage value in Volts
+ */
+double ControllerPower::GetVoltage3V3() {
+  int32_t status = 0;
+  double retVal = getUserVoltage3V3(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the current output of the 3.3V rail
+ * @return The controller 3.3V rail output current value in Amps
+ */
+double ControllerPower::GetCurrent3V3() {
+  int32_t status = 0;
+  double retVal = getUserCurrent3V3(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the enabled state of the 3.3V rail. The rail may be disabled due to a
+ * controller
+ * brownout, a short circuit on the rail, or controller over-voltage
+ * @return The controller 3.3V rail enabled value. True for enabled.
+ */
+bool ControllerPower::GetEnabled3V3() {
+  int32_t status = 0;
+  bool retVal = getUserActive3V3(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the count of the total current faults on the 3.3V rail since the
+ * controller has booted
+ * @return The number of faults
+ */
+int ControllerPower::GetFaultCount3V3() {
+  int32_t status = 0;
+  int retVal = getUserCurrentFaults3V3(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
\ No newline at end of file
diff --git a/wpilibc/Athena/src/Counter.cpp b/wpilibc/Athena/src/Counter.cpp
new file mode 100644
index 0000000..cd70de5
--- /dev/null
+++ b/wpilibc/Athena/src/Counter.cpp
@@ -0,0 +1,590 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Counter.h"
+#include "AnalogTrigger.h"
+#include "DigitalInput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+/**
+ * Create an instance of a counter where no sources are selected.
+ * They all must be selected by calling functions to specify the upsource and
+ * the downsource
+ * independently.
+ *
+ * This creates a ChipObject counter and initializes status variables
+ * appropriately.
+ *
+ * The counter will start counting immediately.
+ * @param mode The counter mode
+ */
+Counter::Counter(Mode mode) {
+  int32_t status = 0;
+  m_counter = initializeCounter(mode, &m_index, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  SetMaxPeriod(.5);
+
+  HALReport(HALUsageReporting::kResourceType_Counter, m_index, mode);
+}
+
+/**
+ * Create an instance of a counter from a Digital Source (such as a Digital
+ * Input).
+ * This is used if an existing digital input is to be shared by multiple other
+ * objects such
+ * as encoders or if the Digital Source is not a Digital Input channel (such as
+ * an Analog Trigger).
+ *
+ * The counter will start counting immediately.
+ * @param source A pointer to the existing DigitalSource object. It will be set
+ * as the Up Source.
+ */
+Counter::Counter(DigitalSource *source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a counter from a Digital Source (such as a Digital
+ * Input).
+ * This is used if an existing digital input is to be shared by multiple other
+ * objects such
+ * as encoders or if the Digital Source is not a Digital Input channel (such as
+ * an Analog Trigger).
+ *
+ * The counter will start counting immediately.
+ * @param source A pointer to the existing DigitalSource object. It will be
+ * set as the Up Source.
+ */
+Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Create an up-Counter instance given a channel.
+ *
+ * The counter will start counting immediately.
+ * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+ * 10-25 are on the MXP
+ */
+Counter::Counter(int32_t channel) : Counter(kTwoPulse) {
+  SetUpSource(channel);
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Create an instance of a simple up-Counter given an analog trigger.
+ * Use the trigger state output from the analog trigger.
+ *
+ * The counter will start counting immediately.
+ * @param trigger The pointer to the existing AnalogTrigger object.
+ */
+DEPRECATED("Use pass-by-reference instead.")
+Counter::Counter(AnalogTrigger *trigger) : Counter(kTwoPulse) {
+  SetUpSource(trigger->CreateOutput(kState));
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Create an instance of a simple up-Counter given an analog trigger.
+ * Use the trigger state output from the analog trigger.
+ *
+ * The counter will start counting immediately.
+ * @param trigger The reference to the existing AnalogTrigger object.
+ */
+Counter::Counter(const AnalogTrigger &trigger) : Counter(kTwoPulse) {
+  SetUpSource(trigger.CreateOutput(kState));
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ * Creates a full up-down counter given two Digital Sources
+ * @param encodingType The quadrature decoding mode (1x or 2x)
+ * @param upSource The pointer to the DigitalSource to set as the up source
+ * @param downSource The pointer to the DigitalSource to set as the down source
+ * @param inverted True to invert the output (reverse the direction)
+ */
+Counter::Counter(EncodingType encodingType, DigitalSource *upSource,
+                 DigitalSource *downSource, bool inverted)
+    : Counter(encodingType,
+              std::shared_ptr<DigitalSource>(upSource,
+                                               NullDeleter<DigitalSource>()),
+              std::shared_ptr<DigitalSource>(downSource,
+                                               NullDeleter<DigitalSource>()),
+              inverted) {}
+
+/**
+ * Create an instance of a Counter object.
+ * Creates a full up-down counter given two Digital Sources
+ * @param encodingType The quadrature decoding mode (1x or 2x)
+ * @param upSource The pointer to the DigitalSource to set as the up source
+ * @param downSource The pointer to the DigitalSource to set as the down source
+ * @param inverted True to invert the output (reverse the direction)
+ */
+Counter::Counter(EncodingType encodingType,
+                 std::shared_ptr<DigitalSource> upSource,
+                 std::shared_ptr<DigitalSource> downSource, bool inverted)
+    : Counter(kExternalDirection) {
+  if (encodingType != k1X && encodingType != k2X) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Counter only supports 1X and 2X quadrature decoding.");
+    return;
+  }
+  SetUpSource(upSource);
+  SetDownSource(downSource);
+  int32_t status = 0;
+
+  if (encodingType == k1X) {
+    SetUpSourceEdge(true, false);
+    setCounterAverageSize(m_counter, 1, &status);
+  } else {
+    SetUpSourceEdge(true, true);
+    setCounterAverageSize(m_counter, 2, &status);
+  }
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  SetDownSourceEdge(inverted, true);
+}
+
+/**
+ * Delete the Counter object.
+ */
+Counter::~Counter() {
+  SetUpdateWhenEmpty(true);
+
+  int32_t status = 0;
+  freeCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  m_counter = nullptr;
+}
+
+/**
+ * Set the upsource for the counter as a digital input channel.
+ * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+ * 10-25 are on the MXP
+ */
+void Counter::SetUpSource(int32_t channel) {
+  if (StatusIsFatal()) return;
+  SetUpSource(std::make_shared<DigitalInput>(channel));
+}
+
+/**
+ * Set the up counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Up Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetUpSource(AnalogTrigger *analogTrigger,
+                          AnalogTriggerType triggerType) {
+  SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                               NullDeleter<AnalogTrigger>()),
+              triggerType);
+}
+
+/**
+ * Set the up counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Up Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                          AnalogTriggerType triggerType) {
+  if (StatusIsFatal()) return;
+  SetUpSource(analogTrigger->CreateOutput(triggerType));
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ * Set the up counting DigitalSource.
+ * @param source Pointer to the DigitalSource object to set as the up source
+ */
+void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
+  if (StatusIsFatal()) return;
+  m_upSource = source;
+  if (m_upSource->StatusIsFatal()) {
+    CloneError(*m_upSource);
+  } else {
+    int32_t status = 0;
+    setCounterUpSource(m_counter, source->GetChannelForRouting(),
+                       source->GetAnalogTriggerForRouting(), &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+void Counter::SetUpSource(DigitalSource *source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ * Set the up counting DigitalSource.
+ * @param source Reference to the DigitalSource object to set as the up source
+ */
+void Counter::SetUpSource(DigitalSource &source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the edge sensitivity on an up counting source.
+ * Set the up source to either detect rising edges or falling edges or both.
+ * @param risingEdge True to trigger on rising edges
+ * @param fallingEdge True to trigger on falling edges
+ */
+void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_upSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr UpSource before setting UpSourceEdge");
+  }
+  int32_t status = 0;
+  setCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Disable the up counting source to the counter.
+ */
+void Counter::ClearUpSource() {
+  if (StatusIsFatal()) return;
+  m_upSource.reset();
+  int32_t status = 0;
+  clearCounterUpSource(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the down counting source to be a digital input channel.
+ * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+ * 10-25 are on the MXP
+ */
+void Counter::SetDownSource(int32_t channel) {
+  if (StatusIsFatal()) return;
+  SetDownSource(std::make_shared<DigitalInput>(channel));
+}
+
+/**
+ * Set the down counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Down
+ * Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetDownSource(AnalogTrigger *analogTrigger,
+                            AnalogTriggerType triggerType) {
+  SetDownSource(std::shared_ptr<AnalogTrigger>(analogTrigger, NullDeleter<AnalogTrigger>()), triggerType);
+}
+
+/**
+ * Set the down counting source to be an analog trigger.
+ * @param analogTrigger The analog trigger object that is used for the Down
+ * Source
+ * @param triggerType The analog trigger output that will trigger the counter.
+ */
+void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                            AnalogTriggerType triggerType) {
+  if (StatusIsFatal()) return;
+  SetDownSource(analogTrigger->CreateOutput(triggerType));
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ * Set the down counting DigitalSource.
+ * @param source Pointer to the DigitalSource object to set as the down source
+ */
+void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
+  if (StatusIsFatal()) return;
+  m_downSource = source;
+  if (m_downSource->StatusIsFatal()) {
+    CloneError(*m_downSource);
+  } else {
+    int32_t status = 0;
+    setCounterDownSource(m_counter, source->GetChannelForRouting(),
+                         source->GetAnalogTriggerForRouting(), &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+void Counter::SetDownSource(DigitalSource *source) {
+  SetDownSource(std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ * Set the down counting DigitalSource.
+ * @param source Reference to the DigitalSource object to set as the down source
+ */
+void Counter::SetDownSource(DigitalSource &source) {
+  SetDownSource(std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the edge sensitivity on a down counting source.
+ * Set the down source to either detect rising edges or falling edges.
+ * @param risingEdge True to trigger on rising edges
+ * @param fallingEdge True to trigger on falling edges
+ */
+void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_downSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr DownSource before setting DownSourceEdge");
+  }
+  int32_t status = 0;
+  setCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Disable the down counting source to the counter.
+ */
+void Counter::ClearDownSource() {
+  if (StatusIsFatal()) return;
+  m_downSource.reset();
+  int32_t status = 0;
+  clearCounterDownSource(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set standard up / down counting mode on this counter.
+ * Up and down counts are sourced independently from two inputs.
+ */
+void Counter::SetUpDownCounterMode() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterUpDownMode(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set external direction mode on this counter.
+ * Counts are sourced on the Up counter input.
+ * The Down counter input represents the direction to count.
+ */
+void Counter::SetExternalDirectionMode() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterExternalDirectionMode(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set Semi-period mode on this counter.
+ * Counts up on both rising and falling edges.
+ */
+void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterSemiPeriodMode(m_counter, highSemiPeriod, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Configure the counter to count in up or down based on the length of the input
+ * pulse.
+ * This mode is most useful for direction sensitive gear tooth sensors.
+ * @param threshold The pulse length beyond which the counter counts the
+ * opposite direction.  Units are seconds.
+ */
+void Counter::SetPulseLengthMode(float threshold) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterPulseLengthMode(m_counter, threshold, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the Samples to Average which specifies the number of samples of the timer
+ * to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+ */
+int Counter::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int32_t samples = getCounterSamplesToAverage(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return samples;
+}
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer
+ * to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void Counter::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+  }
+  int32_t status = 0;
+  setCounterSamplesToAverage(m_counter, samplesToAverage, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Read the current counter value.
+ * Read the value at this instant. It may still be running, so it reflects the
+ * current value. Next
+ * time it is read, it might have a different value.
+ */
+int32_t Counter::Get() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int32_t value = getCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * Reset the Counter to zero.
+ * Set the counter value to zero. This doesn't effect the running state of the
+ * counter, just sets
+ * the current value to zero.
+ */
+void Counter::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  resetCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the Period of the most recent count.
+ * Returns the time interval of the most recent count. This can be used for
+ * velocity calculations
+ * to determine shaft speed.
+ * @returns The period between the last two pulses in units of seconds.
+ */
+double Counter::GetPeriod() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = getCounterPeriod(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * Set the maximum period where the device is still considered "moving".
+ * Sets the maximum period where the device is considered moving. This value is
+ * used to determine
+ * the "stopped" state of the counter using the GetStopped method.
+ * @param maxPeriod The maximum period where the counted device is considered
+ * moving in
+ * seconds.
+ */
+void Counter::SetMaxPeriod(double maxPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterMaxPeriod(m_counter, maxPeriod, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Select whether you want to continue updating the event timer output when
+ * there are no samples captured.
+ * The output of the event timer has a buffer of periods that are averaged and
+ * posted to
+ * a register on the FPGA.  When the timer detects that the event source has
+ * stopped
+ * (based on the MaxPeriod) the buffer of samples to be averaged is emptied.  If
+ * you
+ * enable the update when empty, you will be notified of the stopped source and
+ * the event
+ * time will report 0 samples.  If you disable update when empty, the most
+ * recent average
+ * will remain on the output until a new sample is acquired.  You will never see
+ * 0 samples
+ * output (except when there have been no events since an FPGA reset) and you
+ * will likely not
+ * see the stopped bit become true (since it is updated at the end of an average
+ * and there are
+ * no samples to average).
+ * @param enabled True to enable update when empty
+ */
+void Counter::SetUpdateWhenEmpty(bool enabled) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterUpdateWhenEmpty(m_counter, enabled, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Determine if the clock is stopped.
+ * Determine if the clocked input is stopped based on the MaxPeriod value set
+ * using the
+ * SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the device (and
+ * counter) are
+ * assumed to be stopped and it returns true.
+ * @return Returns true if the most recent counter period exceeds the MaxPeriod
+ * value set by
+ * SetMaxPeriod.
+ */
+bool Counter::GetStopped() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = getCounterStopped(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * The last direction the counter value changed.
+ * @return The last direction the counter value changed.
+ */
+bool Counter::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = getCounterDirection(m_counter, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * Set the Counter to return reversed sensing on the direction.
+ * This allows counters to change the direction they are counting in the case of
+ * 1X and 2X
+ * quadrature encoding only. Any other counter mode isn't supported.
+ * @param reverseDirection true if the value counted should be negated.
+ */
+void Counter::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  setCounterReverseDirection(m_counter, reverseDirection, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+void Counter::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+void Counter::StartLiveWindowMode() {}
+
+void Counter::StopLiveWindowMode() {}
+
+std::string Counter::GetSmartDashboardType() const { return "Counter"; }
+
+void Counter::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Counter::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/DigitalGlitchFilter.cpp b/wpilibc/Athena/src/DigitalGlitchFilter.cpp
new file mode 100644
index 0000000..56147cb
--- /dev/null
+++ b/wpilibc/Athena/src/DigitalGlitchFilter.cpp
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include <algorithm>
+#include <array>
+
+#include "DigitalGlitchFilter.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "Encoder.h"
+#include "Counter.h"
+#include "Utility.h"
+
+std::array<bool, 3> DigitalGlitchFilter::m_filterAllocated = {{false, false,
+                                                               false}};
+priority_mutex DigitalGlitchFilter::m_mutex;
+
+DigitalGlitchFilter::DigitalGlitchFilter() {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  auto index =
+      std::find(m_filterAllocated.begin(), m_filterAllocated.end(), false);
+  wpi_assert(index != m_filterAllocated.end());
+
+  m_channelIndex = std::distance(m_filterAllocated.begin(), index);
+  *index = true;
+
+  HALReport(HALUsageReporting::kResourceType_DigitalFilter, m_channelIndex);
+}
+
+DigitalGlitchFilter::~DigitalGlitchFilter() {
+  if (m_channelIndex >= 0) {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_filterAllocated[m_channelIndex] = false;
+  }
+}
+
+/**
+ * Assigns the DigitalSource to this glitch filter.
+ *
+ * @param input The DigitalSource to add.
+ */
+void DigitalGlitchFilter::Add(DigitalSource *input) {
+  DoAdd(input, m_channelIndex + 1);
+}
+
+void DigitalGlitchFilter::DoAdd(DigitalSource *input, int requested_index) {
+  // Some sources from Counters and Encoders are null.  By pushing the check
+  // here, we catch the issue more generally.
+  if (input) {
+    int32_t status = 0;
+    setFilterSelect(m_digital_ports[input->GetChannelForRouting()],
+                    requested_index, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+    // Validate that we set it correctly.
+    int actual_index = getFilterSelect(
+        m_digital_ports[input->GetChannelForRouting()], &status);
+    wpi_assertEqual(actual_index, requested_index);
+
+    HALReport(HALUsageReporting::kResourceType_DigitalInput,
+              input->GetChannelForRouting());
+  }
+}
+
+/**
+ * Assigns the Encoder to this glitch filter.
+ *
+ * @param input The Encoder to add.
+ */
+void DigitalGlitchFilter::Add(Encoder *input) {
+  Add(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_bSource.get());
+}
+
+/**
+ * Assigns the Counter to this glitch filter.
+ *
+ * @param input The Counter to add.
+ */
+void DigitalGlitchFilter::Add(Counter *input) {
+  Add(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_downSource.get());
+}
+
+/**
+ * Removes a digital input from this filter.
+ *
+ * Removes the DigitalSource from this glitch filter and re-assigns it to
+ * the default filter.
+ *
+ * @param input The DigitalSource to remove.
+ */
+void DigitalGlitchFilter::Remove(DigitalSource *input) {
+  DoAdd(input, 0);
+}
+
+/**
+ * Removes an encoder from this filter.
+ *
+ * Removes the Encoder from this glitch filter and re-assigns it to
+ * the default filter.
+ *
+ * @param input The Encoder to remove.
+ */
+void DigitalGlitchFilter::Remove(Encoder *input) {
+  Remove(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_bSource.get());
+}
+
+/**
+ * Removes a counter from this filter.
+ *
+ * Removes the Counter from this glitch filter and re-assigns it to
+ * the default filter.
+ *
+ * @param input The Counter to remove.
+ */
+void DigitalGlitchFilter::Remove(Counter *input) {
+  Remove(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_downSource.get());
+}
+
+/**
+ * Sets the number of cycles that the input must not change state for.
+ *
+ * @param fpga_cycles The number of FPGA cycles.
+ */
+void DigitalGlitchFilter::SetPeriodCycles(uint32_t fpga_cycles) {
+  int32_t status = 0;
+  setFilterPeriod(m_channelIndex, fpga_cycles, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Sets the number of nanoseconds that the input must not change state for.
+ *
+ * @param nanoseconds The number of nanoseconds.
+ */
+void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
+  int32_t status = 0;
+  uint32_t fpga_cycles =
+      nanoseconds * kSystemClockTicksPerMicrosecond / 4 / 1000;
+  setFilterPeriod(m_channelIndex, fpga_cycles, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Gets the number of cycles that the input must not change state for.
+ *
+ * @return The number of cycles.
+ */
+uint32_t DigitalGlitchFilter::GetPeriodCycles() {
+  int32_t status = 0;
+  uint32_t fpga_cycles = getFilterPeriod(m_channelIndex, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  return fpga_cycles;
+}
+
+/**
+ * Gets the number of nanoseconds that the input must not change state for.
+ *
+ * @return The number of nanoseconds.
+ */
+uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() {
+  int32_t status = 0;
+  uint32_t fpga_cycles = getFilterPeriod(m_channelIndex, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  return static_cast<uint64_t>(fpga_cycles) * 1000L /
+         static_cast<uint64_t>(kSystemClockTicksPerMicrosecond / 4);
+}
diff --git a/wpilibc/Athena/src/DigitalInput.cpp b/wpilibc/Athena/src/DigitalInput.cpp
new file mode 100644
index 0000000..f6b96f5
--- /dev/null
+++ b/wpilibc/Athena/src/DigitalInput.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalInput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+#include <limits>
+#include <sstream>
+
+/**
+ * Create an instance of a Digital Input class.
+ * Creates a digital input given a channel.
+ *
+ * @param channel The DIO channel 0-9 are on-board, 10-25 are on the MXP port
+ */
+DigitalInput::DigitalInput(uint32_t channel) {
+  std::stringstream buf;
+
+  if (!CheckDigitalChannel(channel)) {
+    buf << "Digital Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    m_channel = std::numeric_limits<uint32_t>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  allocateDIO(m_digital_ports[channel], true, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  LiveWindow::GetInstance()->AddSensor("DigitalInput", channel, this);
+  HALReport(HALUsageReporting::kResourceType_DigitalInput, channel);
+}
+
+/**
+ * Free resources associated with the Digital Input class.
+ */
+DigitalInput::~DigitalInput() {
+  if (StatusIsFatal()) return;
+  if (m_interrupt != nullptr) {
+    int32_t status = 0;
+    cleanInterrupts(m_interrupt, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    m_interrupt = nullptr;
+    m_interrupts->Free(m_interruptIndex);
+  }
+
+  int32_t status = 0;
+  freeDIO(m_digital_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the value from a digital input channel.
+ * Retrieve the value of a single digital input channel from the FPGA.
+ */
+bool DigitalInput::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = getDIO(m_digital_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * @return The GPIO channel number that this object represents.
+ */
+uint32_t DigitalInput::GetChannel() const { return m_channel; }
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+uint32_t DigitalInput::GetChannelForRouting() const { return GetChannel(); }
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+uint32_t DigitalInput::GetModuleForRouting() const { return 0; }
+
+/**
+ * @return The value to be written to the analog trigger field of a routing mux.
+ */
+bool DigitalInput::GetAnalogTriggerForRouting() const { return false; }
+
+void DigitalInput::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutBoolean("Value", Get());
+  }
+}
+
+void DigitalInput::StartLiveWindowMode() {}
+
+void DigitalInput::StopLiveWindowMode() {}
+
+std::string DigitalInput::GetSmartDashboardType() const {
+  return "DigitalInput";
+}
+
+void DigitalInput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> DigitalInput::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/DigitalOutput.cpp b/wpilibc/Athena/src/DigitalOutput.cpp
new file mode 100644
index 0000000..d74f93b
--- /dev/null
+++ b/wpilibc/Athena/src/DigitalOutput.cpp
@@ -0,0 +1,230 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "DigitalOutput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+#include <limits>
+#include <sstream>
+
+/**
+ * Create an instance of a digital output.
+ * Create a digital output given a channel.
+ *
+ * @param channel The digital channel 0-9 are on-board, 10-25 are on the MXP
+ * port
+ */
+DigitalOutput::DigitalOutput(uint32_t channel) {
+  std::stringstream buf;
+
+  m_pwmGenerator = (void *)std::numeric_limits<uint32_t>::max();
+  if (!CheckDigitalChannel(channel)) {
+    buf << "Digital Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    m_channel = std::numeric_limits<uint32_t>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  allocateDIO(m_digital_ports[channel], false, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_DigitalOutput, channel);
+}
+
+/**
+ * Free the resources associated with a digital output.
+ */
+DigitalOutput::~DigitalOutput() {
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+  if (StatusIsFatal()) return;
+  // Disable the PWM in case it was running.
+  DisablePWM();
+
+  int32_t status = 0;
+  freeDIO(m_digital_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the value of a digital output.
+ * Set the value of a digital output to either one (true) or zero (false).
+ * @param value 1 (true) for high, 0 (false) for disabled
+ */
+void DigitalOutput::Set(uint32_t value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  setDIO(m_digital_ports[m_channel], value, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * @return The GPIO channel number that this object represents.
+ */
+uint32_t DigitalOutput::GetChannel() const { return m_channel; }
+
+/**
+ * Output a single pulse on the digital output line.
+ * Send a single pulse on the digital output line where the pulse duration is
+ * specified in seconds.
+ * Maximum pulse length is 0.0016 seconds.
+ * @param length The pulselength in seconds
+ */
+void DigitalOutput::Pulse(float length) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  pulse(m_digital_ports[m_channel], length, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Determine if the pulse is still going.
+ * Determine if a previously started pulse is still going.
+ */
+bool DigitalOutput::IsPulsing() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool value = isPulsing(m_digital_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+
+/**
+ * Change the PWM frequency of the PWM output on a Digital Output line.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz.  The frequency resolution is
+ * logarithmic.
+ *
+ * There is only one PWM frequency for all digital channels.
+ *
+ * @param rate The frequency to output all digital output PWM signals.
+ */
+void DigitalOutput::SetPWMRate(float rate) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  setPWMRate(rate, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Enable a PWM Output on this line.
+ *
+ * Allocate one of the 6 DO PWM generator resources from this module.
+ *
+ * Supply the initial duty-cycle to output so as to avoid a glitch when first
+ * starting.
+ *
+ * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
+ * but is reduced the higher the frequency of the PWM signal is.
+ *
+ * @param initialDutyCycle The duty-cycle to start generating. [0..1]
+ */
+void DigitalOutput::EnablePWM(float initialDutyCycle) {
+  if (m_pwmGenerator != (void *)std::numeric_limits<uint32_t>::max()) return;
+
+  int32_t status = 0;
+
+  if (StatusIsFatal()) return;
+  m_pwmGenerator = allocatePWM(&status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+  setPWMDutyCycle(m_pwmGenerator, initialDutyCycle, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+  setPWMOutputChannel(m_pwmGenerator, m_channel, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Change this line from a PWM output back to a static Digital Output line.
+ *
+ * Free up one of the 6 DO PWM generator resources that were in use.
+ */
+void DigitalOutput::DisablePWM() {
+  if (StatusIsFatal()) return;
+  if (m_pwmGenerator == (void *)std::numeric_limits<uint32_t>::max()) return;
+
+  int32_t status = 0;
+
+  // Disable the output by routing to a dead bit.
+  setPWMOutputChannel(m_pwmGenerator, kDigitalChannels, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  freePWM(m_pwmGenerator, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  m_pwmGenerator = (void *)std::numeric_limits<uint32_t>::max();
+}
+
+/**
+ * Change the duty-cycle that is being generated on the line.
+ *
+ * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
+ * but is reduced the higher the frequency of the PWM signal is.
+ *
+ * @param dutyCycle The duty-cycle to change to. [0..1]
+ */
+void DigitalOutput::UpdateDutyCycle(float dutyCycle) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  setPWMDutyCycle(m_pwmGenerator, dutyCycle, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+uint32_t DigitalOutput::GetChannelForRouting() const { return GetChannel(); }
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+uint32_t DigitalOutput::GetModuleForRouting() const { return 0; }
+
+/**
+ * @return The value to be written to the analog trigger field of a routing mux.
+ */
+bool DigitalOutput::GetAnalogTriggerForRouting() const { return false; }
+
+void DigitalOutput::ValueChanged(ITable* source, llvm::StringRef key,
+                                 std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsBoolean()) return;
+  Set(value->GetBoolean());
+}
+
+void DigitalOutput::UpdateTable() {}
+
+void DigitalOutput::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void DigitalOutput::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string DigitalOutput::GetSmartDashboardType() const {
+  return "Digital Output";
+}
+
+void DigitalOutput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> DigitalOutput::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/DoubleSolenoid.cpp b/wpilibc/Athena/src/DoubleSolenoid.cpp
new file mode 100644
index 0000000..4fb2943
--- /dev/null
+++ b/wpilibc/Athena/src/DoubleSolenoid.cpp
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "DoubleSolenoid.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+#include <sstream>
+
+/**
+ * Constructor.
+ * Uses the default PCM ID of 0
+ * @param forwardChannel The forward channel number on the PCM (0..7).
+ * @param reverseChannel The reverse channel number on the PCM (0..7).
+ */
+DoubleSolenoid::DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel)
+    : DoubleSolenoid(GetDefaultSolenoidModule(), forwardChannel, reverseChannel) {}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The CAN ID of the PCM.
+ * @param forwardChannel The forward channel on the PCM to control (0..7).
+ * @param reverseChannel The reverse channel on the PCM to control (0..7).
+ */
+DoubleSolenoid::DoubleSolenoid(uint8_t moduleNumber, uint32_t forwardChannel,
+                               uint32_t reverseChannel)
+    : SolenoidBase(moduleNumber),
+      m_forwardChannel(forwardChannel),
+      m_reverseChannel(reverseChannel) {
+  std::stringstream buf;
+  if (!CheckSolenoidModule(m_moduleNumber)) {
+    buf << "Solenoid Module " << m_moduleNumber;
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf.str());
+    return;
+  }
+  if (!CheckSolenoidChannel(m_forwardChannel)) {
+    buf << "Solenoid Module " << m_forwardChannel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+  if (!CheckSolenoidChannel(m_reverseChannel)) {
+    buf << "Solenoid Module " << m_reverseChannel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+  Resource::CreateResourceObject(
+      m_allocated, m_maxModules * m_maxPorts);
+
+  buf << "Solenoid " << m_forwardChannel << " (Module: " << m_moduleNumber
+      << ")";
+  if (m_allocated->Allocate(
+          m_moduleNumber * kSolenoidChannels + m_forwardChannel, buf.str()) ==
+      std::numeric_limits<uint32_t>::max()) {
+    CloneError(*m_allocated);
+    return;
+  }
+
+  buf << "Solenoid " << m_reverseChannel << " (Module: " << m_moduleNumber
+      << ")";
+  if (m_allocated->Allocate(
+          m_moduleNumber * kSolenoidChannels + m_reverseChannel, buf.str()) ==
+      std::numeric_limits<uint32_t>::max()) {
+    CloneError(*m_allocated);
+    return;
+  }
+
+  m_forwardMask = 1 << m_forwardChannel;
+  m_reverseMask = 1 << m_reverseChannel;
+  HALReport(HALUsageReporting::kResourceType_Solenoid, m_forwardChannel,
+            m_moduleNumber);
+  HALReport(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel,
+            m_moduleNumber);
+  LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", m_moduleNumber,
+                                         m_forwardChannel, this);
+}
+
+/**
+ * Destructor.
+ */
+DoubleSolenoid::~DoubleSolenoid() {
+  if (CheckSolenoidModule(m_moduleNumber)) {
+    m_allocated->Free(m_moduleNumber * kSolenoidChannels + m_forwardChannel);
+    m_allocated->Free(m_moduleNumber * kSolenoidChannels + m_reverseChannel);
+  }
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param value The value to set (Off, Forward or Reverse)
+ */
+void DoubleSolenoid::Set(Value value) {
+  if (StatusIsFatal()) return;
+  uint8_t rawValue = 0x00;
+
+  switch (value) {
+    case kOff:
+      rawValue = 0x00;
+      break;
+    case kForward:
+      rawValue = m_forwardMask;
+      break;
+    case kReverse:
+      rawValue = m_reverseMask;
+      break;
+  }
+
+  SolenoidBase::Set(rawValue, m_forwardMask | m_reverseMask, m_moduleNumber);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+DoubleSolenoid::Value DoubleSolenoid::Get() const {
+  if (StatusIsFatal()) return kOff;
+  uint8_t value = GetAll(m_moduleNumber);
+
+  if (value & m_forwardMask) return kForward;
+  if (value & m_reverseMask) return kReverse;
+  return kOff;
+}
+/**
+ * Check if the forward solenoid is blacklisted.
+ * 		If a solenoid is shorted, it is added to the blacklist and
+ * 		disabled until power cycle, or until faults are cleared.
+ * 		@see ClearAllPCMStickyFaults()
+ *
+ * @return If solenoid is disabled due to short.
+ */
+bool DoubleSolenoid::IsFwdSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_forwardMask) ? 1 : 0;
+}
+/**
+ * Check if the reverse solenoid is blacklisted.
+ * 		If a solenoid is shorted, it is added to the blacklist and
+ * 		disabled until power cycle, or until faults are cleared.
+ * 		@see ClearAllPCMStickyFaults()
+ *
+ * @return If solenoid is disabled due to short.
+ */
+bool DoubleSolenoid::IsRevSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_reverseMask) ? 1 : 0;
+}
+
+void DoubleSolenoid::ValueChanged(ITable* source, llvm::StringRef key,
+                                  std::shared_ptr<nt::Value> value,
+                                  bool isNew) {
+  if (!value->IsString()) return;
+  Value lvalue = kOff;
+  if (value->GetString() == "Forward")
+    lvalue = kForward;
+  else if (value->GetString() == "Reverse")
+    lvalue = kReverse;
+  Set(lvalue);
+}
+
+void DoubleSolenoid::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutString(
+        "Value", (Get() == kForward ? "Forward"
+                                    : (Get() == kReverse ? "Reverse" : "Off")));
+  }
+}
+
+void DoubleSolenoid::StartLiveWindowMode() {
+  Set(kOff);
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void DoubleSolenoid::StopLiveWindowMode() {
+  Set(kOff);
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string DoubleSolenoid::GetSmartDashboardType() const {
+  return "Double Solenoid";
+}
+
+void DoubleSolenoid::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> DoubleSolenoid::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/DriverStation.cpp b/wpilibc/Athena/src/DriverStation.cpp
new file mode 100644
index 0000000..455a987
--- /dev/null
+++ b/wpilibc/Athena/src/DriverStation.cpp
@@ -0,0 +1,537 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "DriverStation.h"
+#include "AnalogInput.h"
+#include "Timer.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "MotorSafetyHelper.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include <string.h>
+#include "Log.hpp"
+
+// set the logging level
+TLogLevel dsLogLevel = logDEBUG;
+const double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
+
+#define DS_LOG(level)     \
+  if (level > dsLogLevel) \
+    ;                     \
+  else                    \
+  Log().Get(level)
+
+const uint32_t DriverStation::kJoystickPorts;
+
+/**
+ * DriverStation constructor.
+ *
+ * This is only called once the first time GetInstance() is called
+ */
+DriverStation::DriverStation() {
+  // All joysticks should default to having zero axes, povs and buttons, so
+  // uninitialized memory doesn't get sent to speed controllers.
+  for (unsigned int i = 0; i < kJoystickPorts; i++) {
+    m_joystickAxes[i].count = 0;
+    m_joystickPOVs[i].count = 0;
+    m_joystickButtons[i].count = 0;
+    m_joystickDescriptor[i].isXbox = 0;
+    m_joystickDescriptor[i].type = -1;
+    m_joystickDescriptor[i].name[0] = '\0';
+  }
+  // Register that semaphore with the network communications task.
+  // It will signal when new packet data is available.
+  HALSetNewDataSem(&m_packetDataAvailableCond);
+
+  AddToSingletonList();
+
+  m_task = Task("DriverStation", &DriverStation::Run, this);
+}
+
+DriverStation::~DriverStation() {
+  m_isRunning = false;
+  m_task.join();
+
+  // Unregister our semaphore.
+  HALSetNewDataSem(nullptr);
+}
+
+void DriverStation::Run() {
+  m_isRunning = true;
+  int period = 0;
+  while (m_isRunning) {
+    {
+      std::unique_lock<priority_mutex> lock(m_packetDataAvailableMutex);
+      m_packetDataAvailableCond.wait(lock);
+    }
+    GetData();
+    m_waitForDataCond.notify_all();
+
+    if (++period >= 4) {
+      MotorSafetyHelper::CheckMotors();
+      period = 0;
+    }
+    if (m_userInDisabled) HALNetworkCommunicationObserveUserProgramDisabled();
+    if (m_userInAutonomous)
+      HALNetworkCommunicationObserveUserProgramAutonomous();
+    if (m_userInTeleop) HALNetworkCommunicationObserveUserProgramTeleop();
+    if (m_userInTest) HALNetworkCommunicationObserveUserProgramTest();
+  }
+}
+
+/**
+ * Return a pointer to the singleton DriverStation.
+ * @return Pointer to the DS instance
+ */
+DriverStation &DriverStation::GetInstance() {
+  static DriverStation instance;
+  return instance;
+}
+
+/**
+ * Copy data from the DS task for the user.
+ * If no new data exists, it will just be returned, otherwise
+ * the data will be copied from the DS polling loop.
+ */
+void DriverStation::GetData() {
+  // Get the status of all of the joysticks
+  for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
+    HALGetJoystickAxes(stick, &m_joystickAxes[stick]);
+    HALGetJoystickPOVs(stick, &m_joystickPOVs[stick]);
+    HALGetJoystickButtons(stick, &m_joystickButtons[stick]);
+    HALGetJoystickDescriptor(stick, &m_joystickDescriptor[stick]);
+  }
+  m_newControlData.give();
+}
+
+/**
+ * Read the battery voltage.
+ *
+ * @return The battery voltage in Volts.
+ */
+float DriverStation::GetBatteryVoltage() const {
+  int32_t status = 0;
+  float voltage = getVinVoltage(&status);
+  wpi_setErrorWithContext(status, "getVinVoltage");
+
+  return voltage;
+}
+
+/**
+ * Reports errors related to unplugged joysticks
+ * Throttles the errors so that they don't overwhelm the DS
+ */
+void DriverStation::ReportJoystickUnpluggedError(std::string message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportError(message);
+    m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
+  }
+}
+
+/**
+ * Returns the number of axes on a given joystick port
+ *
+ * @param stick The joystick port number
+ * @return The number of axes on the indicated joystick
+ */
+int DriverStation::GetStickAxisCount(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  HALJoystickAxes joystickAxes;
+  HALGetJoystickAxes(stick, &joystickAxes);
+  return joystickAxes.count;
+}
+
+/**
+ * Returns the name of the joystick at the given port
+ *
+ * @param stick The joystick port number
+ * @return The name of the joystick at the given port
+ */
+std::string DriverStation::GetJoystickName(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  }
+  std::string retVal(m_joystickDescriptor[0].name);
+  return retVal;
+}
+
+/**
+ * Returns the type of joystick at a given port
+ *
+ * @param stick The joystick port number
+ * @return The HID type of joystick at the given port
+ */
+int DriverStation::GetJoystickType(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  return (int)m_joystickDescriptor[stick].type;
+}
+
+/**
+ * Returns a boolean indicating if the controller is an xbox controller.
+ *
+ * @param stick The joystick port number
+ * @return A boolean that is true if the controller is an xbox controller.
+ */
+bool DriverStation::GetJoystickIsXbox(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  return (bool)m_joystickDescriptor[stick].isXbox;
+}
+
+/**
+ * Returns the types of Axes on a given joystick port
+ *
+ * @param stick The joystick port number and the target axis
+ * @return What type of axis the axis is reporting to be
+ */
+int DriverStation::GetJoystickAxisType(uint32_t stick, uint8_t axis) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  return m_joystickDescriptor[stick].axisTypes[axis];
+}
+
+/**
+ * Returns the number of POVs on a given joystick port
+ *
+ * @param stick The joystick port number
+ * @return The number of POVs on the indicated joystick
+ */
+int DriverStation::GetStickPOVCount(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  HALJoystickPOVs joystickPOVs;
+  HALGetJoystickPOVs(stick, &joystickPOVs);
+  return joystickPOVs.count;
+}
+
+/**
+ * Returns the number of buttons on a given joystick port
+ *
+ * @param stick The joystick port number
+ * @return The number of buttons on the indicated joystick
+ */
+int DriverStation::GetStickButtonCount(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  HALJoystickButtons joystickButtons;
+  HALGetJoystickButtons(stick, &joystickButtons);
+  return joystickButtons.count;
+}
+
+/**
+ * Get the value of the axis on a joystick.
+ * This depends on the mapping of the joystick connected to the specified port.
+ *
+ * @param stick The joystick to read.
+ * @param axis The analog axis value to read from the joystick.
+ * @return The value of the axis on the joystick.
+ */
+float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  if (axis >= m_joystickAxes[stick].count) {
+    if (axis >= kMaxJoystickAxes)
+      wpi_setWPIError(BadJoystickAxis);
+    else
+      ReportJoystickUnpluggedError(
+          "WARNING: Joystick Axis missing, check if all controllers are "
+          "plugged in\n");
+    return 0.0f;
+  }
+
+  int8_t value = m_joystickAxes[stick].axes[axis];
+
+  if (value < 0) {
+    return value / 128.0f;
+  } else {
+    return value / 127.0f;
+  }
+}
+
+/**
+ * Get the state of a POV on the joystick.
+ *
+ * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+ */
+int DriverStation::GetStickPOV(uint32_t stick, uint32_t pov) {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+
+  if (pov >= m_joystickPOVs[stick].count) {
+    if (pov >= kMaxJoystickPOVs)
+      wpi_setWPIError(BadJoystickAxis);
+    else
+      ReportJoystickUnpluggedError(
+          "WARNING: Joystick POV missing, check if all controllers are plugged "
+          "in\n");
+    return -1;
+  }
+
+  return m_joystickPOVs[stick].povs[pov];
+}
+
+/**
+ * The state of the buttons on the joystick.
+ *
+ * @param stick The joystick to read.
+ * @return The state of the buttons on the joystick.
+ */
+uint32_t DriverStation::GetStickButtons(uint32_t stick) const {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  return m_joystickButtons[stick].buttons;
+}
+
+/**
+ * The state of one joystick button. Button indexes begin at 1.
+ *
+ * @param stick The joystick to read.
+ * @param button The button index, beginning at 1.
+ * @return The state of the joystick button.
+ */
+bool DriverStation::GetStickButton(uint32_t stick, uint8_t button) {
+  if (stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+
+  if (button > m_joystickButtons[stick].count) {
+    ReportJoystickUnpluggedError(
+        "WARNING: Joystick Button missing, check if all controllers are "
+        "plugged in\n");
+    return false;
+  }
+  if (button == 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+  return ((0x1 << (button - 1)) & m_joystickButtons[stick].buttons) != 0;
+}
+
+/**
+ * Check if the DS has enabled the robot
+ * @return True if the robot is enabled and the DS is connected
+ */
+bool DriverStation::IsEnabled() const {
+  HALControlWord controlWord;
+  memset(&controlWord, 0, sizeof(controlWord));
+  HALGetControlWord(&controlWord);
+  return controlWord.enabled && controlWord.dsAttached;
+}
+
+/**
+ * Check if the robot is disabled
+ * @return True if the robot is explicitly disabled or the DS is not connected
+ */
+bool DriverStation::IsDisabled() const {
+  HALControlWord controlWord;
+  memset(&controlWord, 0, sizeof(controlWord));
+  HALGetControlWord(&controlWord);
+  return !(controlWord.enabled && controlWord.dsAttached);
+}
+
+/**
+ * Check if the DS is commanding autonomous mode
+ * @return True if the robot is being commanded to be in autonomous mode
+ */
+bool DriverStation::IsAutonomous() const {
+  HALControlWord controlWord;
+  memset(&controlWord, 0, sizeof(controlWord));
+  HALGetControlWord(&controlWord);
+  return controlWord.autonomous;
+}
+
+/**
+ * Check if the DS is commanding teleop mode
+ * @return True if the robot is being commanded to be in teleop mode
+ */
+bool DriverStation::IsOperatorControl() const {
+  HALControlWord controlWord;
+  memset(&controlWord, 0, sizeof(controlWord));
+  HALGetControlWord(&controlWord);
+  return !(controlWord.autonomous || controlWord.test);
+}
+
+/**
+ * Check if the DS is commanding test mode
+ * @return True if the robot is being commanded to be in test mode
+ */
+bool DriverStation::IsTest() const {
+  HALControlWord controlWord;
+  HALGetControlWord(&controlWord);
+  return controlWord.test;
+}
+
+/**
+ * Check if the DS is attached
+ * @return True if the DS is connected to the robot
+ */
+bool DriverStation::IsDSAttached() const {
+  HALControlWord controlWord;
+  memset(&controlWord, 0, sizeof(controlWord));
+  HALGetControlWord(&controlWord);
+  return controlWord.dsAttached;
+}
+
+/**
+ * Check if the FPGA outputs are enabled. The outputs may be disabled if the
+ * robot is disabled
+ * or e-stopped, the watchdog has expired, or if the roboRIO browns out.
+ * @return True if the FPGA outputs are enabled.
+ */
+bool DriverStation::IsSysActive() const {
+  int32_t status = 0;
+  bool retVal = HALGetSystemActive(&status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Check if the system is browned out.
+ * @return True if the system is browned out
+ */
+bool DriverStation::IsSysBrownedOut() const {
+  int32_t status = 0;
+  bool retVal = HALGetBrownedOut(&status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Has a new control packet from the driver station arrived since the last time
+ * this function was called?
+ * Warning: If you call this function from more than one place at the same time,
+ * you will not get the get the intended behaviour.
+ * @return True if the control data has been updated since the last call.
+ */
+bool DriverStation::IsNewControlData() const {
+  return m_newControlData.tryTake() == false;
+}
+
+/**
+ * Is the driver station attached to a Field Management System?
+ * @return True if the robot is competing on a field being controlled by a Field
+ * Management System
+ */
+bool DriverStation::IsFMSAttached() const {
+  HALControlWord controlWord;
+  HALGetControlWord(&controlWord);
+  return controlWord.fmsAttached;
+}
+
+/**
+ * Return the alliance that the driver station says it is on.
+ * This could return kRed or kBlue
+ * @return The Alliance enum (kRed, kBlue or kInvalid)
+ */
+DriverStation::Alliance DriverStation::GetAlliance() const {
+  HALAllianceStationID allianceStationID;
+  HALGetAllianceStation(&allianceStationID);
+  switch (allianceStationID) {
+    case kHALAllianceStationID_red1:
+    case kHALAllianceStationID_red2:
+    case kHALAllianceStationID_red3:
+      return kRed;
+    case kHALAllianceStationID_blue1:
+    case kHALAllianceStationID_blue2:
+    case kHALAllianceStationID_blue3:
+      return kBlue;
+    default:
+      return kInvalid;
+  }
+}
+
+/**
+ * Return the driver station location on the field
+ * This could return 1, 2, or 3
+ * @return The location of the driver station (1-3, 0 for invalid)
+ */
+uint32_t DriverStation::GetLocation() const {
+  HALAllianceStationID allianceStationID;
+  HALGetAllianceStation(&allianceStationID);
+  switch (allianceStationID) {
+    case kHALAllianceStationID_red1:
+    case kHALAllianceStationID_blue1:
+      return 1;
+    case kHALAllianceStationID_red2:
+    case kHALAllianceStationID_blue2:
+      return 2;
+    case kHALAllianceStationID_red3:
+    case kHALAllianceStationID_blue3:
+      return 3;
+    default:
+      return 0;
+  }
+}
+
+/**
+ * Wait until a new packet comes from the driver station
+ * This blocks on a semaphore, so the waiting is efficient.
+ * This is a good way to delay processing until there is new driver station data
+ * to act on
+ */
+void DriverStation::WaitForData() {
+  std::unique_lock<priority_mutex> lock(m_waitForDataMutex);
+  m_waitForDataCond.wait(lock);
+}
+
+/**
+ * Return the approximate match time
+ * The FMS does not send an official match time to the robots, but does send an
+ * approximate match time.
+ * The value will count down the time remaining in the current period (auto or
+ * teleop).
+ * Warning: This is not an official time (so it cannot be used to dispute ref
+ * calls or guarantee that a function
+ * will trigger before the match ends)
+ * The Practice Match function of the DS approximates the behaviour seen on the
+ * field.
+ * @return Time remaining in current match period (auto or teleop)
+ */
+double DriverStation::GetMatchTime() const {
+  float matchTime;
+  HALGetMatchTime(&matchTime);
+  return (double)matchTime;
+}
+
+/**
+ * Report an error to the DriverStation messages window.
+ * The error is also printed to the program console.
+ */
+void DriverStation::ReportError(std::string error) {
+  std::cout << error << std::endl;
+
+  HALControlWord controlWord;
+  HALGetControlWord(&controlWord);
+  if (controlWord.dsAttached) {
+    HALSetErrorData(error.c_str(), error.size(), 0);
+  }
+}
diff --git a/wpilibc/Athena/src/Encoder.cpp b/wpilibc/Athena/src/Encoder.cpp
new file mode 100644
index 0000000..0fa12df
--- /dev/null
+++ b/wpilibc/Athena/src/Encoder.cpp
@@ -0,0 +1,561 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Encoder.h"
+#include "DigitalInput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Common initialization code for Encoders.
+ * This code allocates resources for Encoders and is common to all constructors.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param reverseDirection If true, counts down instead of up (this is all
+ * relative)
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ * decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be
+ * 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are
+ * selected then
+ * a counter object will be used and the returned value will either exactly
+ * match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
+  m_encodingType = encodingType;
+  switch (encodingType) {
+    case k4X: {
+      m_encodingScale = 4;
+      if (m_aSource->StatusIsFatal()) {
+        CloneError(*m_aSource);
+        return;
+      }
+      if (m_bSource->StatusIsFatal()) {
+        CloneError(*m_bSource);
+        return;
+      }
+      int32_t status = 0;
+      m_encoder = initializeEncoder(
+          m_aSource->GetModuleForRouting(), m_aSource->GetChannelForRouting(),
+          m_aSource->GetAnalogTriggerForRouting(),
+          m_bSource->GetModuleForRouting(), m_bSource->GetChannelForRouting(),
+          m_bSource->GetAnalogTriggerForRouting(), reverseDirection, &m_index,
+          &status);
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      m_counter = nullptr;
+      SetMaxPeriod(.5);
+      break;
+    }
+    case k1X:
+    case k2X: {
+      m_encodingScale = encodingType == k1X ? 1 : 2;
+      m_counter = std::make_unique<Counter>(m_encodingType, m_aSource,
+                                              m_bSource, reverseDirection);
+      m_index = m_counter->GetFPGAIndex();
+      break;
+    }
+    default:
+      wpi_setErrorWithContext(-1, "Invalid encodingType argument");
+      break;
+  }
+
+  HALReport(HALUsageReporting::kResourceType_Encoder, m_index, encodingType);
+  LiveWindow::GetInstance()->AddSensor("Encoder",
+                                       m_aSource->GetChannelForRouting(), this);
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b channels.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param aChannel The a channel DIO channel. 0-9 are on-board, 10-25 are on the
+ * MXP port
+ * @param bChannel The b channel DIO channel. 0-9 are on-board, 10-25 are on the
+ * MXP port
+ * @param reverseDirection represents the orientation of the encoder and inverts
+ * the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ * decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be
+ * 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are
+ * selected then
+ * a counter object will be used and the returned value will either exactly
+ * match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection,
+                 EncodingType encodingType) {
+  m_aSource = std::make_shared<DigitalInput>(aChannel);
+  m_bSource = std::make_shared<DigitalInput>(bChannel);
+  InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b channels as digital inputs. This is used in
+ * the case where the digital inputs are shared. The Encoder class will not
+ * allocate the digital inputs and assume that they already are counted.
+ * The counter will start counting immediately.
+ *
+ * @param aSource The source that should be used for the a channel.
+ * @param bSource the source that should be used for the b channel.
+ * @param reverseDirection represents the orientation of the encoder and inverts
+ * the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ * decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be
+ * 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are
+ * selected then
+ * a counter object will be used and the returned value will either exactly
+ * match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(DigitalSource *aSource, DigitalSource *bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(aSource, NullDeleter<DigitalSource>()),
+      m_bSource(bSource, NullDeleter<DigitalSource>()) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::Encoder(std::shared_ptr<DigitalSource> aSource,
+                 std::shared_ptr<DigitalSource> bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(aSource), m_bSource(bSource) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Encoder constructor.
+ * Construct a Encoder given a and b channels as digital inputs. This is used in
+ * the case
+ * where the digital inputs are shared. The Encoder class will not allocate the
+ * digital inputs
+ * and assume that they already are counted.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param aSource The source that should be used for the a channel.
+ * @param bSource the source that should be used for the b channel.
+ * @param reverseDirection represents the orientation of the encoder and inverts
+ * the output values
+ * if necessary so forward represents positive values.
+ * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ * decoding. If 4X is
+ * selected, then an encoder FPGA object is used and the returned counts will be
+ * 4x the encoder
+ * spec'd value since all rising and falling edges are counted. If 1X or 2X are
+ * selected then
+ * a counter object will be used and the returned value will either exactly
+ * match the spec'd count
+ * or be double (2x) the spec'd count.
+ */
+Encoder::Encoder(DigitalSource &aSource, DigitalSource &bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(&aSource, NullDeleter<DigitalSource>()),
+      m_bSource(&bSource, NullDeleter<DigitalSource>())
+{
+  InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Free the resources for an Encoder.
+ * Frees the FPGA resources associated with an Encoder.
+ */
+Encoder::~Encoder() {
+  if (!m_counter) {
+    int32_t status = 0;
+    freeEncoder(m_encoder, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
+ * Used to divide raw edge counts down to spec'd counts.
+ */
+int32_t Encoder::GetEncodingScale() const { return m_encodingScale; }
+
+/**
+ * Gets the raw value from the encoder.
+ * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
+ * factor.
+ * @return Current raw count from the encoder
+ */
+int32_t Encoder::GetRaw() const {
+  if (StatusIsFatal()) return 0;
+  int32_t value;
+  if (m_counter)
+    value = m_counter->Get();
+  else {
+    int32_t status = 0;
+    value = getEncoder(m_encoder, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+  return value;
+}
+
+/**
+ * Gets the current count.
+ * Returns the current count on the Encoder.
+ * This method compensates for the decoding type.
+ *
+ * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale
+ * factor.
+ */
+int32_t Encoder::Get() const {
+  if (StatusIsFatal()) return 0;
+  return (int32_t)(GetRaw() * DecodingScaleFactor());
+}
+
+/**
+ * Reset the Encoder distance to zero.
+ * Resets the current count to zero on the encoder.
+ */
+void Encoder::Reset() {
+  if (StatusIsFatal()) return;
+  if (m_counter)
+    m_counter->Reset();
+  else {
+    int32_t status = 0;
+    resetEncoder(m_encoder, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use GetRate() in favor of this method.  This returns unscaled
+ * periods and GetRate() scales using value from SetDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ */
+double Encoder::GetPeriod() const {
+  if (StatusIsFatal()) return 0.0;
+  if (m_counter) {
+    return m_counter->GetPeriod() / DecodingScaleFactor();
+  } else {
+    int32_t status = 0;
+    double period = getEncoderPeriod(m_encoder, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    return period;
+  }
+}
+
+/**
+ * Sets the maximum period for stopped detection.
+ * Sets the value that represents the maximum period of the Encoder before it
+ * will assume
+ * that the attached device is stopped. This timeout allows users to determine
+ * if the wheels or
+ * other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
+ * periods and SetMinRate() scales using value from SetDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before the
+ * FPGA will
+ * report the device stopped. This is expressed in seconds.
+ */
+void Encoder::SetMaxPeriod(double maxPeriod) {
+  if (StatusIsFatal()) return;
+  if (m_counter) {
+    m_counter->SetMaxPeriod(maxPeriod * DecodingScaleFactor());
+  } else {
+    int32_t status = 0;
+    setEncoderMaxPeriod(m_encoder, maxPeriod, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Determine if the encoder is stopped.
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder
+ * is considered
+ * stopped and false if it is still moving. A stopped encoder is one where the
+ * most recent pulse
+ * width exceeds the MaxPeriod.
+ * @return True if the encoder is considered stopped.
+ */
+bool Encoder::GetStopped() const {
+  if (StatusIsFatal()) return true;
+  if (m_counter) {
+    return m_counter->GetStopped();
+  } else {
+    int32_t status = 0;
+    bool value = getEncoderStopped(m_encoder, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    return value;
+  }
+}
+
+/**
+ * The last direction the encoder value changed.
+ * @return The last direction the encoder value changed.
+ */
+bool Encoder::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  if (m_counter) {
+    return m_counter->GetDirection();
+  } else {
+    int32_t status = 0;
+    bool value = getEncoderDirection(m_encoder, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    return value;
+  }
+}
+
+/**
+ * The scale needed to convert a raw counter value into a number of encoder
+ * pulses.
+ */
+double Encoder::DecodingScaleFactor() const {
+  if (StatusIsFatal()) return 0.0;
+  switch (m_encodingType) {
+    case k1X:
+      return 1.0;
+    case k2X:
+      return 0.5;
+    case k4X:
+      return 0.25;
+    default:
+      return 0.0;
+  }
+}
+
+/**
+ * Get the distance the robot has driven since the last reset.
+ *
+ * @return The distance driven since the last reset as scaled by the value from
+ * SetDistancePerPulse().
+ */
+double Encoder::GetDistance() const {
+  if (StatusIsFatal()) return 0.0;
+  return GetRaw() * DecodingScaleFactor() * m_distancePerPulse;
+}
+
+/**
+ * Get the current rate of the encoder.
+ * Units are distance per second as scaled by the value from
+ * SetDistancePerPulse().
+ *
+ * @return The current rate of the encoder.
+ */
+double Encoder::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  return (m_distancePerPulse / GetPeriod());
+}
+
+/**
+ * Set the minimum rate of the device before the hardware reports it stopped.
+ *
+ * @param minRate The minimum rate.  The units are in distance per second as
+ * scaled by the value from SetDistancePerPulse().
+ */
+void Encoder::SetMinRate(double minRate) {
+  if (StatusIsFatal()) return;
+  SetMaxPeriod(m_distancePerPulse / minRate);
+}
+
+/**
+ * Set the distance per pulse for this encoder.
+ * This sets the multiplier used to determine the distance driven based on the
+ * count value
+ * from the encoder.
+ * Do not include the decoding type in this scale.  The library already
+ * compensates for the decoding type.
+ * Set this value based on the encoder's rated Pulses per Revolution and
+ * factor in gearing reductions following the encoder shaft.
+ * This distance can be in any units you like, linear or angular.
+ *
+ * @param distancePerPulse The scale factor that will be used to convert pulses
+ * to useful units.
+ */
+void Encoder::SetDistancePerPulse(double distancePerPulse) {
+  if (StatusIsFatal()) return;
+  m_distancePerPulse = distancePerPulse;
+}
+
+/**
+ * Set the direction sensing for this encoder.
+ * This sets the direction sensing on the encoder so that it could count in the
+ * correct
+ * software direction regardless of the mounting.
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void Encoder::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  if (m_counter) {
+    m_counter->SetReverseDirection(reverseDirection);
+  } else {
+    int32_t status = 0;
+    setEncoderReverseDirection(m_encoder, reverseDirection, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer
+ * to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void Encoder::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+  }
+  int32_t status = 0;
+  switch (m_encodingType) {
+    case k4X:
+      setEncoderSamplesToAverage(m_encoder, samplesToAverage, &status);
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      break;
+    case k1X:
+    case k2X:
+      m_counter->SetSamplesToAverage(samplesToAverage);
+      break;
+  }
+}
+
+/**
+ * Get the Samples to Average which specifies the number of samples of the timer
+ * to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+ */
+int Encoder::GetSamplesToAverage() const {
+  int result = 1;
+  int32_t status = 0;
+  switch (m_encodingType) {
+    case k4X:
+      result = getEncoderSamplesToAverage(m_encoder, &status);
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      break;
+    case k1X:
+    case k2X:
+      result = m_counter->GetSamplesToAverage();
+      break;
+  }
+  return result;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current value of the selected source parameter.
+ */
+double Encoder::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kDisplacement:
+      return GetDistance();
+    case PIDSourceType::kRate:
+      return GetRate();
+    default:
+      return 0.0;
+  }
+}
+
+/**
+ * Set the index source for the encoder.  When this source is activated, the
+ * encoder count automatically resets.
+ *
+ * @param channel A DIO channel to set as the encoder index
+ * @param type The state that will cause the encoder to reset
+ */
+void Encoder::SetIndexSource(uint32_t channel, Encoder::IndexingType type) {
+  int32_t status = 0;
+  bool activeHigh = (type == kResetWhileHigh) || (type == kResetOnRisingEdge);
+  bool edgeSensitive =
+      (type == kResetOnFallingEdge) || (type == kResetOnRisingEdge);
+
+  setEncoderIndexSource(m_encoder, channel, false, activeHigh, edgeSensitive,
+                        &status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the index source for the encoder.  When this source is activated, the
+ * encoder count automatically resets.
+ *
+ * @param channel A digital source to set as the encoder index
+ * @param type The state that will cause the encoder to reset
+ */
+DEPRECATED("Use pass-by-reference instead.")
+void Encoder::SetIndexSource(DigitalSource *source,
+                             Encoder::IndexingType type) {
+  SetIndexSource(*source, type);
+}
+
+/**
+ * Set the index source for the encoder.  When this source is activated, the
+ * encoder count automatically resets.
+ *
+ * @param channel A digital source to set as the encoder index
+ * @param type The state that will cause the encoder to reset
+ */
+void Encoder::SetIndexSource(const DigitalSource &source,
+                             Encoder::IndexingType type) {
+  int32_t status = 0;
+  bool activeHigh = (type == kResetWhileHigh) || (type == kResetOnRisingEdge);
+  bool edgeSensitive =
+      (type == kResetOnFallingEdge) || (type == kResetOnRisingEdge);
+
+  setEncoderIndexSource(m_encoder, source.GetChannelForRouting(),
+                        source.GetAnalogTriggerForRouting(), activeHigh,
+                        edgeSensitive, &status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+}
+
+void Encoder::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Speed", GetRate());
+    m_table->PutNumber("Distance", GetDistance());
+    m_table->PutNumber("Distance per Tick", m_distancePerPulse);
+  }
+}
+
+void Encoder::StartLiveWindowMode() {}
+
+void Encoder::StopLiveWindowMode() {}
+
+std::string Encoder::GetSmartDashboardType() const {
+  if (m_encodingType == k4X)
+    return "Quadrature Encoder";
+  else
+    return "Encoder";
+}
+
+void Encoder::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Encoder::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/GearTooth.cpp b/wpilibc/Athena/src/GearTooth.cpp
new file mode 100644
index 0000000..b659125
--- /dev/null
+++ b/wpilibc/Athena/src/GearTooth.cpp
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "GearTooth.h"
+#include "LiveWindow/LiveWindow.h"
+
+constexpr double GearTooth::kGearToothThreshold;
+
+/**
+ * Common code called by the constructors.
+ */
+void GearTooth::EnableDirectionSensing(bool directionSensitive) {
+  if (directionSensitive) {
+    SetPulseLengthMode(kGearToothThreshold);
+  }
+}
+
+/**
+ * Construct a GearTooth sensor given a channel.
+ *
+ * @param channel The DIO channel that the sensor is connected to. 0-9 are
+ * on-board, 10-25 are on the MXP.
+ * @param directionSensitive True to enable the pulse length decoding in
+ * hardware to specify count direction.
+ */
+GearTooth::GearTooth(uint32_t channel, bool directionSensitive)
+    : Counter(channel) {
+  EnableDirectionSensing(directionSensitive);
+  LiveWindow::GetInstance()->AddSensor("GearTooth", channel, this);
+}
+
+/**
+ * Construct a GearTooth sensor given a digital input.
+ * This should be used when sharing digital inputs.
+ *
+ * @param source A pointer to the existing DigitalSource object (such as a
+ * DigitalInput)
+ * @param directionSensitive True to enable the pulse length decoding in
+ * hardware to specify count direction.
+ */
+GearTooth::GearTooth(DigitalSource *source, bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Construct a GearTooth sensor given a digital input.
+ * This should be used when sharing digital inputs.
+ *
+ * @param source A reference to the existing DigitalSource object (such as a
+ * DigitalInput)
+ * @param directionSensitive True to enable the pulse length decoding in
+ * hardware to specify count direction.
+ */
+GearTooth::GearTooth(std::shared_ptr<DigitalSource> source, bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+}
+
+std::string GearTooth::GetSmartDashboardType() const { return "GearTooth"; }
diff --git a/wpilibc/Athena/src/GyroBase.cpp b/wpilibc/Athena/src/GyroBase.cpp
new file mode 100644
index 0000000..4cc9056
--- /dev/null
+++ b/wpilibc/Athena/src/GyroBase.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "GyroBase.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Get the PIDOutput for the PIDSource base object. Can be set to return
+ * angle or rate using SetPIDSourceType(). Defaults to angle.
+ *
+ * @return The PIDOutput (angle or rate, defaults to angle)
+ */
+double GyroBase::PIDGet() {
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kRate:
+      return GetRate();
+    case PIDSourceType::kDisplacement:
+      return GetAngle();
+    default:
+      return 0;
+  }
+}
+
+void GyroBase::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetAngle());
+  }
+}
+
+void GyroBase::StartLiveWindowMode() {}
+
+void GyroBase::StopLiveWindowMode() {}
+
+std::string GyroBase::GetSmartDashboardType() const { return "Gyro"; }
+
+void GyroBase::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> GyroBase::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/I2C.cpp b/wpilibc/Athena/src/I2C.cpp
new file mode 100644
index 0000000..79767b3
--- /dev/null
+++ b/wpilibc/Athena/src/I2C.cpp
@@ -0,0 +1,199 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "I2C.h"
+#include "HAL/HAL.hpp"
+#include "HAL/Digital.hpp"
+#include "WPIErrors.h"
+
+/**
+ * Constructor.
+ *
+ * @param port The I2C port to which the device is connected.
+ * @param deviceAddress The address of the device on the I2C bus.
+ */
+I2C::I2C(Port port, uint8_t deviceAddress)
+    : m_port(port), m_deviceAddress(deviceAddress) {
+  int32_t status = 0;
+  i2CInitialize(m_port, &status);
+  // wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_I2C, deviceAddress);
+}
+
+/**
+ * Destructor.
+ */
+I2C::~I2C() { i2CClose(m_port); }
+
+/**
+ * Generic transaction.
+ *
+ * This is a lower-level interface to the I2C hardware giving you more control
+ * over each transaction.
+ *
+ * @param dataToSend Buffer of data to send as part of the transaction.
+ * @param sendSize Number of bytes to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize Number of bytes to read from the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Transaction(uint8_t *dataToSend, uint8_t sendSize,
+                      uint8_t *dataReceived, uint8_t receiveSize) {
+  int32_t status = 0;
+  status = i2CTransaction(m_port, m_deviceAddress, dataToSend, sendSize,
+                          dataReceived, receiveSize);
+  // wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return status < 0;
+}
+
+/**
+ * Attempt to address a device on the I2C bus.
+ *
+ * This allows you to figure out if there is a device on the I2C bus that
+ * responds to the address specified in the constructor.
+ *
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::AddressOnly() {
+  int32_t status = 0;
+  status = Transaction(nullptr, 0, nullptr, 0);
+  return status < 0;
+}
+
+/**
+ * Execute a write transaction with the device.
+ *
+ * Write a single byte to a register on a device and wait until the
+ *   transaction is complete.
+ *
+ * @param registerAddress The address of the register on the device to be
+ * written.
+ * @param data The byte to write to the register on the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Write(uint8_t registerAddress, uint8_t data) {
+  uint8_t buffer[2];
+  buffer[0] = registerAddress;
+  buffer[1] = data;
+  int32_t status = 0;
+  status = i2CWrite(m_port, m_deviceAddress, buffer, sizeof(buffer));
+  return status < 0;
+}
+
+/**
+ * Execute a bulk write transaction with the device.
+ *
+ * Write multiple bytes to a device and wait until the
+ *   transaction is complete.
+ *
+ * @param data The data to write to the register on the device.
+ * @param count The number of bytes to be written.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::WriteBulk(uint8_t *data, uint8_t count) {
+  int32_t status = 0;
+  status = i2CWrite(m_port, m_deviceAddress, data, count);
+  return status < 0;
+}
+
+/**
+ * Execute a read transaction with the device.
+ *
+ * Read bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally allowing
+ *   you to read consecutive registers on a device in a single transaction.
+ *
+ * @param registerAddress The register to read first in the transaction.
+ * @param count The number of bytes to read in the transaction.
+ * @param buffer A pointer to the array of bytes to store the data read from the
+ * device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Read(uint8_t registerAddress, uint8_t count, uint8_t *buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  int32_t status = 0;
+  status =
+      Transaction(&registerAddress, sizeof(registerAddress), buffer, count);
+  return status < 0;
+}
+
+/**
+ * Execute a read only transaction with the device.
+ *
+ * Read bytes from a device. This method does not write any data to prompt the
+ * device.
+ *
+ * @param buffer
+ *            A pointer to the array of bytes to store the data read from
+ *            the device.
+ * @param count
+              The number of bytes to read in the transaction.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::ReadOnly(uint8_t count, uint8_t *buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  int32_t status = 0;
+  status = i2CRead(m_port, m_deviceAddress, buffer, count);
+  return status < 0;
+}
+
+/**
+ * Send a broadcast write to all devices on the I2C bus.
+ *
+ * This is not currently implemented!
+ *
+ * @param registerAddress The register to write on all devices on the bus.
+ * @param data The value to write to the devices.
+ */
+[[gnu::warning("I2C::Broadcast() is not implemented.")]]
+void I2C::Broadcast(uint8_t registerAddress, uint8_t data) {}
+
+/**
+ * Verify that a device's registers contain expected values.
+ *
+ * Most devices will have a set of registers that contain a known value that
+ *   can be used to identify them.  This allows an I2C device driver to easily
+ *   verify that the device contains the expected value.
+ *
+ * @pre The device must support and be configured to use register
+ * auto-increment.
+ *
+ * @param registerAddress The base register to start reading from the device.
+ * @param count The size of the field to be verified.
+ * @param expected A buffer containing the values expected from the device.
+ */
+bool I2C::VerifySensor(uint8_t registerAddress, uint8_t count,
+                       const uint8_t *expected) {
+  // TODO: Make use of all 7 read bytes
+  uint8_t deviceData[4];
+  for (uint8_t i = 0, curRegisterAddress = registerAddress; i < count;
+       i += 4, curRegisterAddress += 4) {
+    uint8_t toRead = count - i < 4 ? count - i : 4;
+    // Read the chunk of data.  Return false if the sensor does not respond.
+    if (Read(curRegisterAddress, toRead, deviceData)) return false;
+
+    for (uint8_t j = 0; j < toRead; j++) {
+      if (deviceData[j] != expected[i + j]) return false;
+    }
+  }
+  return true;
+}
diff --git a/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp b/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp
new file mode 100644
index 0000000..2176c80
--- /dev/null
+++ b/wpilibc/Athena/src/Internal/HardwareHLReporting.cpp
@@ -0,0 +1,12 @@
+
+#include "Internal/HardwareHLReporting.h"
+#include "HAL/HAL.hpp"
+
+void HardwareHLReporting::ReportScheduler() {
+  HALReport(HALUsageReporting::kResourceType_Command,
+            HALUsageReporting::kCommand_Scheduler);
+}
+
+void HardwareHLReporting::ReportSmartDashboard() {
+  HALReport(HALUsageReporting::kResourceType_SmartDashboard, 0);
+}
diff --git a/wpilibc/Athena/src/InterruptableSensorBase.cpp b/wpilibc/Athena/src/InterruptableSensorBase.cpp
new file mode 100644
index 0000000..6e66c34
--- /dev/null
+++ b/wpilibc/Athena/src/InterruptableSensorBase.cpp
@@ -0,0 +1,198 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "InterruptableSensorBase.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+std::unique_ptr<Resource> InterruptableSensorBase::m_interrupts =
+    std::make_unique<Resource>(interrupt_kNumSystems);
+
+InterruptableSensorBase::InterruptableSensorBase() {
+}
+
+/**
+* Request one of the 8 interrupts asynchronously on this digital input.
+* Request interrupts in asynchronous mode where the user's interrupt handler
+* will be
+* called when the interrupt fires. Users that want control over the thread
+* priority
+* should use the synchronous method with their own spawned thread.
+* The default is interrupt on rising edges only.
+*/
+void InterruptableSensorBase::RequestInterrupts(
+    InterruptHandlerFunction handler, void *param) {
+  if (StatusIsFatal()) return;
+  uint32_t index = m_interrupts->Allocate("Async Interrupt");
+  if (index == std::numeric_limits<uint32_t>::max()) {
+    CloneError(*m_interrupts);
+    return;
+  }
+  m_interruptIndex = index;
+
+  // Creates a manager too
+  AllocateInterrupts(false);
+
+  int32_t status = 0;
+  requestInterrupts(m_interrupt, GetModuleForRouting(), GetChannelForRouting(),
+                    GetAnalogTriggerForRouting(), &status);
+  SetUpSourceEdge(true, false);
+  attachInterruptHandler(m_interrupt, handler, param, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+* Request one of the 8 interrupts synchronously on this digital input.
+* Request interrupts in synchronous mode where the user program will have to
+* explicitly
+* wait for the interrupt to occur using WaitForInterrupt.
+* The default is interrupt on rising edges only.
+*/
+void InterruptableSensorBase::RequestInterrupts() {
+  if (StatusIsFatal()) return;
+  uint32_t index = m_interrupts->Allocate("Sync Interrupt");
+  if (index == std::numeric_limits<uint32_t>::max()) {
+    CloneError(*m_interrupts);
+    return;
+  }
+  m_interruptIndex = index;
+
+  AllocateInterrupts(true);
+
+  int32_t status = 0;
+  requestInterrupts(m_interrupt, GetModuleForRouting(), GetChannelForRouting(),
+                    GetAnalogTriggerForRouting(), &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  SetUpSourceEdge(true, false);
+}
+
+void InterruptableSensorBase::AllocateInterrupts(bool watcher) {
+  wpi_assert(m_interrupt == nullptr);
+  // Expects the calling leaf class to allocate an interrupt index.
+  int32_t status = 0;
+  m_interrupt = initializeInterrupts(m_interruptIndex, watcher, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Cancel interrupts on this device.
+ * This deallocates all the chipobject structures and disables any interrupts.
+ */
+void InterruptableSensorBase::CancelInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != nullptr);
+  int32_t status = 0;
+  cleanInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  m_interrupt = nullptr;
+  m_interrupts->Free(m_interruptIndex);
+}
+
+/**
+ * In synchronous mode, wait for the defined interrupt to occur. You should
+ * <b>NOT</b> attempt to read the
+ * sensor from another thread while waiting for an interrupt. This is not
+ * threadsafe, and can cause
+ * memory corruption
+ * @param timeout Timeout in seconds
+ * @param ignorePrevious If true, ignore interrupts that happened before
+ * WaitForInterrupt was called.
+ * @return What interrupts fired
+ */
+InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
+    float timeout, bool ignorePrevious) {
+  if (StatusIsFatal()) return InterruptableSensorBase::kTimeout;
+  wpi_assert(m_interrupt != nullptr);
+  int32_t status = 0;
+  uint32_t result;
+
+  result = waitForInterrupt(m_interrupt, timeout, ignorePrevious, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  return static_cast<WaitResult>(result);
+}
+
+/**
+ * Enable interrupts to occur on this input.
+ * Interrupts are disabled when the RequestInterrupt call is made. This gives
+ * time to do the
+ * setup of the other options before starting to field interrupts.
+ */
+void InterruptableSensorBase::EnableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != nullptr);
+  int32_t status = 0;
+  enableInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Disable Interrupts without without deallocating structures.
+ */
+void InterruptableSensorBase::DisableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != nullptr);
+  int32_t status = 0;
+  disableInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Return the timestamp for the rising interrupt that occurred most recently.
+ * This is in the same time domain as GetClock().
+ * The rising-edge interrupt should be enabled with
+ * {@link #DigitalInput.SetUpSourceEdge}
+ * @return Timestamp in seconds since boot.
+ */
+double InterruptableSensorBase::ReadRisingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != nullptr);
+  int32_t status = 0;
+  double timestamp = readRisingTimestamp(m_interrupt, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return timestamp;
+}
+
+/**
+ * Return the timestamp for the falling interrupt that occurred most recently.
+ * This is in the same time domain as GetClock().
+ * The falling-edge interrupt should be enabled with
+ * {@link #DigitalInput.SetUpSourceEdge}
+ * @return Timestamp in seconds since boot.
+*/
+double InterruptableSensorBase::ReadFallingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != nullptr);
+  int32_t status = 0;
+  double timestamp = readFallingTimestamp(m_interrupt, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return timestamp;
+}
+
+/**
+ * Set which edge to trigger interrupts on
+ *
+ * @param risingEdge
+ *            true to interrupt on rising edge
+ * @param fallingEdge
+ *            true to interrupt on falling edge
+ */
+void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,
+                                              bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_interrupt == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "You must call RequestInterrupts before SetUpSourceEdge");
+    return;
+  }
+  if (m_interrupt != nullptr) {
+    int32_t status = 0;
+    setInterruptUpSourceEdge(m_interrupt, risingEdge, fallingEdge, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
diff --git a/wpilibc/Athena/src/IterativeRobot.cpp b/wpilibc/Athena/src/IterativeRobot.cpp
new file mode 100644
index 0000000..fa1d2ba
--- /dev/null
+++ b/wpilibc/Athena/src/IterativeRobot.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "IterativeRobot.h"
+
+#include "DriverStation.h"
+#include "HAL/HAL.hpp"
+#include "SmartDashboard/SmartDashboard.h"
+#include "LiveWindow/LiveWindow.h"
+#include "networktables/NetworkTable.h"
+
+constexpr double IterativeRobot::kDefaultPeriod;
+
+/**
+ * Provide an alternate "main loop" via StartCompetition().
+ *
+ * This specific StartCompetition() implements "main loop" behaviour synced with
+ * the DS packets
+ */
+void IterativeRobot::StartCompetition() {
+  HALReport(HALUsageReporting::kResourceType_Framework,
+            HALUsageReporting::kFramework_Iterative);
+
+  LiveWindow *lw = LiveWindow::GetInstance();
+  // first and one-time initialization
+  SmartDashboard::init();
+  NetworkTable::GetTable("LiveWindow")
+      ->GetSubTable("~STATUS~")
+      ->PutBoolean("LW Enabled", false);
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HALNetworkCommunicationObserveUserProgramStarting();
+
+  // loop forever, calling the appropriate mode-dependent function
+  lw->SetEnabled(false);
+  while (true) {
+    // Call the appropriate function depending upon the current robot mode
+    if (IsDisabled()) {
+      // call DisabledInit() if we are now just entering disabled mode from
+      // either a different mode or from power-on
+      if (!m_disabledInitialized) {
+        lw->SetEnabled(false);
+        DisabledInit();
+        m_disabledInitialized = true;
+        // reset the initialization flags for the other modes
+        m_autonomousInitialized = false;
+        m_teleopInitialized = false;
+        m_testInitialized = false;
+      }
+      HALNetworkCommunicationObserveUserProgramDisabled();
+      DisabledPeriodic();
+    } else if (IsAutonomous()) {
+      // call AutonomousInit() if we are now just entering autonomous mode from
+      // either a different mode or from power-on
+      if (!m_autonomousInitialized) {
+        lw->SetEnabled(false);
+        AutonomousInit();
+        m_autonomousInitialized = true;
+        // reset the initialization flags for the other modes
+        m_disabledInitialized = false;
+        m_teleopInitialized = false;
+        m_testInitialized = false;
+      }
+      HALNetworkCommunicationObserveUserProgramAutonomous();
+      AutonomousPeriodic();
+    } else if (IsTest()) {
+      // call TestInit() if we are now just entering test mode from
+      // either a different mode or from power-on
+      if (!m_testInitialized) {
+        lw->SetEnabled(true);
+        TestInit();
+        m_testInitialized = true;
+        // reset the initialization flags for the other modes
+        m_disabledInitialized = false;
+        m_autonomousInitialized = false;
+        m_teleopInitialized = false;
+      }
+      HALNetworkCommunicationObserveUserProgramTest();
+      TestPeriodic();
+    } else {
+      // call TeleopInit() if we are now just entering teleop mode from
+      // either a different mode or from power-on
+      if (!m_teleopInitialized) {
+        lw->SetEnabled(false);
+        TeleopInit();
+        m_teleopInitialized = true;
+        // reset the initialization flags for the other modes
+        m_disabledInitialized = false;
+        m_autonomousInitialized = false;
+        m_testInitialized = false;
+        Scheduler::GetInstance()->SetEnabled(true);
+      }
+      HALNetworkCommunicationObserveUserProgramTeleop();
+      TeleopPeriodic();
+    }
+    // wait for driver station data so the loop doesn't hog the CPU
+    m_ds.WaitForData();
+  }
+}
+
+/**
+ * Robot-wide initialization code should go here.
+ *
+ * Users should override this method for default Robot-wide initialization which
+ * will be called when the robot is first powered on. It will be called exactly
+ * one time.
+ *
+ * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+ * indicators will be off until RobotInit() exits. Code in RobotInit() that
+ * waits for enable will cause the robot to never indicate that the code is
+ * ready, causing the robot to be bypassed in a match.
+ */
+void IterativeRobot::RobotInit() {
+  printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for disabled mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time
+ * the robot enters disabled mode.
+ */
+void IterativeRobot::DisabledInit() {
+  printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for autonomous mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time
+ * the robot enters autonomous mode.
+ */
+void IterativeRobot::AutonomousInit() {
+  printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for teleop mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time
+ * the robot enters teleop mode.
+ */
+void IterativeRobot::TeleopInit() {
+  printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for test mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time
+ * the robot enters test mode.
+ */
+void IterativeRobot::TestInit() {
+  printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Periodic code for disabled mode should go here.
+ *
+ * Users should override this method for code which will be called periodically
+ * at a regular
+ * rate while the robot is in disabled mode.
+ */
+void IterativeRobot::DisabledPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+  delayTicks(1);
+}
+
+/**
+ * Periodic code for autonomous mode should go here.
+ *
+ * Users should override this method for code which will be called periodically
+ * at a regular
+ * rate while the robot is in autonomous mode.
+ */
+void IterativeRobot::AutonomousPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+  delayTicks(1);
+}
+
+/**
+ * Periodic code for teleop mode should go here.
+ *
+ * Users should override this method for code which will be called periodically
+ * at a regular
+ * rate while the robot is in teleop mode.
+ */
+void IterativeRobot::TeleopPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+  delayTicks(1);
+}
+
+/**
+ * Periodic code for test mode should go here.
+ *
+ * Users should override this method for code which will be called periodically
+ * at a regular
+ * rate while the robot is in test mode.
+ */
+void IterativeRobot::TestPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+  delayTicks(1);
+}
diff --git a/wpilibc/Athena/src/Jaguar.cpp b/wpilibc/Athena/src/Jaguar.cpp
new file mode 100644
index 0000000..ce61d36
--- /dev/null
+++ b/wpilibc/Athena/src/Jaguar.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Jaguar.h"
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Constructor for a Jaguar connected via PWM
+ * @param channel The PWM channel that the Jaguar is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) {
+  /**
+   * Input profile defined by Luminary Micro.
+   *
+   * Full reverse ranges from 0.671325ms to 0.6972211ms
+   * Proportional reverse ranges from 0.6972211ms to 1.4482078ms
+   * Neutral ranges from 1.4482078ms to 1.5517922ms
+   * Proportional forward ranges from 1.5517922ms to 2.3027789ms
+   * Full forward ranges from 2.3027789ms to 2.328675ms
+   */
+  SetBounds(2.31, 1.55, 1.507, 1.454, .697);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  HALReport(HALUsageReporting::kResourceType_Jaguar, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void Jaguar::Set(float speed, uint8_t syncGroup) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float Jaguar::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Jaguar::Disable() { SetRaw(kPwmDisabled); }
+
+/**
+* Common interface for inverting direction of a speed controller.
+* @param isInverted The state of inversion, true is inverted.
+*/
+void Jaguar::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool Jaguar::GetInverted() const { return m_isInverted; }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void Jaguar::PIDWrite(float output) { Set(output); }
diff --git a/wpilibc/Athena/src/Joystick.cpp b/wpilibc/Athena/src/Joystick.cpp
new file mode 100644
index 0000000..388832c
--- /dev/null
+++ b/wpilibc/Athena/src/Joystick.cpp
@@ -0,0 +1,376 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Joystick.h"
+#include "DriverStation.h"
+#include "WPIErrors.h"
+#include <math.h>
+#include <string.h>
+
+const uint32_t Joystick::kDefaultXAxis;
+const uint32_t Joystick::kDefaultYAxis;
+const uint32_t Joystick::kDefaultZAxis;
+const uint32_t Joystick::kDefaultTwistAxis;
+const uint32_t Joystick::kDefaultThrottleAxis;
+const uint32_t Joystick::kDefaultTriggerButton;
+const uint32_t Joystick::kDefaultTopButton;
+static Joystick *joysticks[DriverStation::kJoystickPorts];
+static bool joySticksInitialized = false;
+
+/**
+ * Construct an instance of a joystick.
+ * The joystick index is the usb port on the drivers station.
+ *
+ * @param port The port on the driver station that the joystick is plugged into
+ * (0-5).
+ */
+Joystick::Joystick(uint32_t port)
+    : Joystick(port, kNumAxisTypes, kNumButtonTypes) {
+  m_axes[kXAxis] = kDefaultXAxis;
+  m_axes[kYAxis] = kDefaultYAxis;
+  m_axes[kZAxis] = kDefaultZAxis;
+  m_axes[kTwistAxis] = kDefaultTwistAxis;
+  m_axes[kThrottleAxis] = kDefaultThrottleAxis;
+
+  m_buttons[kTriggerButton] = kDefaultTriggerButton;
+  m_buttons[kTopButton] = kDefaultTopButton;
+
+  HALReport(HALUsageReporting::kResourceType_Joystick, port);
+}
+
+/**
+ * Version of the constructor to be called by sub-classes.
+ *
+ * This constructor allows the subclass to configure the number of constants
+ * for axes and buttons.
+ *
+ * @param port The port on the driver station that the joystick is plugged into.
+ * @param numAxisTypes The number of axis types in the enum.
+ * @param numButtonTypes The number of button types in the enum.
+ */
+Joystick::Joystick(uint32_t port, uint32_t numAxisTypes,
+                   uint32_t numButtonTypes)
+    : m_ds(DriverStation::GetInstance()),
+      m_port(port),
+      m_axes(numAxisTypes),
+      m_buttons(numButtonTypes) {
+  if (!joySticksInitialized) {
+    for (auto& joystick : joysticks) joystick = nullptr;
+    joySticksInitialized = true;
+  }
+  if (m_port >= DriverStation::kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  } else {
+    joysticks[m_port] = this;
+  }
+}
+
+Joystick *Joystick::GetStickForPort(uint32_t port) {
+  Joystick *stick = joysticks[port];
+  if (stick == nullptr) {
+    stick = new Joystick(port);
+    joysticks[port] = stick;
+  }
+  return stick;
+}
+
+/**
+ * Get the X value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ * @param hand This parameter is ignored for the Joystick class and is only here
+ * to complete the GenericHID interface.
+ */
+float Joystick::GetX(JoystickHand hand) const {
+  return GetRawAxis(m_axes[kXAxis]);
+}
+
+/**
+ * Get the Y value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ * @param hand This parameter is ignored for the Joystick class and is only here
+ * to complete the GenericHID interface.
+ */
+float Joystick::GetY(JoystickHand hand) const {
+  return GetRawAxis(m_axes[kYAxis]);
+}
+
+/**
+ * Get the Z value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetZ() const { return GetRawAxis(m_axes[kZAxis]); }
+
+/**
+ * Get the twist value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); }
+
+/**
+ * Get the throttle value of the current joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetThrottle() const {
+  return GetRawAxis(m_axes[kThrottleAxis]);
+}
+
+/**
+ * Get the value of the axis.
+ *
+ * @param axis The axis to read, starting at 0.
+ * @return The value of the axis.
+ */
+float Joystick::GetRawAxis(uint32_t axis) const {
+  return m_ds.GetStickAxis(m_port, axis);
+}
+
+/**
+ * For the current joystick, return the axis determined by the argument.
+ *
+ * This is for cases where the joystick axis is returned programatically,
+ * otherwise one of the
+ * previous functions would be preferable (for example GetX()).
+ *
+ * @param axis The axis to read.
+ * @return The value of the axis.
+ */
+float Joystick::GetAxis(AxisType axis) const {
+  switch (axis) {
+    case kXAxis:
+      return this->GetX();
+    case kYAxis:
+      return this->GetY();
+    case kZAxis:
+      return this->GetZ();
+    case kTwistAxis:
+      return this->GetTwist();
+    case kThrottleAxis:
+      return this->GetThrottle();
+    default:
+      wpi_setWPIError(BadJoystickAxis);
+      return 0.0;
+  }
+}
+
+/**
+ * Read the state of the trigger on the joystick.
+ *
+ * Look up which button has been assigned to the trigger and read its state.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only here
+ * to complete the GenericHID interface.
+ * @return The state of the trigger.
+ */
+bool Joystick::GetTrigger(JoystickHand hand) const {
+  return GetRawButton(m_buttons[kTriggerButton]);
+}
+
+/**
+ * Read the state of the top button on the joystick.
+ *
+ * Look up which button has been assigned to the top and read its state.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only here
+ * to complete the GenericHID interface.
+ * @return The state of the top button.
+ */
+bool Joystick::GetTop(JoystickHand hand) const {
+  return GetRawButton(m_buttons[kTopButton]);
+}
+
+/**
+ * This is not supported for the Joystick.
+ * This method is only here to complete the GenericHID interface.
+ */
+bool Joystick::GetBumper(JoystickHand hand) const {
+  // Joysticks don't have bumpers.
+  return false;
+}
+
+/**
+ * Get the button value (starting at button 1)
+ *
+ * The buttons are returned in a single 16 bit value with one bit representing
+ * the state
+ * of each button. The appropriate button is returned as a boolean value.
+ *
+ * @param button The button number to be read (starting at 1)
+ * @return The state of the button.
+ **/
+bool Joystick::GetRawButton(uint32_t button) const {
+  return m_ds.GetStickButton(m_port, button);
+}
+
+/**
+ * Get the state of a POV on the joystick.
+ *
+ * @param pov The index of the POV to read (starting at 0)
+ * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+ */
+int Joystick::GetPOV(uint32_t pov) const {
+  return m_ds.GetStickPOV(m_port, pov);
+}
+
+/**
+ * Get buttons based on an enumerated type.
+ *
+ * The button type will be looked up in the list of buttons and then read.
+ *
+ * @param button The type of button to read.
+ * @return The state of the button.
+ */
+bool Joystick::GetButton(ButtonType button) const {
+  switch (button) {
+    case kTriggerButton:
+      return GetTrigger();
+    case kTopButton:
+      return GetTop();
+    default:
+      return false;
+  }
+}
+
+/**
+ * Get the number of axis for a joystick
+ *
+ * @return the number of axis for the current joystick
+ */
+int Joystick::GetAxisCount() const { return m_ds.GetStickAxisCount(m_port); }
+
+/**
+ * Get the value of isXbox for the joystick.
+ *
+ * @return A boolean that is true if the joystick is an xbox controller.
+ */
+bool Joystick::GetIsXbox() const { return m_ds.GetJoystickIsXbox(m_port); }
+
+/**
+ * Get the HID type of the controller.
+ *
+ * @return the HID type of the controller.
+ */
+Joystick::HIDType Joystick::GetType() const {
+  return static_cast<HIDType>(m_ds.GetJoystickType(m_port));
+}
+
+/**
+ * Get the name of the joystick.
+ *
+ * @return the name of the controller.
+ */
+std::string Joystick::GetName() const { return m_ds.GetJoystickName(m_port); }
+
+// int Joystick::GetAxisType(uint8_t axis) const
+//{
+//	return m_ds.GetJoystickAxisType(m_port, axis);
+//}
+
+/**
+  * Get the number of axis for a joystick
+  *
+* @return the number of buttons on the current joystick
+ */
+int Joystick::GetButtonCount() const {
+  return m_ds.GetStickButtonCount(m_port);
+}
+
+/**
+ * Get the number of axis for a joystick
+ *
+ * @return then umber of POVs for the current joystick
+ */
+int Joystick::GetPOVCount() const { return m_ds.GetStickPOVCount(m_port); }
+
+/**
+ * Get the channel currently associated with the specified axis.
+ *
+ * @param axis The axis to look up the channel for.
+ * @return The channel fr the axis.
+ */
+uint32_t Joystick::GetAxisChannel(AxisType axis) const { return m_axes[axis]; }
+
+/**
+ * Set the channel associated with a specified axis.
+ *
+ * @param axis The axis to set the channel for.
+ * @param channel The channel to set the axis to.
+ */
+void Joystick::SetAxisChannel(AxisType axis, uint32_t channel) {
+  m_axes[axis] = channel;
+}
+
+/**
+ * Get the magnitude of the direction vector formed by the joystick's
+ * current position relative to its origin
+ *
+ * @return The magnitude of the direction vector
+ */
+float Joystick::GetMagnitude() const {
+  return sqrt(pow(GetX(), 2) + pow(GetY(), 2));
+}
+
+/**
+ * Get the direction of the vector formed by the joystick and its origin
+ * in radians
+ *
+ * @return The direction of the vector in radians
+ */
+float Joystick::GetDirectionRadians() const { return atan2(GetX(), -GetY()); }
+
+/**
+ * Get the direction of the vector formed by the joystick and its origin
+ * in degrees
+ *
+ * uses acos(-1) to represent Pi due to absence of readily accessible Pi
+ * constant in C++
+ *
+ * @return The direction of the vector in degrees
+ */
+float Joystick::GetDirectionDegrees() const {
+  return (180 / acos(-1)) * GetDirectionRadians();
+}
+
+/**
+ * Set the rumble output for the joystick. The DS currently supports 2 rumble
+ * values,
+ * left rumble and right rumble
+ * @param type Which rumble value to set
+ * @param value The normalized value (0 to 1) to set the rumble to
+ */
+void Joystick::SetRumble(RumbleType type, float value) {
+  if (value < 0)
+    value = 0;
+  else if (value > 1)
+    value = 1;
+  if (type == kLeftRumble)
+    m_leftRumble = value * 65535;
+  else
+    m_rightRumble = value * 65535;
+  HALSetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+/**
+ * Set a single HID output value for the joystick.
+ * @param outputNumber The index of the output to set (1-32)
+ * @param value The value to set the output to
+ */
+
+void Joystick::SetOutput(uint8_t outputNumber, bool value) {
+  m_outputs =
+      (m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1));
+
+  HALSetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+/**
+ * Set all HID output values for the joystick.
+ * @param value The 32 bit output value (1 bit for each output)
+ */
+void Joystick::SetOutputs(uint32_t value) {
+  m_outputs = value;
+  HALSetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
diff --git a/wpilibc/Athena/src/MotorSafetyHelper.cpp b/wpilibc/Athena/src/MotorSafetyHelper.cpp
new file mode 100644
index 0000000..60bba30
--- /dev/null
+++ b/wpilibc/Athena/src/MotorSafetyHelper.cpp
@@ -0,0 +1,139 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "MotorSafetyHelper.h"
+
+#include "DriverStation.h"
+#include "MotorSafety.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+#include <stdio.h>
+#include <sstream>
+
+std::set<MotorSafetyHelper*> MotorSafetyHelper::m_helperList;
+priority_recursive_mutex MotorSafetyHelper::m_listMutex;
+
+/**
+ * The constructor for a MotorSafetyHelper object.
+ * The helper object is constructed for every object that wants to implement the
+ * Motor
+ * Safety protocol. The helper object has the code to actually do the timing and
+ * call the
+ * motors Stop() method when the timeout expires. The motor object is expected
+ * to call the
+ * Feed() method whenever the motors value is updated.
+ * @param safeObject a pointer to the motor object implementing MotorSafety.
+ * This is used
+ * to call the Stop() method on the motor.
+ */
+MotorSafetyHelper::MotorSafetyHelper(MotorSafety *safeObject)
+    : m_safeObject(safeObject) {
+  m_enabled = false;
+  m_expiration = DEFAULT_SAFETY_EXPIRATION;
+  m_stopTime = Timer::GetFPGATimestamp();
+
+  std::lock_guard<priority_recursive_mutex> sync(m_listMutex);
+  m_helperList.insert(this);
+}
+
+MotorSafetyHelper::~MotorSafetyHelper() {
+  std::lock_guard<priority_recursive_mutex> sync(m_listMutex);
+  m_helperList.erase(this);
+}
+
+/**
+ * Feed the motor safety object.
+ * Resets the timer on this object that is used to do the timeouts.
+ */
+void MotorSafetyHelper::Feed() {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
+}
+
+/**
+ * Set the expiration time for the corresponding motor safety object.
+ * @param expirationTime The timeout value in seconds.
+ */
+void MotorSafetyHelper::SetExpiration(float expirationTime) {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  m_expiration = expirationTime;
+}
+
+/**
+ * Retrieve the timeout value for the corresponding motor safety object.
+ * @return the timeout value in seconds.
+ */
+float MotorSafetyHelper::GetExpiration() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  return m_expiration;
+}
+
+/**
+ * Determine if the motor is still operating or has timed out.
+ * @return a true value if the motor is still operating normally and hasn't
+ * timed out.
+ */
+bool MotorSafetyHelper::IsAlive() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
+}
+
+/**
+ * Check if this motor has exceeded its timeout.
+ * This method is called periodically to determine if this motor has exceeded
+ * its timeout
+ * value. If it has, the stop method is called, and the motor is shut down until
+ * its value is
+ * updated again.
+ */
+void MotorSafetyHelper::Check() {
+  DriverStation &ds = DriverStation::GetInstance();
+  if (!m_enabled || ds.IsDisabled() || ds.IsTest()) return;
+
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  if (m_stopTime < Timer::GetFPGATimestamp()) {
+    std::ostringstream desc;
+    m_safeObject->GetDescription(desc);
+    desc <<  "... Output not updated often enough.";
+    wpi_setWPIErrorWithContext(Timeout, desc.str().c_str());
+    m_safeObject->StopMotor();
+  }
+}
+
+/**
+ * Enable/disable motor safety for this device
+ * Turn on and off the motor safety option for this PWM object.
+ * @param enabled True if motor safety is enforced for this object
+ */
+void MotorSafetyHelper::SetSafetyEnabled(bool enabled) {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  m_enabled = enabled;
+}
+
+/**
+ * Return the state of the motor safety enabled flag
+ * Return if the motor safety is currently enabled for this devicce.
+ * @return True if motor safety is enforced for this device
+ */
+bool MotorSafetyHelper::IsSafetyEnabled() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  return m_enabled;
+}
+
+/**
+ * Check the motors to see if any have timed out.
+ * This static  method is called periodically to poll all the motors and stop
+ * any that have
+ * timed out.
+ */
+void MotorSafetyHelper::CheckMotors() {
+  std::lock_guard<priority_recursive_mutex> sync(m_listMutex);
+  for (auto elem : m_helperList) {
+    elem->Check();
+  }
+}
diff --git a/wpilibc/Athena/src/Notifier.cpp b/wpilibc/Athena/src/Notifier.cpp
new file mode 100644
index 0000000..fc3059c
--- /dev/null
+++ b/wpilibc/Athena/src/Notifier.cpp
@@ -0,0 +1,263 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Notifier.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include "HAL/HAL.hpp"
+
+Notifier *Notifier::timerQueueHead = nullptr;
+priority_recursive_mutex Notifier::queueMutex;
+priority_mutex Notifier::halMutex;
+void *Notifier::m_notifier = nullptr;
+std::atomic<int> Notifier::refcount{0};
+
+/**
+ * Create a Notifier for timer event notification.
+ * @param handler The handler is called at the notification time which is set
+ * using StartSingle or StartPeriodic.
+ */
+Notifier::Notifier(TimerEventHandler handler, void *param) {
+  if (handler == nullptr)
+    wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
+  m_handler = handler;
+  m_param = param;
+  // do the first time intialization of static variables
+  if (refcount.fetch_add(1) == 0) {
+    int32_t status = 0;
+    {
+      std::lock_guard<priority_mutex> sync(halMutex);
+      if (!m_notifier)
+        m_notifier = initializeNotifier(ProcessQueue, nullptr, &status);
+    }
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+}
+
+/**
+ * Free the resources for a timer event.
+ * All resources will be freed and the timer event will be removed from the
+ * queue if necessary.
+ */
+Notifier::~Notifier() {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+    DeleteFromQueue();
+  }
+
+  // Delete the static variables when the last one is going away
+  if (refcount.fetch_sub(1) == 1) {
+    int32_t status = 0;
+    {
+      std::lock_guard<priority_mutex> sync(halMutex);
+      if (m_notifier) {
+        cleanNotifier(m_notifier, &status);
+        m_notifier = nullptr;
+      }
+    }
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  }
+
+  // Acquire the mutex; this makes certain that the handler is
+  // not being executed by the interrupt manager.
+  std::lock_guard<priority_mutex> lock(m_handlerMutex);
+}
+
+/**
+ * Update the alarm hardware to reflect the current first element in the queue.
+ * Compute the time the next alarm should occur based on the current time and
+ * the
+ * period for the first element in the timer queue.
+ * WARNING: this method does not do synchronization! It must be called from
+ * somewhere
+ * that is taking care of synchronizing access to the queue.
+ */
+void Notifier::UpdateAlarm() {
+  if (timerQueueHead != nullptr) {
+    int32_t status = 0;
+    // This locking is necessary in order to avoid two things:
+    //  1) Race condition issues with calling cleanNotifer() and
+    //     updateNotifierAlarm() at the same time.
+    //  2) Avoid deadlock by making it so that this won't block waiting
+    //     for the mutex to unlock.
+    // Checking refcount as well is unnecessary, but will not hurt.
+    if (halMutex.try_lock() && refcount != 0) {
+      if (m_notifier)
+        updateNotifierAlarm(m_notifier,
+                            (uint32_t)(timerQueueHead->m_expirationTime * 1e6),
+                            &status);
+      halMutex.unlock();
+    }
+    wpi_setStaticErrorWithContext(timerQueueHead, status,
+                                  getHALErrorMessage(status));
+  }
+}
+
+/**
+ * ProcessQueue is called whenever there is a timer interrupt.
+ * We need to wake up and process the current top item in the timer queue as
+ * long
+ * as its scheduled time is after the current time. Then the item is removed or
+ * rescheduled (repetitive events) in the queue.
+ */
+void Notifier::ProcessQueue(uint32_t currentTimeInt, void *params) {
+  Notifier *current;
+  while (true)  // keep processing past events until no more
+  {
+    {
+      std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+      double currentTime = currentTimeInt * 1.0e-6;
+      current = timerQueueHead;
+      if (current == nullptr || current->m_expirationTime > currentTime) {
+        break;  // no more timer events to process
+      }
+      // need to process this entry
+      timerQueueHead = current->m_nextEvent;
+      if (current->m_periodic) {
+        // if periodic, requeue the event
+        // compute when to put into queue
+        current->InsertInQueue(true);
+      } else {
+        // not periodic; removed from queue
+        current->m_queued = false;
+      }
+      // Take handler mutex while holding queue mutex to make sure
+      //  the handler will execute to completion in case we are being deleted.
+      current->m_handlerMutex.lock();
+    }
+
+    current->m_handler(current->m_param);  // call the event handler
+    current->m_handlerMutex.unlock();
+  }
+  // reschedule the first item in the queue
+  std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+  UpdateAlarm();
+}
+
+/**
+ * Insert this Notifier into the timer queue in right place.
+ * WARNING: this method does not do synchronization! It must be called from
+ * somewhere
+ * that is taking care of synchronizing access to the queue.
+ * @param reschedule If false, the scheduled alarm is based on the current time
+ * and UpdateAlarm
+ * method is called which will enable the alarm if necessary.
+ * If true, update the time by adding the period (no drift) when rescheduled
+ * periodic from ProcessQueue.
+ * This ensures that the public methods only update the queue after finishing
+ * inserting.
+ */
+void Notifier::InsertInQueue(bool reschedule) {
+  if (reschedule) {
+    m_expirationTime += m_period;
+  } else {
+    m_expirationTime = GetClock() + m_period;
+  }
+  if (m_expirationTime > Timer::kRolloverTime) {
+    m_expirationTime -= Timer::kRolloverTime;
+  }
+  if (timerQueueHead == nullptr ||
+      timerQueueHead->m_expirationTime >= this->m_expirationTime) {
+    // the queue is empty or greater than the new entry
+    // the new entry becomes the first element
+    this->m_nextEvent = timerQueueHead;
+    timerQueueHead = this;
+    if (!reschedule) {
+      // since the first element changed, update alarm, unless we already plan
+      // to
+      UpdateAlarm();
+    }
+  } else {
+    for (Notifier **npp = &(timerQueueHead->m_nextEvent);;
+         npp = &(*npp)->m_nextEvent) {
+      Notifier *n = *npp;
+      if (n == nullptr || n->m_expirationTime > this->m_expirationTime) {
+        *npp = this;
+        this->m_nextEvent = n;
+        break;
+      }
+    }
+  }
+  m_queued = true;
+}
+
+/**
+ * Delete this Notifier from the timer queue.
+ * WARNING: this method does not do synchronization! It must be called from
+ * somewhere
+ * that is taking care of synchronizing access to the queue.
+ * Remove this Notifier from the timer queue and adjust the next interrupt time
+ * to reflect
+ * the current top of the queue.
+ */
+void Notifier::DeleteFromQueue() {
+  if (m_queued) {
+    m_queued = false;
+    wpi_assert(timerQueueHead != nullptr);
+    if (timerQueueHead == this) {
+      // remove the first item in the list - update the alarm
+      timerQueueHead = this->m_nextEvent;
+      UpdateAlarm();
+    } else {
+      for (Notifier *n = timerQueueHead; n != nullptr; n = n->m_nextEvent) {
+        if (n->m_nextEvent == this) {
+          // this element is the next element from *n from the queue
+          n->m_nextEvent = this->m_nextEvent;  // point around this one
+        }
+      }
+    }
+  }
+}
+
+/**
+ * Register for single event notification.
+ * A timer event is queued for a single event after the specified delay.
+ * @param delay Seconds to wait before the handler is called.
+ */
+void Notifier::StartSingle(double delay) {
+  std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+  m_periodic = false;
+  m_period = delay;
+  DeleteFromQueue();
+  InsertInQueue(false);
+}
+
+/**
+ * Register for periodic event notification.
+ * A timer event is queued for periodic event notification. Each time the
+ * interrupt
+ * occurs, the event will be immediately requeued for the same time interval.
+ * @param period Period in seconds to call the handler starting one period after
+ * the call to this method.
+ */
+void Notifier::StartPeriodic(double period) {
+  std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+  m_periodic = true;
+  m_period = period;
+  DeleteFromQueue();
+  InsertInQueue(false);
+}
+
+/**
+ * Stop timer events from occuring.
+ * Stop any repeating timer events from occuring. This will also remove any
+ * single
+ * notification events from the queue.
+ * If a timer-based call to the registered handler is in progress, this function
+ * will
+ * block until the handler call is complete.
+ */
+void Notifier::Stop() {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(queueMutex);
+    DeleteFromQueue();
+  }
+  // Wait for a currently executing handler to complete before returning from
+  // Stop()
+  std::lock_guard<priority_mutex> sync(m_handlerMutex);
+}
diff --git a/wpilibc/Athena/src/PIDController.cpp b/wpilibc/Athena/src/PIDController.cpp
new file mode 100644
index 0000000..fdbbb5a
--- /dev/null
+++ b/wpilibc/Athena/src/PIDController.cpp
@@ -0,0 +1,582 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "PIDController.h"
+#include "Notifier.h"
+#include "PIDSource.h"
+#include "PIDOutput.h"
+#include <math.h>
+#include <vector>
+#include "HAL/HAL.hpp"
+
+static const std::string kP = "p";
+static const std::string kI = "i";
+static const std::string kD = "d";
+static const std::string kF = "f";
+static const std::string kSetpoint = "setpoint";
+static const std::string kEnabled = "enabled";
+
+/**
+ * Allocate a PID object with the given constants for P, I, D
+ * @param Kp the proportional coefficient
+ * @param Ki the integral coefficient
+ * @param Kd the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ * @param period the loop time for doing calculations. This particularly effects
+ * calculations of the
+ * integral and differental terms. The default is 50ms.
+ */
+PIDController::PIDController(float Kp, float Ki, float Kd, PIDSource *source,
+                             PIDOutput *output, float period) {
+  Initialize(Kp, Ki, Kd, 0.0f, source, output, period);
+}
+
+/**
+ * Allocate a PID object with the given constants for P, I, D
+ * @param Kp the proportional coefficient
+ * @param Ki the integral coefficient
+ * @param Kd the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ * @param period the loop time for doing calculations. This particularly effects
+ * calculations of the
+ * integral and differental terms. The default is 50ms.
+ */
+PIDController::PIDController(float Kp, float Ki, float Kd, float Kf,
+                             PIDSource *source, PIDOutput *output, float period) {
+  Initialize(Kp, Ki, Kd, Kf, source, output, period);
+}
+
+void PIDController::Initialize(float Kp, float Ki, float Kd, float Kf,
+                               PIDSource *source, PIDOutput *output,
+                               float period) {
+  m_controlLoop = std::make_unique<Notifier>(PIDController::CallCalculate, this);
+
+  m_P = Kp;
+  m_I = Ki;
+  m_D = Kd;
+  m_F = Kf;
+
+  m_pidInput = source;
+  m_pidOutput = output;
+  m_period = period;
+
+  m_controlLoop->StartPeriodic(m_period);
+
+  static int32_t instances = 0;
+  instances++;
+  HALReport(HALUsageReporting::kResourceType_PIDController, instances);
+}
+
+PIDController::~PIDController() {
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Call the Calculate method as a non-static method. This avoids having to
+ * prepend
+ * all local variables in that method with the class pointer. This way the
+ * "this"
+ * pointer will be set up and class variables can be called more easily.
+ * This method is static and called by the Notifier class.
+ * @param controller the address of the PID controller object to use in the
+ * background loop
+ */
+void PIDController::CallCalculate(void *controller) {
+  PIDController *control = (PIDController *)controller;
+  control->Calculate();
+}
+
+/**
+ * Read the input, calculate the output accordingly, and write to the output.
+ * This should only be called by the Notifier indirectly through CallCalculate
+ * and is created during initialization.
+ */
+void PIDController::Calculate() {
+  bool enabled;
+  PIDSource *pidInput;
+  PIDOutput *pidOutput;
+
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    pidInput = m_pidInput;
+    pidOutput = m_pidOutput;
+    enabled = m_enabled;
+  }
+
+  if (pidInput == nullptr) return;
+  if (pidOutput == nullptr) return;
+
+  if (enabled) {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    float input = pidInput->PIDGet();
+    float result;
+    PIDOutput *pidOutput;
+
+    m_error = m_setpoint - input;
+    if (m_continuous) {
+      if (fabs(m_error) > (m_maximumInput - m_minimumInput) / 2) {
+        if (m_error > 0) {
+          m_error = m_error - m_maximumInput + m_minimumInput;
+        } else {
+          m_error = m_error + m_maximumInput - m_minimumInput;
+        }
+      }
+    }
+
+    if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+      if (m_P != 0) {
+        double potentialPGain = (m_totalError + m_error) * m_P;
+        if (potentialPGain < m_maximumOutput) {
+          if (potentialPGain > m_minimumOutput)
+            m_totalError += m_error;
+          else
+            m_totalError = m_minimumOutput / m_P;
+        } else {
+          m_totalError = m_maximumOutput / m_P;
+        }
+      }
+
+      m_result = m_D * m_error + m_P * m_totalError + m_setpoint * m_F;
+    }
+    else {
+      if (m_I != 0) {
+        double potentialIGain = (m_totalError + m_error) * m_I;
+        if (potentialIGain < m_maximumOutput) {
+          if (potentialIGain > m_minimumOutput)
+            m_totalError += m_error;
+          else
+            m_totalError = m_minimumOutput / m_I;
+        } else {
+          m_totalError = m_maximumOutput / m_I;
+        }
+      }
+
+      m_result = m_P * m_error + m_I * m_totalError +
+                 m_D * (m_prevInput - input) + m_setpoint * m_F;
+    }
+    m_prevInput = input;
+
+    if (m_result > m_maximumOutput)
+      m_result = m_maximumOutput;
+    else if (m_result < m_minimumOutput)
+      m_result = m_minimumOutput;
+
+    pidOutput = m_pidOutput;
+    result = m_result;
+
+    pidOutput->PIDWrite(result);
+
+    // Update the buffer.
+    m_buf.push(m_error);
+    m_bufTotal += m_error;
+    // Remove old elements when buffer is full.
+    if (m_buf.size() > m_bufLength) {
+      m_bufTotal -= m_buf.front();
+      m_buf.pop();
+    }
+  }
+}
+
+/**
+ * Set the PID Controller gain parameters.
+ * Set the proportional, integral, and differential coefficients.
+ * @param p Proportional coefficient
+ * @param i Integral coefficient
+ * @param d Differential coefficient
+ */
+void PIDController::SetPID(double p, double i, double d) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_P = p;
+    m_I = i;
+    m_D = d;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutNumber("p", m_P);
+    m_table->PutNumber("i", m_I);
+    m_table->PutNumber("d", m_D);
+  }
+}
+
+/**
+ * Set the PID Controller gain parameters.
+ * Set the proportional, integral, and differential coefficients.
+ * @param p Proportional coefficient
+ * @param i Integral coefficient
+ * @param d Differential coefficient
+ * @param f Feed forward coefficient
+ */
+void PIDController::SetPID(double p, double i, double d, double f) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_P = p;
+    m_I = i;
+    m_D = d;
+    m_F = f;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutNumber("p", m_P);
+    m_table->PutNumber("i", m_I);
+    m_table->PutNumber("d", m_D);
+    m_table->PutNumber("f", m_F);
+  }
+}
+
+/**
+ * Get the Proportional coefficient
+ * @return proportional coefficient
+ */
+double PIDController::GetP() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_P;
+}
+
+/**
+ * Get the Integral coefficient
+ * @return integral coefficient
+ */
+double PIDController::GetI() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_I;
+}
+
+/**
+ * Get the Differential coefficient
+ * @return differential coefficient
+ */
+double PIDController::GetD() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_D;
+}
+
+/**
+ * Get the Feed forward coefficient
+ * @return Feed forward coefficient
+ */
+double PIDController::GetF() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_F;
+}
+
+/**
+ * Return the current PID result
+ * This is always centered on zero and constrained the the max and min outs
+ * @return the latest calculated output
+ */
+float PIDController::Get() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_result;
+}
+
+/**
+ *  Set the PID controller to consider the input to be continuous,
+ *  Rather then using the max and min in as constraints, it considers them to
+ *  be the same point and automatically calculates the shortest route to
+ *  the setpoint.
+ * @param continuous Set to true turns on continuous, false turns off continuous
+ */
+void PIDController::SetContinuous(bool continuous) {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  m_continuous = continuous;
+}
+
+/**
+ * Sets the maximum and minimum values expected from the input.
+ *
+ * @param minimumInput the minimum value expected from the input
+ * @param maximumInput the maximum value expected from the output
+ */
+void PIDController::SetInputRange(float minimumInput, float maximumInput) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_minimumInput = minimumInput;
+    m_maximumInput = maximumInput;
+  }
+
+  SetSetpoint(m_setpoint);
+}
+
+/**
+ * Sets the minimum and maximum values to write.
+ *
+ * @param minimumOutput the minimum value to write to the output
+ * @param maximumOutput the maximum value to write to the output
+ */
+void PIDController::SetOutputRange(float minimumOutput, float maximumOutput) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_minimumOutput = minimumOutput;
+    m_maximumOutput = maximumOutput;
+  }
+}
+
+/**
+ * Set the setpoint for the PIDController
+ * Clears the queue for GetAvgError().
+ * @param setpoint the desired setpoint
+ */
+void PIDController::SetSetpoint(float setpoint) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    if (m_maximumInput > m_minimumInput) {
+      if (setpoint > m_maximumInput)
+        m_setpoint = m_maximumInput;
+      else if (setpoint < m_minimumInput)
+        m_setpoint = m_minimumInput;
+      else
+        m_setpoint = setpoint;
+    } else {
+      m_setpoint = setpoint;
+    }
+
+    // Clear m_buf.
+    m_buf = std::queue<double>();
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutNumber("setpoint", m_setpoint);
+  }
+}
+
+/**
+ * Returns the current setpoint of the PIDController
+ * @return the current setpoint
+ */
+double PIDController::GetSetpoint() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_setpoint;
+}
+
+/**
+ * Returns the current difference of the input from the setpoint
+ * @return the current error
+ */
+float PIDController::GetError() const {
+  double pidInput;
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    pidInput = m_pidInput->PIDGet();
+  }
+  return GetSetpoint() - pidInput;
+}
+
+/**
+ * Sets what type of input the PID controller will use
+ */
+void PIDController::SetPIDSourceType(PIDSourceType pidSource) {
+  m_pidInput->SetPIDSourceType(pidSource);
+}
+/**
+ * Returns the type of input the PID controller is using
+ * @return the PID controller input type
+ */
+PIDSourceType PIDController::GetPIDSourceType() const {
+  return m_pidInput->GetPIDSourceType();
+}
+
+/**
+ * Returns the current average of the error over the past few iterations.
+ * You can specify the number of iterations to average with SetToleranceBuffer()
+ * (defaults to 1). This is the same value that is used for OnTarget().
+ * @return the average error
+ */
+float PIDController::GetAvgError() const {
+  float avgError = 0;
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    // Don't divide by zero.
+    if (m_buf.size()) avgError = m_bufTotal / m_buf.size();
+  }
+  return avgError;
+}
+
+/*
+ * Set the percentage error which is considered tolerable for use with
+ * OnTarget.
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetTolerance(float percent) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_toleranceType = kPercentTolerance;
+    m_tolerance = percent;
+  }
+}
+
+/*
+ * Set the percentage error which is considered tolerable for use with
+ * OnTarget.
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetPercentTolerance(float percent) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_toleranceType = kPercentTolerance;
+    m_tolerance = percent;
+  }
+}
+
+/*
+ * Set the absolute error which is considered tolerable for use with
+ * OnTarget.
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetAbsoluteTolerance(float absTolerance) {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_toleranceType = kAbsoluteTolerance;
+    m_tolerance = absTolerance;
+  }
+}
+
+/*
+ * Set the number of previous error samples to average for tolerancing. When
+ * determining whether a mechanism is on target, the user may want to use a
+ * rolling average of previous measurements instead of a precise position or
+ * velocity. This is useful for noisy sensors which return a few erroneous
+ * measurements when the mechanism is on target. However, the mechanism will
+ * not register as on target for at least the specified bufLength cycles.
+ * @param bufLength Number of previous cycles to average. Defaults to 1.
+ */
+void PIDController::SetToleranceBuffer(unsigned bufLength) {
+  m_bufLength = bufLength;
+
+  // Cut the buffer down to size if needed.
+  while (m_buf.size() > bufLength) {
+    m_bufTotal -= m_buf.front();
+    m_buf.pop();
+  }
+}
+
+/*
+ * Return true if the error is within the percentage of the total input range,
+ * determined by SetTolerance. This asssumes that the maximum and minimum input
+ * were set using SetInput.
+ * Currently this just reports on target as the actual value passes through the
+ * setpoint.
+ * Ideally it should be based on being within the tolerance for some period of
+ * time.
+ */
+bool PIDController::OnTarget() const {
+  double error = GetAvgError();
+
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  switch (m_toleranceType) {
+    case kPercentTolerance:
+      return fabs(error) < m_tolerance / 100 * (m_maximumInput - m_minimumInput);
+      break;
+    case kAbsoluteTolerance:
+      return fabs(error) < m_tolerance;
+      break;
+    case kNoTolerance:
+      // TODO: this case needs an error
+      return false;
+  }
+  return false;
+}
+
+/**
+ * Begin running the PIDController
+ */
+void PIDController::Enable() {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_enabled = true;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutBoolean("enabled", true);
+  }
+}
+
+/**
+ * Stop running the PIDController, this sets the output to zero before stopping.
+ */
+void PIDController::Disable() {
+  {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    m_pidOutput->PIDWrite(0);
+    m_enabled = false;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutBoolean("enabled", false);
+  }
+}
+
+/**
+ * Return true if PIDController is enabled.
+ */
+bool PIDController::IsEnabled() const {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  return m_enabled;
+}
+
+/**
+ * Reset the previous error,, the integral term, and disable the controller.
+ */
+void PIDController::Reset() {
+  Disable();
+
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  m_prevInput = 0;
+  m_totalError = 0;
+  m_result = 0;
+}
+
+std::string PIDController::GetSmartDashboardType() const {
+  return "PIDController";
+}
+
+void PIDController::InitTable(std::shared_ptr<ITable> table) {
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+  m_table = table;
+  if (m_table != nullptr) {
+    m_table->PutNumber(kP, GetP());
+    m_table->PutNumber(kI, GetI());
+    m_table->PutNumber(kD, GetD());
+    m_table->PutNumber(kF, GetF());
+    m_table->PutNumber(kSetpoint, GetSetpoint());
+    m_table->PutBoolean(kEnabled, IsEnabled());
+    m_table->AddTableListener(this, false);
+  }
+}
+
+std::shared_ptr<ITable> PIDController::GetTable() const { return m_table; }
+
+void PIDController::ValueChanged(ITable* source, llvm::StringRef key,
+                                 std::shared_ptr<nt::Value> value, bool isNew) {
+  if (key == kP || key == kI || key == kD || key == kF) {
+    if (m_P != m_table->GetNumber(kP, 0.0) ||
+        m_I != m_table->GetNumber(kI, 0.0) ||
+        m_D != m_table->GetNumber(kD, 0.0) ||
+        m_F != m_table->GetNumber(kF, 0.0)) {
+      SetPID(m_table->GetNumber(kP, 0.0), m_table->GetNumber(kI, 0.0),
+             m_table->GetNumber(kD, 0.0), m_table->GetNumber(kF, 0.0));
+    }
+  } else if (key == kSetpoint && value->IsDouble() &&
+             m_setpoint != value->GetDouble()) {
+    SetSetpoint(value->GetDouble());
+  } else if (key == kEnabled && value->IsBoolean() &&
+             m_enabled != value->GetBoolean()) {
+    if (value->GetBoolean()) {
+      Enable();
+    } else {
+      Disable();
+    }
+  }
+}
+
+void PIDController::UpdateTable() {}
+
+void PIDController::StartLiveWindowMode() { Disable(); }
+
+void PIDController::StopLiveWindowMode() {}
diff --git a/wpilibc/Athena/src/PWM.cpp b/wpilibc/Athena/src/PWM.cpp
new file mode 100644
index 0000000..6b3b4b7
--- /dev/null
+++ b/wpilibc/Athena/src/PWM.cpp
@@ -0,0 +1,374 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "PWM.h"
+
+#include "Resource.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include "HAL/HAL.hpp"
+
+#include <sstream>
+
+constexpr float PWM::kDefaultPwmPeriod;
+constexpr float PWM::kDefaultPwmCenter;
+const int32_t PWM::kDefaultPwmStepsDown;
+const int32_t PWM::kPwmDisabled;
+
+/**
+ * Allocate a PWM given a channel number.
+ *
+ * Checks channel value range and allocates the appropriate channel.
+ * The allocation is only done to help users ensure that they don't double
+ * assign channels.
+ * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP
+ * port
+ */
+PWM::PWM(uint32_t channel) {
+  std::stringstream buf;
+
+  if (!CheckPWMChannel(channel)) {
+    buf << "PWM Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  int32_t status = 0;
+  allocatePWMChannel(m_pwm_ports[channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  m_channel = channel;
+
+  setPWM(m_pwm_ports[m_channel], kPwmDisabled, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  m_eliminateDeadband = false;
+
+  HALReport(HALUsageReporting::kResourceType_PWM, channel);
+}
+
+/**
+ * Free the PWM channel.
+ *
+ * Free the resource associated with the PWM channel and set the value to 0.
+ */
+PWM::~PWM() {
+  int32_t status = 0;
+
+  setPWM(m_pwm_ports[m_channel], kPwmDisabled, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  freePWMChannel(m_pwm_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Optionally eliminate the deadband from a speed controller.
+ * @param eliminateDeadband If true, set the motor curve on the Jaguar to
+ * eliminate
+ * the deadband in the middle of the range. Otherwise, keep the full range
+ * without
+ * modifying any values.
+ */
+void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
+  if (StatusIsFatal()) return;
+  m_eliminateDeadband = eliminateDeadband;
+}
+
+/**
+ * Set the bounds on the PWM values.
+ * This sets the bounds on the PWM values for a particular each type of
+ * controller. The values
+ * determine the upper and lower speeds as well as the deadband bracket.
+ * @param max The Minimum pwm value
+ * @param deadbandMax The high end of the deadband range
+ * @param center The center speed (off)
+ * @param deadbandMin The low end of the deadband range
+ * @param min The minimum pwm value
+ */
+void PWM::SetBounds(int32_t max, int32_t deadbandMax, int32_t center,
+                    int32_t deadbandMin, int32_t min) {
+  if (StatusIsFatal()) return;
+  m_maxPwm = max;
+  m_deadbandMaxPwm = deadbandMax;
+  m_centerPwm = center;
+  m_deadbandMinPwm = deadbandMin;
+  m_minPwm = min;
+}
+
+/**
+ * Set the bounds on the PWM pulse widths.
+ * This sets the bounds on the PWM values for a particular type of controller.
+ * The values
+ * determine the upper and lower speeds as well as the deadband bracket.
+ * @param max The max PWM pulse width in ms
+ * @param deadbandMax The high end of the deadband range pulse width in ms
+ * @param center The center (off) pulse width in ms
+ * @param deadbandMin The low end of the deadband pulse width in ms
+ * @param min The minimum pulse width in ms
+ */
+void PWM::SetBounds(double max, double deadbandMax, double center,
+                    double deadbandMin, double min) {
+  // calculate the loop time in milliseconds
+  int32_t status = 0;
+  double loopTime =
+      getLoopTiming(&status) / (kSystemClockTicksPerMicrosecond * 1e3);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+
+  m_maxPwm = (int32_t)((max - kDefaultPwmCenter) / loopTime +
+                       kDefaultPwmStepsDown - 1);
+  m_deadbandMaxPwm = (int32_t)((deadbandMax - kDefaultPwmCenter) / loopTime +
+                               kDefaultPwmStepsDown - 1);
+  m_centerPwm = (int32_t)((center - kDefaultPwmCenter) / loopTime +
+                          kDefaultPwmStepsDown - 1);
+  m_deadbandMinPwm = (int32_t)((deadbandMin - kDefaultPwmCenter) / loopTime +
+                               kDefaultPwmStepsDown - 1);
+  m_minPwm = (int32_t)((min - kDefaultPwmCenter) / loopTime +
+                       kDefaultPwmStepsDown - 1);
+}
+
+/**
+ * Set the PWM value based on a position.
+ *
+ * This is intended to be used by servos.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @param pos The position to set the servo between 0.0 and 1.0.
+ */
+void PWM::SetPosition(float pos) {
+  if (StatusIsFatal()) return;
+  if (pos < 0.0) {
+    pos = 0.0;
+  } else if (pos > 1.0) {
+    pos = 1.0;
+  }
+
+  // note, need to perform the multiplication below as floating point before
+  // converting to int
+  unsigned short rawValue =
+      (int32_t)((pos * (float)GetFullRangeScaleFactor()) + GetMinNegativePwm());
+  //	printf("MinNegPWM: %d FullRangeScaleFactor: %d Raw value: %5d   Input
+  //value: %4.4f\n", GetMinNegativePwm(), GetFullRangeScaleFactor(), rawValue,
+  //pos);
+
+  //	wpi_assert((rawValue >= GetMinNegativePwm()) && (rawValue <=
+  //GetMaxPositivePwm()));
+  wpi_assert(rawValue != kPwmDisabled);
+
+  // send the computed pwm value to the FPGA
+  SetRaw((unsigned short)rawValue);
+}
+
+/**
+ * Get the PWM value in terms of a position.
+ *
+ * This is intended to be used by servos.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @return The position the servo is set to between 0.0 and 1.0.
+ */
+float PWM::GetPosition() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t value = GetRaw();
+  if (value < GetMinNegativePwm()) {
+    return 0.0;
+  } else if (value > GetMaxPositivePwm()) {
+    return 1.0;
+  } else {
+    return (float)(value - GetMinNegativePwm()) /
+           (float)GetFullRangeScaleFactor();
+  }
+}
+
+/**
+ * Set the PWM value based on a speed.
+ *
+ * This is intended to be used by speed controllers.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinPositivePwm() called.
+ * @pre SetCenterPwm() called.
+ * @pre SetMaxNegativePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @param speed The speed to set the speed controller between -1.0 and 1.0.
+ */
+void PWM::SetSpeed(float speed) {
+  if (StatusIsFatal()) return;
+  // clamp speed to be in the range 1.0 >= speed >= -1.0
+  if (speed < -1.0) {
+    speed = -1.0;
+  } else if (speed > 1.0) {
+    speed = 1.0;
+  }
+
+  // calculate the desired output pwm value by scaling the speed appropriately
+  int32_t rawValue;
+  if (speed == 0.0) {
+    rawValue = GetCenterPwm();
+  } else if (speed > 0.0) {
+    rawValue = (int32_t)(speed * ((float)GetPositiveScaleFactor()) +
+                         ((float)GetMinPositivePwm()) + 0.5);
+  } else {
+    rawValue = (int32_t)(speed * ((float)GetNegativeScaleFactor()) +
+                         ((float)GetMaxNegativePwm()) + 0.5);
+  }
+
+  // the above should result in a pwm_value in the valid range
+  wpi_assert((rawValue >= GetMinNegativePwm()) &&
+             (rawValue <= GetMaxPositivePwm()));
+  wpi_assert(rawValue != kPwmDisabled);
+
+  // send the computed pwm value to the FPGA
+  SetRaw(rawValue);
+}
+
+/**
+ * Get the PWM value in terms of speed.
+ *
+ * This is intended to be used by speed controllers.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinPositivePwm() called.
+ * @pre SetMaxNegativePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @return The most recently set speed between -1.0 and 1.0.
+ */
+float PWM::GetSpeed() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t value = GetRaw();
+  if (value == PWM::kPwmDisabled) {
+    return 0.0;
+  } else if (value > GetMaxPositivePwm()) {
+    return 1.0;
+  } else if (value < GetMinNegativePwm()) {
+    return -1.0;
+  } else if (value > GetMinPositivePwm()) {
+    return (float)(value - GetMinPositivePwm()) /
+           (float)GetPositiveScaleFactor();
+  } else if (value < GetMaxNegativePwm()) {
+    return (float)(value - GetMaxNegativePwm()) /
+           (float)GetNegativeScaleFactor();
+  } else {
+    return 0.0;
+  }
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param value Raw PWM value.
+ */
+void PWM::SetRaw(unsigned short value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  setPWM(m_pwm_ports[m_channel], value, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @return Raw PWM control value.
+ */
+unsigned short PWM::GetRaw() const {
+  if (StatusIsFatal()) return 0;
+
+  int32_t status = 0;
+  unsigned short value = getPWM(m_pwm_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  return value;
+}
+
+/**
+ * Slow down the PWM signal for old devices.
+ *
+ * @param mult The period multiplier to apply to this channel
+ */
+void PWM::SetPeriodMultiplier(PeriodMultiplier mult) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (mult) {
+    case kPeriodMultiplier_4X:
+      setPWMPeriodScale(m_pwm_ports[m_channel], 3,
+                        &status);  // Squelch 3 out of 4 outputs
+      break;
+    case kPeriodMultiplier_2X:
+      setPWMPeriodScale(m_pwm_ports[m_channel], 1,
+                        &status);  // Squelch 1 out of 2 outputs
+      break;
+    case kPeriodMultiplier_1X:
+      setPWMPeriodScale(m_pwm_ports[m_channel], 0,
+                        &status);  // Don't squelch any outputs
+      break;
+    default:
+      wpi_assert(false);
+  }
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+void PWM::SetZeroLatch() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  latchPWMZero(m_pwm_ports[m_channel], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+void PWM::ValueChanged(ITable* source, llvm::StringRef key,
+                       std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsDouble()) return;
+  SetSpeed(value->GetDouble());
+}
+
+void PWM::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetSpeed());
+  }
+}
+
+void PWM::StartLiveWindowMode() {
+  SetSpeed(0);
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void PWM::StopLiveWindowMode() {
+  SetSpeed(0);
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string PWM::GetSmartDashboardType() const { return "Speed Controller"; }
+
+void PWM::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> PWM::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/PowerDistributionPanel.cpp b/wpilibc/Athena/src/PowerDistributionPanel.cpp
new file mode 100644
index 0000000..fb428cf
--- /dev/null
+++ b/wpilibc/Athena/src/PowerDistributionPanel.cpp
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "PowerDistributionPanel.h"
+#include "WPIErrors.h"
+#include "HAL/PDP.hpp"
+#include "LiveWindow/LiveWindow.h"
+
+#include <sstream>
+
+PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {}
+
+/**
+ * Initialize the PDP.
+ */
+PowerDistributionPanel::PowerDistributionPanel(uint8_t module)
+    : m_module(module) {
+  initializePDP(m_module);
+}
+
+/**
+ * Query the input voltage of the PDP
+ * @return The voltage of the PDP in volts
+ */
+double PowerDistributionPanel::GetVoltage() const {
+  int32_t status = 0;
+
+  double voltage = getPDPVoltage(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return voltage;
+}
+
+/**
+ * Query the temperature of the PDP
+ * @return The temperature of the PDP in degrees Celsius
+ */
+double PowerDistributionPanel::GetTemperature() const {
+  int32_t status = 0;
+
+  double temperature = getPDPTemperature(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return temperature;
+}
+
+/**
+ * Query the current of a single channel of the PDP
+ * @return The current of one of the PDP channels (channels 0-15) in Amperes
+ */
+double PowerDistributionPanel::GetCurrent(uint8_t channel) const {
+  int32_t status = 0;
+
+  if (!CheckPDPChannel(channel)) {
+    std::stringstream buf;
+    buf << "PDP Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+  }
+
+  double current = getPDPChannelCurrent(m_module, channel, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return current;
+}
+
+/**
+ * Query the total current of all monitored PDP channels (0-15)
+ * @return The the total current drawn from the PDP channels in Amperes
+ */
+double PowerDistributionPanel::GetTotalCurrent() const {
+  int32_t status = 0;
+
+  double current = getPDPTotalCurrent(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return current;
+}
+
+/**
+ * Query the total power drawn from the monitored PDP channels
+ * @return The the total power drawn from the PDP channels in Watts
+ */
+double PowerDistributionPanel::GetTotalPower() const {
+  int32_t status = 0;
+
+  double power = getPDPTotalPower(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return power;
+}
+
+/**
+ * Query the total energy drawn from the monitored PDP channels
+ * @return The the total energy drawn from the PDP channels in Joules
+ */
+double PowerDistributionPanel::GetTotalEnergy() const {
+  int32_t status = 0;
+
+  double energy = getPDPTotalEnergy(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return energy;
+}
+
+/**
+ * Reset the total energy drawn from the PDP
+ * @see PowerDistributionPanel#GetTotalEnergy
+ */
+void PowerDistributionPanel::ResetTotalEnergy() {
+  int32_t status = 0;
+
+  resetPDPTotalEnergy(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+/**
+ * Remove all of the fault flags on the PDP
+ */
+void PowerDistributionPanel::ClearStickyFaults() {
+  int32_t status = 0;
+
+  clearPDPStickyFaults(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+void PowerDistributionPanel::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Chan0", GetCurrent(0));
+    m_table->PutNumber("Chan1", GetCurrent(1));
+    m_table->PutNumber("Chan2", GetCurrent(2));
+    m_table->PutNumber("Chan3", GetCurrent(3));
+    m_table->PutNumber("Chan4", GetCurrent(4));
+    m_table->PutNumber("Chan5", GetCurrent(5));
+    m_table->PutNumber("Chan6", GetCurrent(6));
+    m_table->PutNumber("Chan7", GetCurrent(7));
+    m_table->PutNumber("Chan8", GetCurrent(8));
+    m_table->PutNumber("Chan9", GetCurrent(9));
+    m_table->PutNumber("Chan10", GetCurrent(10));
+    m_table->PutNumber("Chan11", GetCurrent(11));
+    m_table->PutNumber("Chan12", GetCurrent(12));
+    m_table->PutNumber("Chan13", GetCurrent(13));
+    m_table->PutNumber("Chan14", GetCurrent(14));
+    m_table->PutNumber("Chan15", GetCurrent(15));
+    m_table->PutNumber("Voltage", GetVoltage());
+    m_table->PutNumber("TotalCurrent", GetTotalCurrent());
+  }
+}
+
+void PowerDistributionPanel::StartLiveWindowMode() {}
+
+void PowerDistributionPanel::StopLiveWindowMode() {}
+
+std::string PowerDistributionPanel::GetSmartDashboardType() const {
+  return "PowerDistributionPanel";
+}
+
+void PowerDistributionPanel::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> PowerDistributionPanel::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/Preferences.cpp b/wpilibc/Athena/src/Preferences.cpp
new file mode 100644
index 0000000..95f6a4a
--- /dev/null
+++ b/wpilibc/Athena/src/Preferences.cpp
@@ -0,0 +1,217 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Preferences.h"
+
+#include "WPIErrors.h"
+#include "HAL/HAL.hpp"
+
+#include <stdio.h>
+#include <algorithm>
+
+/** The Preferences table name */
+static const char *kTableName = "Preferences";
+
+void Preferences::Listener::ValueChanged(ITable* source, llvm::StringRef key,
+                                         std::shared_ptr<nt::Value> value,
+                                         bool isNew) {}
+void Preferences::Listener::ValueChangedEx(ITable* source, llvm::StringRef key,
+                                           std::shared_ptr<nt::Value> value,
+                                           unsigned int flags) {
+  source->SetPersistent(key);
+}
+
+Preferences::Preferences() : m_table(NetworkTable::GetTable(kTableName)) {
+  m_table->AddTableListenerEx(&m_listener, NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  HALReport(HALUsageReporting::kResourceType_Preferences, 0);
+}
+
+/**
+ * Get the one and only {@link Preferences} object
+ * @return pointer to the {@link Preferences}
+ */
+Preferences *Preferences::GetInstance() {
+  static Preferences instance;
+  return &instance;
+}
+
+/**
+ * Returns a vector of all the keys
+ * @return a vector of the keys
+ */
+std::vector<std::string> Preferences::GetKeys() { return m_table->GetKeys(); }
+
+/**
+ * Returns the string at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+std::string Preferences::GetString(llvm::StringRef key,
+                                   llvm::StringRef defaultValue) {
+  return m_table->GetString(key, defaultValue);
+}
+
+/**
+ * Returns the int at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+int Preferences::GetInt(llvm::StringRef key, int defaultValue) {
+  return static_cast<int>(m_table->GetNumber(key, defaultValue));
+}
+
+/**
+ * Returns the double at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+double Preferences::GetDouble(llvm::StringRef key, double defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+/**
+ * Returns the float at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+float Preferences::GetFloat(llvm::StringRef key, float defaultValue) {
+  return static_cast<float>(m_table->GetNumber(key, defaultValue));
+}
+
+/**
+ * Returns the boolean at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+bool Preferences::GetBoolean(llvm::StringRef key, bool defaultValue) {
+  return m_table->GetBoolean(key, defaultValue);
+}
+
+/**
+ * Returns the long (int64_t) at the given key.  If this table does not have a
+ * value
+ * for that position, then the given defaultValue value will be returned.
+ * @param key the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+int64_t Preferences::GetLong(llvm::StringRef key, int64_t defaultValue) {
+  return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
+}
+
+/**
+ * Puts the given string into the preferences table.
+ *
+ * <p>The value may not have quotation marks, nor may the key
+ * have any whitespace nor an equals sign</p>
+ *
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutString(llvm::StringRef key, llvm::StringRef value) {
+  m_table->PutString(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given int into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutInt(llvm::StringRef key, int value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given double into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutDouble(llvm::StringRef key, double value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given float into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutFloat(llvm::StringRef key, float value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given boolean into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutBoolean(llvm::StringRef key, bool value) {
+  m_table->PutBoolean(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given long (int64_t) into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key the key
+ * @param value the value
+ */
+void Preferences::PutLong(llvm::StringRef key, int64_t value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * This function is no longer required, as NetworkTables automatically
+ * saves persistent values (which all Preferences values are) periodically
+ * when running as a server.
+ * @deprecated backwards compatibility shim
+ */
+void Preferences::Save() {}
+
+/**
+ * Returns whether or not there is a key with the given name.
+ * @param key the key
+ * @return if there is a value at the given key
+ */
+bool Preferences::ContainsKey(llvm::StringRef key) {
+  return m_table->ContainsKey(key);
+}
+
+/**
+ * Remove a preference
+ * @param key the key
+ */
+void Preferences::Remove(llvm::StringRef key) {
+  m_table->Delete(key);
+}
diff --git a/wpilibc/Athena/src/Relay.cpp b/wpilibc/Athena/src/Relay.cpp
new file mode 100644
index 0000000..17f0ef8
--- /dev/null
+++ b/wpilibc/Athena/src/Relay.cpp
@@ -0,0 +1,293 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Relay.h"
+
+#include "MotorSafetyHelper.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+#include "HAL/HAL.hpp"
+
+#include <sstream>
+
+// Allocate each direction separately.
+static std::unique_ptr<Resource> relayChannels;
+
+/**
+ * Relay constructor given a channel.
+ *
+ * This code initializes the relay and reserves all resources that need to be
+ * locked. Initially the relay is set to both lines at 0v.
+ * @param channel The channel number (0-3).
+ * @param direction The direction that the Relay object will control.
+ */
+Relay::Relay(uint32_t channel, Relay::Direction direction)
+    : m_channel(channel), m_direction(direction) {
+  std::stringstream buf;
+  Resource::CreateResourceObject(relayChannels,
+                                 dio_kNumSystems * kRelayChannels * 2);
+  if (!SensorBase::CheckRelayChannel(m_channel)) {
+    buf << "Relay Channel " << m_channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+    buf << "Forward Relay " << m_channel;
+    if (relayChannels->Allocate(m_channel * 2, buf.str()) ==
+        std::numeric_limits<uint32_t>::max()) {
+      CloneError(*relayChannels);
+      return;
+    }
+
+    HALReport(HALUsageReporting::kResourceType_Relay, m_channel);
+  }
+  if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+    buf << "Reverse Relay " << m_channel;
+    if (relayChannels->Allocate(m_channel * 2 + 1, buf.str()) ==
+        std::numeric_limits<uint32_t>::max()) {
+      CloneError(*relayChannels);
+      return;
+    }
+
+    HALReport(HALUsageReporting::kResourceType_Relay, m_channel + 128);
+  }
+
+  int32_t status = 0;
+  setRelayForward(m_relay_ports[m_channel], false, &status);
+  setRelayReverse(m_relay_ports[m_channel], false, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+  m_safetyHelper->SetSafetyEnabled(false);
+
+  LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this);
+}
+
+/**
+ * Free the resource associated with a relay.
+ * The relay channels are set to free and the relay output is turned off.
+ */
+Relay::~Relay() {
+  int32_t status = 0;
+  setRelayForward(m_relay_ports[m_channel], false, &status);
+  setRelayReverse(m_relay_ports[m_channel], false, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+    relayChannels->Free(m_channel * 2);
+  }
+  if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+    relayChannels->Free(m_channel * 2 + 1);
+  }
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Set the relay state.
+ *
+ * Valid values depend on which directions of the relay are controlled by the
+ * object.
+ *
+ * When set to kBothDirections, the relay can be any of the four states:
+ * 	 0v-0v, 0v-12v, 12v-0v, 12v-12v
+ *
+ * When set to kForwardOnly or kReverseOnly, you can specify the constant for
+ * the
+ * 	 direction or you can simply specify kOff and kOn.  Using only kOff and
+ * kOn is
+ * 	 recommended.
+ *
+ * @param value The state to set the relay.
+ */
+void Relay::Set(Relay::Value value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (value) {
+    case kOff:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        setRelayForward(m_relay_ports[m_channel], false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        setRelayReverse(m_relay_ports[m_channel], false, &status);
+      }
+      break;
+    case kOn:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        setRelayForward(m_relay_ports[m_channel], true, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        setRelayReverse(m_relay_ports[m_channel], true, &status);
+      }
+      break;
+    case kForward:
+      if (m_direction == kReverseOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        setRelayForward(m_relay_ports[m_channel], true, &status);
+      }
+      if (m_direction == kBothDirections) {
+        setRelayReverse(m_relay_ports[m_channel], false, &status);
+      }
+      break;
+    case kReverse:
+      if (m_direction == kForwardOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections) {
+        setRelayForward(m_relay_ports[m_channel], false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        setRelayReverse(m_relay_ports[m_channel], true, &status);
+      }
+      break;
+  }
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the Relay State
+ *
+ * Gets the current state of the relay.
+ *
+ * When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not
+ * kForward/kReverse (per the recommendation in Set)
+ *
+ * @return The current state of the relay as a Relay::Value
+ */
+Relay::Value Relay::Get() const {
+  int32_t status;
+
+  if (getRelayForward(m_relay_ports[m_channel], &status)) {
+    if (getRelayReverse(m_relay_ports[m_channel], &status)) {
+      return kOn;
+    } else {
+      if (m_direction == kForwardOnly) {
+        return kOn;
+      } else {
+        return kForward;
+      }
+    }
+  } else {
+    if (getRelayReverse(m_relay_ports[m_channel], &status)) {
+      if (m_direction == kReverseOnly) {
+        return kOn;
+      } else {
+        return kReverse;
+      }
+    } else {
+      return kOff;
+    }
+  }
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+uint32_t Relay::GetChannel() const {
+  return m_channel;
+}
+
+/**
+ * Set the expiration time for the Relay object
+ * @param timeout The timeout (in seconds) for this relay object
+ */
+void Relay::SetExpiration(float timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+/**
+ * Return the expiration time for the relay object.
+ * @return The expiration time value.
+ */
+float Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); }
+
+/**
+ * Check if the relay object is currently alive or stopped due to a timeout.
+ * @returns a bool value that is true if the motor has NOT timed out and should
+ * still be running.
+ */
+bool Relay::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+/**
+ * Stop the motor associated with this PWM object.
+ * This is called by the MotorSafetyHelper object when it has a timeout for this
+ * relay and needs to stop it from running.
+ */
+void Relay::StopMotor() { Set(kOff); }
+
+/**
+ * Enable/disable motor safety for this device
+ * Turn on and off the motor safety option for this relay object.
+ * @param enabled True if motor safety is enforced for this object
+ */
+void Relay::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+/**
+ * Check if motor safety is enabled for this object
+ * @returns True if motor safety is enforced for this object
+ */
+bool Relay::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void Relay::GetDescription(std::ostringstream& desc) const {
+  desc << "Relay " << GetChannel();
+}
+
+void Relay::ValueChanged(ITable* source, llvm::StringRef key,
+                         std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsString()) return;
+  if (value->GetString() == "Off") Set(kOff);
+  else if (value->GetString() == "Forward") Set(kForward);
+  else if (value->GetString() == "Reverse") Set(kReverse);
+  else if (value->GetString() == "On") Set(kOn);
+}
+
+void Relay::UpdateTable() {
+  if (m_table != nullptr) {
+    if (Get() == kOn) {
+      m_table->PutString("Value", "On");
+    } else if (Get() == kForward) {
+      m_table->PutString("Value", "Forward");
+    } else if (Get() == kReverse) {
+      m_table->PutString("Value", "Reverse");
+    } else {
+      m_table->PutString("Value", "Off");
+    }
+  }
+}
+
+void Relay::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void Relay::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string Relay::GetSmartDashboardType() const { return "Relay"; }
+
+void Relay::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Relay::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/RobotBase.cpp b/wpilibc/Athena/src/RobotBase.cpp
new file mode 100644
index 0000000..2bd1d13
--- /dev/null
+++ b/wpilibc/Athena/src/RobotBase.cpp
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "RobotBase.h"
+
+#include "DriverStation.h"
+#include "RobotState.h"
+#include "HLUsageReporting.h"
+#include "Internal/HardwareHLReporting.h"
+#include "Utility.h"
+#include "networktables/NetworkTable.h"
+#include <cstring>
+#include "HAL/HAL.hpp"
+#include <cstdio>
+
+RobotBase *RobotBase::m_instance = nullptr;
+
+void RobotBase::setInstance(RobotBase *robot) {
+  wpi_assert(m_instance == nullptr);
+  m_instance = robot;
+}
+
+RobotBase &RobotBase::getInstance() { return *m_instance; }
+
+void RobotBase::robotSetup(RobotBase *robot) {
+  robot->StartCompetition();
+}
+
+/**
+ * Constructor for a generic robot program.
+ * User code should be placed in the constructor that runs before the Autonomous
+ * or Operator
+ * Control period starts. The constructor will run to completion before
+ * Autonomous is entered.
+ *
+ * This must be used to ensure that the communications code starts. In the
+ * future it would be
+ * nice to put this code into it's own task that loads on boot so ensure that it
+ * runs.
+ */
+RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
+  RobotState::SetImplementation(DriverStation::GetInstance());
+  HLUsageReporting::SetImplementation(new HardwareHLReporting());
+
+  RobotBase::setInstance(this);
+
+  NetworkTable::SetNetworkIdentity("Robot");
+
+  FILE *file = nullptr;
+  file = fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
+
+  if (file != nullptr) {
+    fputs("2016 C++ Beta5.0", file);
+    fclose(file);
+  }
+}
+
+/**
+ * Free the resources for a RobotBase class.
+ * This includes deleting all classes that might have been allocated as
+ * Singletons to they
+ * would never be deleted except here.
+ */
+RobotBase::~RobotBase() {
+  SensorBase::DeleteSingletons();
+  delete m_task;
+  m_task = nullptr;
+  m_instance = nullptr;
+}
+
+/**
+ * Determine if the Robot is currently enabled.
+ * @return True if the Robot is currently enabled by the field controls.
+ */
+bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); }
+
+/**
+ * Determine if the Robot is currently disabled.
+ * @return True if the Robot is currently disabled by the field controls.
+ */
+bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); }
+
+/**
+ * Determine if the robot is currently in Autonomous mode.
+ * @return True if the robot is currently operating Autonomously as determined
+ * by the field controls.
+ */
+bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); }
+
+/**
+ * Determine if the robot is currently in Operator Control mode.
+ * @return True if the robot is currently operating in Tele-Op mode as
+ * determined by the field controls.
+ */
+bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); }
+
+/**
+ * Determine if the robot is currently in Test mode.
+ * @return True if the robot is currently running tests as determined by the
+ * field controls.
+ */
+bool RobotBase::IsTest() const { return m_ds.IsTest(); }
+
+/**
+ * Indicates if new data is available from the driver station.
+ * @return Has new data arrived over the network since the last time this
+ * function was called?
+ */
+bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); }
+
+/**
+ * This class exists for the sole purpose of getting its destructor called when
+ * the module unloads.
+ * Before the module is done unloading, we need to delete the RobotBase derived
+ * singleton.  This should delete
+ * the other remaining singletons that were registered.  This should also stop
+ * all tasks that are using
+ * the Task class.
+ */
+class RobotDeleter {
+ public:
+  RobotDeleter() {}
+  ~RobotDeleter() { delete &RobotBase::getInstance(); }
+};
+static RobotDeleter g_robotDeleter;
diff --git a/wpilibc/Athena/src/RobotDrive.cpp b/wpilibc/Athena/src/RobotDrive.cpp
new file mode 100644
index 0000000..c1353e9
--- /dev/null
+++ b/wpilibc/Athena/src/RobotDrive.cpp
@@ -0,0 +1,753 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "RobotDrive.h"
+
+#include "CANJaguar.h"
+#include "GenericHID.h"
+#include "Joystick.h"
+#include "Talon.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include <math.h>
+
+#undef max
+#include <algorithm>
+
+const int32_t RobotDrive::kMaxNumberOfMotors;
+
+static auto make_shared_nodelete(SpeedController *ptr) {
+  return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
+}
+
+/*
+ * Driving functions
+ * These functions provide an interface to multiple motors that is used for C
+ * programming
+ * The Drive(speed, direction) function is the main part of the set that makes
+ * it easy
+ * to set speeds and direction independently in one call.
+ */
+
+/**
+ * Common function to initialize all the robot drive constructors.
+ * Create a motor safety object (the real reason for the common code) and
+ * initialize all the motor assignments. The default timeout is set for the
+ * robot drive.
+ */
+void RobotDrive::InitRobotDrive() {
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+  m_safetyHelper->SetSafetyEnabled(true);
+}
+
+/**
+ * Constructor for RobotDrive with 2 motors specified with channel numbers.
+ * Set up parameters for a two wheel drive system where the
+ * left and right motor pwm channels are specified in the call.
+ * This call assumes Talons for controlling the motors.
+ * @param leftMotorChannel The PWM channel number that drives the left motor.
+ * 0-9 are on-board, 10-19 are on the MXP port
+ * @param rightMotorChannel The PWM channel number that drives the right motor.
+ * 0-9 are on-board, 10-19 are on the MXP port
+ */
+RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
+  m_rearRightMotor = std::make_shared<Talon>(rightMotorChannel);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+/**
+ * Constructor for RobotDrive with 4 motors specified with channel numbers.
+ * Set up parameters for a four wheel drive system where all four motor
+ * pwm channels are specified in the call.
+ * This call assumes Talons for controlling the motors.
+ * @param frontLeftMotor Front left motor channel number. 0-9 are on-board,
+ * 10-19 are on the MXP port
+ * @param rearLeftMotor Rear Left motor channel number. 0-9 are on-board, 10-19
+ * are on the MXP port
+ * @param frontRightMotor Front right motor channel number. 0-9 are on-board,
+ * 10-19 are on the MXP port
+ * @param rearRightMotor Rear Right motor channel number. 0-9 are on-board,
+ * 10-19 are on the MXP port
+ */
+RobotDrive::RobotDrive(uint32_t frontLeftMotor, uint32_t rearLeftMotor,
+                       uint32_t frontRightMotor, uint32_t rearRightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(rearLeftMotor);
+  m_rearRightMotor = std::make_shared<Talon>(rearRightMotor);
+  m_frontLeftMotor = std::make_shared<Talon>(frontLeftMotor);
+  m_frontRightMotor = std::make_shared<Talon>(frontRightMotor);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+/**
+ * Constructor for RobotDrive with 2 motors specified as SpeedController
+ * objects.
+ * The SpeedController version of the constructor enables programs to use the
+ * RobotDrive classes with
+ * subclasses of the SpeedController objects, for example, versions with ramping
+ * or reshaping of
+ * the curve to suit motor bias or deadband elimination.
+ * @param leftMotor The left SpeedController object used to drive the robot.
+ * @param rightMotor the right SpeedController object used to drive the robot.
+ */
+RobotDrive::RobotDrive(SpeedController *leftMotor,
+                       SpeedController *rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = make_shared_nodelete(leftMotor);
+  m_rearRightMotor = make_shared_nodelete(rightMotor);
+}
+
+//TODO: Change to rvalue references & move syntax.
+RobotDrive::RobotDrive(SpeedController &leftMotor,
+                       SpeedController &rightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = make_shared_nodelete(&leftMotor);
+  m_rearRightMotor = make_shared_nodelete(&rightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+                       std::shared_ptr<SpeedController> rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = leftMotor;
+  m_rearRightMotor = rightMotor;
+}
+
+/**
+ * Constructor for RobotDrive with 4 motors specified as SpeedController
+ * objects.
+ * Speed controller input version of RobotDrive (see previous comments).
+ * @param rearLeftMotor The back left SpeedController object used to drive the
+ * robot.
+ * @param frontLeftMotor The front left SpeedController object used to drive the
+ * robot
+ * @param rearRightMotor The back right SpeedController object used to drive the
+ * robot.
+ * @param frontRightMotor The front right SpeedController object used to drive
+ * the robot.
+ */
+RobotDrive::RobotDrive(SpeedController *frontLeftMotor,
+                       SpeedController *rearLeftMotor,
+                       SpeedController *frontRightMotor,
+                       SpeedController *rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = make_shared_nodelete(frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(rearRightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController &frontLeftMotor,
+                       SpeedController &rearLeftMotor,
+                       SpeedController &frontRightMotor,
+                       SpeedController &rearRightMotor) {
+  InitRobotDrive();
+  m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(&frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(&rearRightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+                       std::shared_ptr<SpeedController> rearLeftMotor,
+                       std::shared_ptr<SpeedController> frontRightMotor,
+                       std::shared_ptr<SpeedController> rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = frontLeftMotor;
+  m_rearLeftMotor = rearLeftMotor;
+  m_frontRightMotor = frontRightMotor;
+  m_rearRightMotor = rearRightMotor;
+}
+
+/**
+ * Drive the motors at "outputMagnitude" and "curve".
+ * Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0 represents
+ * stopped and not turning. curve < 0 will turn left and curve > 0 will turn
+ * right.
+ *
+ * The algorithm for steering provides a constant turn radius for any normal
+ * speed range, both forward and backward. Increasing m_sensitivity causes
+ * sharper turns for fixed values of curve.
+ *
+ * This function will most likely be used in an autonomous routine.
+ *
+ * @param outputMagnitude The speed setting for the outside wheel in a turn,
+ *        forward or backwards, +1 to -1.
+ * @param curve The rate of turn, constant for different forward speeds. Set
+ *        curve < 0 for left turn or curve > 0 for right turn.
+ * Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot.
+ * Conversely, turn radius r = -ln(curve)*w for a given value of curve and
+ * wheelbase w.
+ */
+void RobotDrive::Drive(float outputMagnitude, float curve) {
+  float leftOutput, rightOutput;
+  static bool reported = false;
+  if (!reported) {
+    HALReport(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+              HALUsageReporting::kRobotDrive_ArcadeRatioCurve);
+    reported = true;
+  }
+
+  if (curve < 0) {
+    float value = log(-curve);
+    float ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = .0000000001;
+    leftOutput = outputMagnitude / ratio;
+    rightOutput = outputMagnitude;
+  } else if (curve > 0) {
+    float value = log(curve);
+    float ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = .0000000001;
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude / ratio;
+  } else {
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude;
+  }
+  SetLeftRightMotorOutputs(leftOutput, rightOutput);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * Drive the robot using two joystick inputs. The Y-axis will be selected from
+ * each Joystick object.
+ * @param leftStick The joystick to control the left side of the robot.
+ * @param rightStick The joystick to control the right side of the robot.
+ */
+void RobotDrive::TankDrive(GenericHID *leftStick, GenericHID *rightStick,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetY(), rightStick->GetY(), squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID &leftStick, GenericHID &rightStick,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetY(), rightStick.GetY(), squaredInputs);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * This function lets you pick the axis to be used on each Joystick object for
+ * the left
+ * and right sides of the robot.
+ * @param leftStick The Joystick object to use for the left side of the robot.
+ * @param leftAxis The axis to select on the left side Joystick object.
+ * @param rightStick The Joystick object to use for the right side of the robot.
+ * @param rightAxis The axis to select on the right side Joystick object.
+ */
+void RobotDrive::TankDrive(GenericHID *leftStick, uint32_t leftAxis,
+                           GenericHID *rightStick, uint32_t rightAxis,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetRawAxis(leftAxis), rightStick->GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID &leftStick, uint32_t leftAxis,
+                           GenericHID &rightStick, uint32_t rightAxis,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ * This function lets you directly provide joystick values from any source.
+ * @param leftValue The value of the left stick.
+ * @param rightValue The value of the right stick.
+ */
+void RobotDrive::TankDrive(float leftValue, float rightValue,
+                           bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HALReport(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+              HALUsageReporting::kRobotDrive_Tank);
+    reported = true;
+  }
+
+  // square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power
+  leftValue = Limit(leftValue);
+  rightValue = Limit(rightValue);
+  if (squaredInputs) {
+    if (leftValue >= 0.0) {
+      leftValue = (leftValue * leftValue);
+    } else {
+      leftValue = -(leftValue * leftValue);
+    }
+    if (rightValue >= 0.0) {
+      rightValue = (rightValue * rightValue);
+    } else {
+      rightValue = -(rightValue * rightValue);
+    }
+  }
+
+  SetLeftRightMotorOutputs(leftValue, rightValue);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given a single Joystick, the class assumes the Y axis for the move value and
+ * the X axis
+ * for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ * @param stick The joystick to use for Arcade single-stick driving. The Y-axis
+ * will be selected
+ * for forwards/backwards and the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small
+ * values
+ */
+void RobotDrive::ArcadeDrive(GenericHID *stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick->GetY(), stick->GetX(), squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given a single Joystick, the class assumes the Y axis for the move value and
+ * the X axis
+ * for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ * @param stick The joystick to use for Arcade single-stick driving. The Y-axis
+ * will be selected
+ * for forwards/backwards and the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small
+ * values
+ */
+void RobotDrive::ArcadeDrive(GenericHID &stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick.GetY(), stick.GetX(), squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given two joystick instances and two axis, compute the values to send to
+ * either two
+ * or four motors.
+ * @param moveStick The Joystick object that represents the forward/backward
+ * direction
+ * @param moveAxis The axis on the moveStick object to use for fowards/backwards
+ * (typically Y_AXIS)
+ * @param rotateStick The Joystick object that represents the rotation value
+ * @param rotateAxis The axis on the rotation object to use for the rotate
+ * right/left (typically X_AXIS)
+ * @param squaredInputs Setting this parameter to true increases the sensitivity
+ * at lower speeds
+ */
+void RobotDrive::ArcadeDrive(GenericHID *moveStick, uint32_t moveAxis,
+                             GenericHID *rotateStick, uint32_t rotateAxis,
+                             bool squaredInputs) {
+  float moveValue = moveStick->GetRawAxis(moveAxis);
+  float rotateValue = rotateStick->GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * Given two joystick instances and two axis, compute the values to send to
+ * either two
+ * or four motors.
+ * @param moveStick The Joystick object that represents the forward/backward
+ * direction
+ * @param moveAxis The axis on the moveStick object to use for fowards/backwards
+ * (typically Y_AXIS)
+ * @param rotateStick The Joystick object that represents the rotation value
+ * @param rotateAxis The axis on the rotation object to use for the rotate
+ * right/left (typically X_AXIS)
+ * @param squaredInputs Setting this parameter to true increases the sensitivity
+ * at lower speeds
+ */
+
+void RobotDrive::ArcadeDrive(GenericHID &moveStick, uint32_t moveAxis,
+                             GenericHID &rotateStick, uint32_t rotateAxis,
+                             bool squaredInputs) {
+  float moveValue = moveStick.GetRawAxis(moveAxis);
+  float rotateValue = rotateStick.GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ * This function lets you directly provide joystick values from any source.
+ * @param moveValue The value to use for fowards/backwards
+ * @param rotateValue The value to use for the rotate right/left
+ * @param squaredInputs If set, increases the sensitivity at low speeds
+ */
+void RobotDrive::ArcadeDrive(float moveValue, float rotateValue,
+                             bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HALReport(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+              HALUsageReporting::kRobotDrive_ArcadeStandard);
+    reported = true;
+  }
+
+  // local variables to hold the computed PWM values for the motors
+  float leftMotorOutput;
+  float rightMotorOutput;
+
+  moveValue = Limit(moveValue);
+  rotateValue = Limit(rotateValue);
+
+  if (squaredInputs) {
+    // square the inputs (while preserving the sign) to increase fine control
+    // while permitting full power
+    if (moveValue >= 0.0) {
+      moveValue = (moveValue * moveValue);
+    } else {
+      moveValue = -(moveValue * moveValue);
+    }
+    if (rotateValue >= 0.0) {
+      rotateValue = (rotateValue * rotateValue);
+    } else {
+      rotateValue = -(rotateValue * rotateValue);
+    }
+  }
+
+  if (moveValue > 0.0) {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = std::max(moveValue, rotateValue);
+    } else {
+      leftMotorOutput = std::max(moveValue, -rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    }
+  } else {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = -std::max(-moveValue, rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    } else {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = -std::max(-moveValue, -rotateValue);
+    }
+  }
+  SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
+}
+
+/**
+ * Drive method for Mecanum wheeled robots.
+ *
+ * A method for driving with Mecanum wheeled robots. There are 4 wheels
+ * on the robot, arranged so that the front and back wheels are toed in 45
+ * degrees.
+ * When looking at the wheels from the top, the roller axles should form an X
+ * across the robot.
+ *
+ * This is designed to be directly driven by joystick axes.
+ *
+ * @param x The speed that the robot should drive in the X direction.
+ * [-1.0..1.0]
+ * @param y The speed that the robot should drive in the Y direction.
+ * This input is inverted to match the forward == -1.0 that joysticks produce.
+ * [-1.0..1.0]
+ * @param rotation The rate of rotation for the robot that is completely
+ * independent of
+ * the translation. [-1.0..1.0]
+ * @param gyroAngle The current angle reading from the gyro.  Use this to
+ * implement field-oriented controls.
+ */
+void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation,
+                                        float gyroAngle) {
+  static bool reported = false;
+  if (!reported) {
+    HALReport(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+              HALUsageReporting::kRobotDrive_MecanumCartesian);
+    reported = true;
+  }
+
+  double xIn = x;
+  double yIn = y;
+  // Negate y for the joystick.
+  yIn = -yIn;
+  // Compenstate for gyro angle.
+  RotateVector(xIn, yIn, gyroAngle);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = xIn + yIn + rotation;
+  wheelSpeeds[kFrontRightMotor] = -xIn + yIn - rotation;
+  wheelSpeeds[kRearLeftMotor] = -xIn + yIn + rotation;
+  wheelSpeeds[kRearRightMotor] = xIn + yIn - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput,
+                        m_syncGroup);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput,
+                         m_syncGroup);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput, m_syncGroup);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput,
+                        m_syncGroup);
+
+  if (m_syncGroup != 0) {
+    CANJaguar::UpdateSyncGroup(m_syncGroup);
+  }
+
+  m_safetyHelper->Feed();
+}
+
+/**
+ * Drive method for Mecanum wheeled robots.
+ *
+ * A method for driving with Mecanum wheeled robots. There are 4 wheels
+ * on the robot, arranged so that the front and back wheels are toed in 45
+ * degrees.
+ * When looking at the wheels from the top, the roller axles should form an X
+ * across the robot.
+ *
+ * @param magnitude The speed that the robot should drive in a given direction.
+ * [-1.0..1.0]
+ * @param direction The direction the robot should drive in degrees. The
+ * direction and maginitute are
+ * independent of the rotation rate.
+ * @param rotation The rate of rotation for the robot that is completely
+ * independent of
+ * the magnitute or direction. [-1.0..1.0]
+ */
+void RobotDrive::MecanumDrive_Polar(float magnitude, float direction,
+                                    float rotation) {
+  static bool reported = false;
+  if (!reported) {
+    HALReport(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+              HALUsageReporting::kRobotDrive_MecanumPolar);
+    reported = true;
+  }
+
+  // Normalized for full power along the Cartesian axes.
+  magnitude = Limit(magnitude) * sqrt(2.0);
+  // The rollers are at 45 degree angles.
+  double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
+  double cosD = cos(dirInRad);
+  double sinD = sin(dirInRad);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = sinD * magnitude + rotation;
+  wheelSpeeds[kFrontRightMotor] = cosD * magnitude - rotation;
+  wheelSpeeds[kRearLeftMotor] = cosD * magnitude + rotation;
+  wheelSpeeds[kRearRightMotor] = sinD * magnitude - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput,
+                        m_syncGroup);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput,
+                         m_syncGroup);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput, m_syncGroup);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput,
+                        m_syncGroup);
+
+  if (m_syncGroup != 0) {
+    CANJaguar::UpdateSyncGroup(m_syncGroup);
+  }
+
+  m_safetyHelper->Feed();
+}
+
+/**
+ * Holonomic Drive method for Mecanum wheeled robots.
+ *
+ * This is an alias to MecanumDrive_Polar() for backward compatability
+ *
+ * @param magnitude The speed that the robot should drive in a given direction.
+ * [-1.0..1.0]
+ * @param direction The direction the robot should drive. The direction and
+ * maginitute are
+ * independent of the rotation rate.
+ * @param rotation The rate of rotation for the robot that is completely
+ * independent of
+ * the magnitute or direction.  [-1.0..1.0]
+ */
+void RobotDrive::HolonomicDrive(float magnitude, float direction,
+                                float rotation) {
+  MecanumDrive_Polar(magnitude, direction, rotation);
+}
+
+/** Set the speed of the right and left motors.
+ * This is used once an appropriate drive setup function is called such as
+ * TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
+ * and includes flipping the direction of one side for opposing motors.
+ * @param leftOutput The speed to send to the left side of the robot.
+ * @param rightOutput The speed to send to the right side of the robot.
+ */
+void RobotDrive::SetLeftRightMotorOutputs(float leftOutput, float rightOutput) {
+  wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr);
+
+  if (m_frontLeftMotor != nullptr)
+    m_frontLeftMotor->Set(Limit(leftOutput) * m_maxOutput, m_syncGroup);
+  m_rearLeftMotor->Set(Limit(leftOutput) * m_maxOutput, m_syncGroup);
+
+  if (m_frontRightMotor != nullptr)
+    m_frontRightMotor->Set(-Limit(rightOutput) * m_maxOutput, m_syncGroup);
+  m_rearRightMotor->Set(-Limit(rightOutput) * m_maxOutput, m_syncGroup);
+
+  if (m_syncGroup != 0) {
+    CANJaguar::UpdateSyncGroup(m_syncGroup);
+  }
+
+  m_safetyHelper->Feed();
+}
+
+/**
+ * Limit motor values to the -1.0 to +1.0 range.
+ */
+float RobotDrive::Limit(float num) {
+  if (num > 1.0) {
+    return 1.0;
+  }
+  if (num < -1.0) {
+    return -1.0;
+  }
+  return num;
+}
+
+/**
+ * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
+ */
+void RobotDrive::Normalize(double *wheelSpeeds) {
+  double maxMagnitude = fabs(wheelSpeeds[0]);
+  int32_t i;
+  for (i = 1; i < kMaxNumberOfMotors; i++) {
+    double temp = fabs(wheelSpeeds[i]);
+    if (maxMagnitude < temp) maxMagnitude = temp;
+  }
+  if (maxMagnitude > 1.0) {
+    for (i = 0; i < kMaxNumberOfMotors; i++) {
+      wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+    }
+  }
+}
+
+/**
+ * Rotate a vector in Cartesian space.
+ */
+void RobotDrive::RotateVector(double &x, double &y, double angle) {
+  double cosA = cos(angle * (3.14159 / 180.0));
+  double sinA = sin(angle * (3.14159 / 180.0));
+  double xOut = x * cosA - y * sinA;
+  double yOut = x * sinA + y * cosA;
+  x = xOut;
+  y = yOut;
+}
+
+/*
+ * Invert a motor direction.
+ * This is used when a motor should run in the opposite direction as the drive
+ * code would normally run it. Motors that are direct drive would be inverted,
+ * the
+ * Drive code assumes that the motors are geared with one reversal.
+ * @param motor The motor index to invert.
+ * @param isInverted True if the motor should be inverted when operated.
+ */
+void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
+  if (motor < 0 || motor > 3) {
+    wpi_setWPIError(InvalidMotorIndex);
+    return;
+  }
+  switch (motor) {
+    case kFrontLeftMotor:
+      m_frontLeftMotor->SetInverted(isInverted);
+      break;
+    case kFrontRightMotor:
+      m_frontRightMotor->SetInverted(isInverted);
+      break;
+    case kRearLeftMotor:
+      m_rearLeftMotor->SetInverted(isInverted);
+      break;
+    case kRearRightMotor:
+      m_rearRightMotor->SetInverted(isInverted);
+      break;
+  }
+}
+
+/**
+ * Set the turning sensitivity.
+ *
+ * This only impacts the Drive() entry-point.
+ * @param sensitivity Effectively sets the turning sensitivity (or turn radius
+ * for a given value)
+ */
+void RobotDrive::SetSensitivity(float sensitivity) {
+  m_sensitivity = sensitivity;
+}
+
+/**
+ * Configure the scaling factor for using RobotDrive with motor controllers in a
+ * mode other than PercentVbus.
+ * @param maxOutput Multiplied with the output percentage computed by the drive
+ * functions.
+ */
+void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
+
+/**
+ * Set the number of the sync group for the motor controllers.  If the motor
+ * controllers are {@link CANJaguar}s,
+ * then they will all be added to this sync group, causing them to update their
+ * values at the same time.
+ *
+ * @param syncGroup the update group to add the motor controllers to
+ */
+void RobotDrive::SetCANJaguarSyncGroup(uint8_t syncGroup) {
+  m_syncGroup = syncGroup;
+}
+
+void RobotDrive::SetExpiration(float timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+float RobotDrive::GetExpiration() const {
+  return m_safetyHelper->GetExpiration();
+}
+
+bool RobotDrive::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+bool RobotDrive::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void RobotDrive::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void RobotDrive::GetDescription(std::ostringstream& desc) const {
+  desc << "RobotDrive";
+}
+
+void RobotDrive::StopMotor() {
+  if (m_frontLeftMotor != nullptr) m_frontLeftMotor->Disable();
+  if (m_frontRightMotor != nullptr) m_frontRightMotor->Disable();
+  if (m_rearLeftMotor != nullptr) m_rearLeftMotor->Disable();
+  if (m_rearRightMotor != nullptr) m_rearRightMotor->Disable();
+  m_safetyHelper->Feed();
+}
diff --git a/wpilibc/Athena/src/SPI.cpp b/wpilibc/Athena/src/SPI.cpp
new file mode 100644
index 0000000..a470597
--- /dev/null
+++ b/wpilibc/Athena/src/SPI.cpp
@@ -0,0 +1,303 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "SPI.h"
+
+#include "WPIErrors.h"
+#include "HAL/Digital.hpp"
+
+#include <string.h>
+
+/**
+ * Constructor
+ *
+ * @param SPIport the physical SPI port
+ */
+SPI::SPI(Port SPIport) {
+  m_port = SPIport;
+  int32_t status = 0;
+  spiInitialize(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  static int32_t instances = 0;
+  instances++;
+  HALReport(HALUsageReporting::kResourceType_SPI, instances);
+}
+
+/**
+ * Destructor.
+ */
+SPI::~SPI() { spiClose(m_port); }
+
+/**
+ * Configure the rate of the generated clock signal.
+ *
+ * The default value is 500,000Hz.
+ * The maximum value is 4,000,000Hz.
+ *
+ * @param hz	The clock rate in Hertz.
+ */
+void SPI::SetClockRate(double hz) { spiSetSpeed(m_port, hz); }
+
+/**
+ * Configure the order that bits are sent and received on the wire
+ * to be most significant bit first.
+ */
+void SPI::SetMSBFirst() {
+  m_msbFirst = true;
+  spiSetOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing,
+             (int)m_clk_idle_high);
+}
+
+/**
+ * Configure the order that bits are sent and received on the wire
+ * to be least significant bit first.
+ */
+void SPI::SetLSBFirst() {
+  m_msbFirst = false;
+  spiSetOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing,
+             (int)m_clk_idle_high);
+}
+
+/**
+ * Configure that the data is stable on the falling edge and the data
+ * changes on the rising edge.
+ */
+void SPI::SetSampleDataOnFalling() {
+  m_sampleOnTrailing = true;
+  spiSetOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing,
+             (int)m_clk_idle_high);
+}
+
+/**
+ * Configure that the data is stable on the rising edge and the data
+ * changes on the falling edge.
+ */
+void SPI::SetSampleDataOnRising() {
+  m_sampleOnTrailing = false;
+  spiSetOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing,
+             (int)m_clk_idle_high);
+}
+
+/**
+ * Configure the clock output line to be active low.
+ * This is sometimes called clock polarity high or clock idle high.
+ */
+void SPI::SetClockActiveLow() {
+  m_clk_idle_high = true;
+  spiSetOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing,
+             (int)m_clk_idle_high);
+}
+
+/**
+ * Configure the clock output line to be active high.
+ * This is sometimes called clock polarity low or clock idle low.
+ */
+void SPI::SetClockActiveHigh() {
+  m_clk_idle_high = false;
+  spiSetOpts(m_port, (int)m_msbFirst, (int)m_sampleOnTrailing,
+             (int)m_clk_idle_high);
+}
+
+/**
+ * Configure the chip select line to be active high.
+ */
+void SPI::SetChipSelectActiveHigh() {
+  int32_t status = 0;
+  spiSetChipSelectActiveHigh(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Configure the chip select line to be active low.
+ */
+void SPI::SetChipSelectActiveLow() {
+  int32_t status = 0;
+  spiSetChipSelectActiveLow(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Write data to the slave device.  Blocks until there is space in the
+ * output FIFO.
+ *
+ * If not running in output only mode, also saves the data received
+ * on the MISO input during the transfer into the receive FIFO.
+ */
+int32_t SPI::Write(uint8_t* data, uint8_t size) {
+  int32_t retVal = 0;
+  retVal = spiWrite(m_port, data, size);
+  return retVal;
+}
+
+/**
+ * Read a word from the receive FIFO.
+ *
+ * Waits for the current transfer to complete if the receive FIFO is empty.
+ *
+ * If the receive FIFO is empty, there is no active transfer, and initiate
+ * is false, errors.
+ *
+ * @param initiate	If true, this function pushes "0" into the
+ * 				    transmit buffer and initiates a transfer.
+ * 				    If false, this function assumes that data is
+ * 				    already in the receive FIFO from a previous
+ * write.
+ */
+int32_t SPI::Read(bool initiate, uint8_t* dataReceived, uint8_t size) {
+  int32_t retVal = 0;
+  if (initiate) {
+    auto dataToSend = new uint8_t[size];
+    memset(dataToSend, 0, size);
+    retVal = spiTransaction(m_port, dataToSend, dataReceived, size);
+  } else
+    retVal = spiRead(m_port, dataReceived, size);
+  return retVal;
+}
+
+/**
+ * Perform a simultaneous read/write transaction with the device
+ *
+ * @param dataToSend The data to be written out to the device
+ * @param dataReceived Buffer to receive data from the device
+ * @param size The length of the transaction, in bytes
+ */
+int32_t SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived,
+                         uint8_t size) {
+  int32_t retVal = 0;
+  retVal = spiTransaction(m_port, dataToSend, dataReceived, size);
+  return retVal;
+}
+
+/**
+ * Initialize the accumulator.
+ *
+ * @param period Time between reads
+ * @param cmd SPI command to send to request data
+ * @param xfer_size SPI transfer size, in bytes
+ * @param valid_mask Mask to apply to received data for validity checking
+ * @param valid_data After valid_mask is applied, required matching value for
+ *                   validity checking
+ * @param data_shift Bit shift to apply to received data to get actual data
+ *                   value
+ * @param data_size Size (in bits) of data field
+ * @param is_signed Is data field signed?
+ * @param big_endian Is device big endian?
+ */
+void SPI::InitAccumulator(double period, uint32_t cmd, uint8_t xfer_size,
+                          uint32_t valid_mask, uint32_t valid_value,
+                          uint8_t data_shift, uint8_t data_size, bool is_signed,
+                          bool big_endian) {
+  int32_t status = 0;
+  spiInitAccumulator(m_port, (uint32_t)(period * 1e6), cmd, xfer_size,
+                     valid_mask, valid_value, data_shift, data_size, is_signed,
+                     big_endian, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Frees the accumulator.
+ */
+void SPI::FreeAccumulator() {
+  int32_t status = 0;
+  spiFreeAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Resets the accumulator to zero.
+ */
+void SPI::ResetAccumulator() {
+  int32_t status = 0;
+  spiResetAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each value before it is added to the accumulator. This
+ * is used for the center value of devices like gyros and accelerometers to make integration work
+ * and to take the device offset into account when integrating.
+ */
+void SPI::SetAccumulatorCenter(int32_t center) {
+  int32_t status = 0;
+  spiSetAccumulatorCenter(m_port, center, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void SPI::SetAccumulatorDeadband(int32_t deadband) {
+  int32_t status = 0;
+  spiSetAccumulatorDeadband(m_port, deadband, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Read the last value read by the accumulator engine.
+ */
+int32_t SPI::GetAccumulatorLastValue() const {
+  int32_t status = 0;
+  int32_t retVal = spiGetAccumulatorLastValue(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t SPI::GetAccumulatorValue() const {
+  int32_t status = 0;
+  int64_t retVal = spiGetAccumulatorValue(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+uint32_t SPI::GetAccumulatorCount() const {
+  int32_t status = 0;
+  uint32_t retVal = spiGetAccumulatorCount(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the average of the accumulated value.
+ *
+ * @return The accumulated average value (value / count).
+ */
+double SPI::GetAccumulatorAverage() const {
+  int32_t status = 0;
+  double retVal = spiGetAccumulatorAverage(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count atomically.
+ * This can be used for averaging.
+ *
+ * @param value Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void SPI::GetAccumulatorOutput(int64_t &value, uint32_t &count) const {
+  int32_t status = 0;
+  spiGetAccumulatorOutput(m_port, &value, &count, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
diff --git a/wpilibc/Athena/src/SafePWM.cpp b/wpilibc/Athena/src/SafePWM.cpp
new file mode 100644
index 0000000..801e3ee
--- /dev/null
+++ b/wpilibc/Athena/src/SafePWM.cpp
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "SafePWM.h"
+
+/**
+ * Constructor for a SafePWM object taking a channel number.
+ * @param channel The PWM channel number 0-9 are on-board, 10-19 are on the MXP
+ * port
+ */
+SafePWM::SafePWM(uint32_t channel) : PWM(channel) {
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+  m_safetyHelper->SetSafetyEnabled(false);
+}
+
+/**
+ * Set the expiration time for the PWM object
+ * @param timeout The timeout (in seconds) for this motor object
+ */
+void SafePWM::SetExpiration(float timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+/**
+ * Return the expiration time for the PWM object.
+ * @returns The expiration time value.
+ */
+float SafePWM::GetExpiration() const { return m_safetyHelper->GetExpiration(); }
+
+/**
+ * Check if the PWM object is currently alive or stopped due to a timeout.
+ * @returns a bool value that is true if the motor has NOT timed out and should
+ * still
+ * be running.
+ */
+bool SafePWM::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+/**
+ * Stop the motor associated with this PWM object.
+ * This is called by the MotorSafetyHelper object when it has a timeout for this
+ * PWM and needs to
+ * stop it from running.
+ */
+void SafePWM::StopMotor() { SetRaw(kPwmDisabled); }
+
+/**
+ * Enable/disable motor safety for this device
+ * Turn on and off the motor safety option for this PWM object.
+ * @param enabled True if motor safety is enforced for this object
+ */
+void SafePWM::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+/**
+ * Check if motor safety is enabled for this object
+ * @returns True if motor safety is enforced for this object
+ */
+bool SafePWM::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void SafePWM::GetDescription(std::ostringstream& desc) const {
+  desc << "PWM " << GetChannel();
+}
+
+/**
+ * Feed the MotorSafety timer when setting the speed.
+ * This method is called by the subclass motor whenever it updates its speed,
+ * thereby reseting
+ * the timeout value.
+ * @param speed Value to pass to the PWM class
+ */
+void SafePWM::SetSpeed(float speed) {
+  PWM::SetSpeed(speed);
+  m_safetyHelper->Feed();
+}
diff --git a/wpilibc/Athena/src/SampleRobot.cpp b/wpilibc/Athena/src/SampleRobot.cpp
new file mode 100644
index 0000000..37b134f
--- /dev/null
+++ b/wpilibc/Athena/src/SampleRobot.cpp
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "SampleRobot.h"
+
+#include "DriverStation.h"
+#include "Timer.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "LiveWindow/LiveWindow.h"
+#include "networktables/NetworkTable.h"
+
+SampleRobot::SampleRobot() : m_robotMainOverridden(true) {}
+
+/**
+ * Robot-wide initialization code should go here.
+ *
+ * Users should override this method for default Robot-wide initialization which
+ * will be called when the robot is first powered on. It will be called exactly
+ * one time.
+ *
+ * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+ * indicators will be off until RobotInit() exits. Code in RobotInit() that
+ * waits for enable will cause the robot to never indicate that the code is
+ * ready, causing the robot to be bypassed in a match.
+ */
+void SampleRobot::RobotInit() {
+  printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Disabled should go here.
+ * Programmers should override this method to run code that should run while the
+ * field is
+ * disabled.
+ */
+void SampleRobot::Disabled() {
+  printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Autonomous should go here.
+ * Programmers should override this method to run code that should run while the
+ * field is
+ * in the autonomous period. This will be called once each time the robot enters
+ * the
+ * autonomous state.
+ */
+void SampleRobot::Autonomous() {
+  printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Operator control (tele-operated) code should go here.
+ * Programmers should override this method to run code that should run while the
+ * field is
+ * in the Operator Control (tele-operated) period. This is called once each time
+ * the robot
+ * enters the teleop state.
+ */
+void SampleRobot::OperatorControl() {
+  printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Test program should go here.
+ * Programmers should override this method to run code that executes while the
+ * robot is
+ * in test mode. This will be called once whenever the robot enters test mode
+ */
+void SampleRobot::Test() {
+  printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Robot main program for free-form programs.
+ *
+ * This should be overridden by user subclasses if the intent is to not use the
+ * Autonomous() and
+ * OperatorControl() methods. In that case, the program is responsible for
+ * sensing when to run
+ * the autonomous and operator control functions in their program.
+ *
+ * This method will be called immediately after the constructor is called. If it
+ * has not been
+ * overridden by a user subclass (i.e. the default version runs), then the
+ * Autonomous() and
+ * OperatorControl() methods will be called.
+ */
+void SampleRobot::RobotMain() { m_robotMainOverridden = false; }
+
+/**
+ * Start a competition.
+ * This code needs to track the order of the field starting to ensure that
+ * everything happens
+ * in the right order. Repeatedly run the correct method, either Autonomous or
+ * OperatorControl
+ * or Test when the robot is enabled. After running the correct method, wait for
+ * some state to
+ * change, either the other mode starts or the robot is disabled. Then go back
+ * and wait for the
+ * robot to be enabled again.
+ */
+void SampleRobot::StartCompetition() {
+  LiveWindow *lw = LiveWindow::GetInstance();
+
+  HALReport(HALUsageReporting::kResourceType_Framework,
+            HALUsageReporting::kFramework_Sample);
+
+  SmartDashboard::init();
+  NetworkTable::GetTable("LiveWindow")
+      ->GetSubTable("~STATUS~")
+      ->PutBoolean("LW Enabled", false);
+
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HALNetworkCommunicationObserveUserProgramStarting();
+
+  RobotMain();
+
+  if (!m_robotMainOverridden) {
+    // first and one-time initialization
+    lw->SetEnabled(false);
+
+    while (true) {
+      if (IsDisabled()) {
+        m_ds.InDisabled(true);
+        Disabled();
+        m_ds.InDisabled(false);
+        while (IsDisabled()) m_ds.WaitForData();
+      } else if (IsAutonomous()) {
+        m_ds.InAutonomous(true);
+        Autonomous();
+        m_ds.InAutonomous(false);
+        while (IsAutonomous() && IsEnabled()) m_ds.WaitForData();
+      } else if (IsTest()) {
+        lw->SetEnabled(true);
+        m_ds.InTest(true);
+        Test();
+        m_ds.InTest(false);
+        while (IsTest() && IsEnabled()) m_ds.WaitForData();
+        lw->SetEnabled(false);
+      } else {
+        m_ds.InOperatorControl(true);
+        OperatorControl();
+        m_ds.InOperatorControl(false);
+        while (IsOperatorControl() && IsEnabled()) m_ds.WaitForData();
+      }
+    }
+  }
+}
diff --git a/wpilibc/Athena/src/SensorBase.cpp b/wpilibc/Athena/src/SensorBase.cpp
new file mode 100644
index 0000000..05f9f4f
--- /dev/null
+++ b/wpilibc/Athena/src/SensorBase.cpp
@@ -0,0 +1,183 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "SensorBase.h"
+
+#include "NetworkCommunication/LoadOut.h"
+#include "WPIErrors.h"
+#include "HAL/HAL.hpp"
+#include "HAL/Port.h"
+
+const uint32_t SensorBase::kDigitalChannels;
+const uint32_t SensorBase::kAnalogInputs;
+const uint32_t SensorBase::kSolenoidChannels;
+const uint32_t SensorBase::kSolenoidModules;
+const uint32_t SensorBase::kPwmChannels;
+const uint32_t SensorBase::kRelayChannels;
+const uint32_t SensorBase::kPDPChannels;
+const uint32_t SensorBase::kChassisSlots;
+SensorBase* SensorBase::m_singletonList = nullptr;
+
+static bool portsInitialized = false;
+void* SensorBase::m_digital_ports[kDigitalChannels];
+void* SensorBase::m_relay_ports[kRelayChannels];
+void* SensorBase::m_pwm_ports[kPwmChannels];
+
+/**
+ * Creates an instance of the sensor base and gets an FPGA handle
+ */
+SensorBase::SensorBase() {
+  if (!portsInitialized) {
+    for (uint32_t i = 0; i < kDigitalChannels; i++) {
+      void* port = getPort(i);
+      int32_t status = 0;
+      m_digital_ports[i] = initializeDigitalPort(port, &status);
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      freePort(port);
+    }
+
+    for (uint32_t i = 0; i < kRelayChannels; i++) {
+      void* port = getPort(i);
+      int32_t status = 0;
+      m_relay_ports[i] = initializeDigitalPort(port, &status);
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      freePort(port);
+    }
+
+    for (uint32_t i = 0; i < kPwmChannels; i++) {
+      void* port = getPort(i);
+      int32_t status = 0;
+      m_pwm_ports[i] = initializeDigitalPort(port, &status);
+      wpi_setErrorWithContext(status, getHALErrorMessage(status));
+      freePort(port);
+    }
+  }
+}
+
+/**
+ * Add sensor to the singleton list.
+ * Add this sensor to the list of singletons that need to be deleted when
+ * the robot program exits. Each of the sensors on this list are singletons,
+ * that is they aren't allocated directly with new, but instead are allocated
+ * by the static GetInstance method. As a result, they are never deleted when
+ * the program exits. Consequently these sensors may still be holding onto
+ * resources and need to have their destructors called at the end of the
+ * program.
+ */
+void SensorBase::AddToSingletonList() {
+  m_nextSingleton = m_singletonList;
+  m_singletonList = this;
+}
+
+/**
+ * Delete all the singleton classes on the list.
+ * All the classes that were allocated as singletons need to be deleted so
+ * their resources can be freed.
+ */
+void SensorBase::DeleteSingletons() {
+  for (SensorBase* next = m_singletonList; next != nullptr;) {
+    SensorBase* tmp = next;
+    next = next->m_nextSingleton;
+    delete tmp;
+  }
+  m_singletonList = nullptr;
+}
+
+/**
+ * Check that the solenoid module number is valid.
+ *
+ * @return Solenoid module is valid and present
+ */
+bool SensorBase::CheckSolenoidModule(uint8_t moduleNumber) {
+  if (moduleNumber < 64) return true;
+  return false;
+}
+
+/**
+ * Check that the digital channel number is valid.
+ * Verify that the channel number is one of the legal channel numbers. Channel
+ * numbers are
+ * 1-based.
+ *
+ * @return Digital channel is valid
+ */
+bool SensorBase::CheckDigitalChannel(uint32_t channel) {
+  if (channel < kDigitalChannels) return true;
+  return false;
+}
+
+/**
+ * Check that the digital channel number is valid.
+ * Verify that the channel number is one of the legal channel numbers. Channel
+ * numbers are
+ * 1-based.
+ *
+ * @return Relay channel is valid
+ */
+bool SensorBase::CheckRelayChannel(uint32_t channel) {
+  if (channel < kRelayChannels) return true;
+  return false;
+}
+
+/**
+ * Check that the digital channel number is valid.
+ * Verify that the channel number is one of the legal channel numbers. Channel
+ * numbers are
+ * 1-based.
+ *
+ * @return PWM channel is valid
+ */
+bool SensorBase::CheckPWMChannel(uint32_t channel) {
+  if (channel < kPwmChannels) return true;
+  return false;
+}
+
+/**
+ * Check that the analog input number is value.
+ * Verify that the analog input number is one of the legal channel numbers.
+ * Channel numbers
+ * are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool SensorBase::CheckAnalogInput(uint32_t channel) {
+  if (channel < kAnalogInputs) return true;
+  return false;
+}
+
+/**
+ * Check that the analog output number is valid.
+ * Verify that the analog output number is one of the legal channel numbers.
+ * Channel numbers
+ * are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool SensorBase::CheckAnalogOutput(uint32_t channel) {
+  if (channel < kAnalogOutputs) return true;
+  return false;
+}
+
+/**
+ * Verify that the solenoid channel number is within limits.
+ *
+ * @return Solenoid channel is valid
+ */
+bool SensorBase::CheckSolenoidChannel(uint32_t channel) {
+  if (channel < kSolenoidChannels) return true;
+  return false;
+}
+
+/**
+ * Verify that the power distribution channel number is within limits.
+ *
+ * @return PDP channel is valid
+ */
+bool SensorBase::CheckPDPChannel(uint32_t channel) {
+  if (channel < kPDPChannels) return true;
+  return false;
+}
diff --git a/wpilibc/Athena/src/SerialPort.cpp b/wpilibc/Athena/src/SerialPort.cpp
new file mode 100644
index 0000000..c4e259a
--- /dev/null
+++ b/wpilibc/Athena/src/SerialPort.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "SerialPort.h"
+
+#include "HAL/HAL.hpp"
+#include <stdarg.h>
+
+// static ViStatus _VI_FUNCH ioCompleteHandler (ViSession vi, ViEventType
+// eventType, ViEvent event, ViAddr userHandle);
+
+/**
+ * Create an instance of a Serial Port class.
+ *
+ * @param baudRate The baud rate to configure the serial port.
+ * @param port The physical port to use
+ * @param dataBits The number of data bits per transfer.  Valid values are
+ * between 5 and 8 bits.
+ * @param parity Select the type of parity checking to use.
+ * @param stopBits The number of stop bits to use as defined by the enum
+ * StopBits.
+ */
+SerialPort::SerialPort(uint32_t baudRate, Port port, uint8_t dataBits,
+                       SerialPort::Parity parity, SerialPort::StopBits stopBits)
+{
+  int32_t status = 0;
+
+  m_port = port;
+
+  serialInitializePort(port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  serialSetBaudRate(port, baudRate, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  serialSetDataBits(port, dataBits, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  serialSetParity(port, parity, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  serialSetStopBits(port, stopBits, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  // Set the default timeout to 5 seconds.
+  SetTimeout(5.0f);
+
+  // Don't wait until the buffer is full to transmit.
+  SetWriteBufferMode(kFlushOnAccess);
+
+  EnableTermination();
+
+  // viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler,
+  // this);
+  // viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_nullptr);
+
+  HALReport(HALUsageReporting::kResourceType_SerialPort, 0);
+}
+
+/**
+ * Destructor.
+ */
+SerialPort::~SerialPort() {
+  int32_t status = 0;
+  serialClose(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Set the type of flow control to enable on this port.
+ *
+ * By default, flow control is disabled.
+ */
+void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
+  int32_t status = 0;
+  serialSetFlowControl(m_port, flowControl, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Enable termination and specify the termination character.
+ *
+ * Termination is currently only implemented for receive.
+ * When the the terminator is recieved, the Read() or Scanf() will return
+ *   fewer bytes than requested, stopping after the terminator.
+ *
+ * @param terminator The character to use for termination.
+ */
+void SerialPort::EnableTermination(char terminator) {
+  int32_t status = 0;
+  serialEnableTermination(m_port, terminator, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Disable termination behavior.
+ */
+void SerialPort::DisableTermination() {
+  int32_t status = 0;
+  serialDisableTermination(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Get the number of bytes currently available to read from the serial port.
+ *
+ * @return The number of bytes available to read
+ */
+int32_t SerialPort::GetBytesReceived() {
+  int32_t status = 0;
+  int32_t retVal = serialGetBytesReceived(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read raw bytes out of the buffer.
+ *
+ * @param buffer Pointer to the buffer to store the bytes in.
+ * @param count The maximum number of bytes to read.
+ * @return The number of bytes actually read into the buffer.
+ */
+uint32_t SerialPort::Read(char *buffer, int32_t count) {
+  int32_t status = 0;
+  int32_t retVal = serialRead(m_port, buffer, count, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Write raw bytes to the buffer.
+ *
+ * @param buffer Pointer to the buffer to read the bytes from.
+ * @param count The maximum number of bytes to write.
+ * @return The number of bytes actually written into the port.
+ */
+uint32_t SerialPort::Write(const std::string &buffer, int32_t count) {
+  int32_t status = 0;
+  int32_t retVal = serialWrite(m_port, buffer.c_str(), count, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Configure the timeout of the serial port.
+ *
+ * This defines the timeout for transactions with the hardware.
+ * It will affect reads and very large writes.
+ *
+ * @param timeout The number of seconds to to wait for I/O.
+ */
+void SerialPort::SetTimeout(float timeout) {
+  int32_t status = 0;
+  serialSetTimeout(m_port, timeout, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Specify the size of the input buffer.
+ *
+ * Specify the amount of data that can be stored before data
+ * from the device is returned to Read or Scanf.  If you want
+ * data that is recieved to be returned immediately, set this to 1.
+ *
+ * It the buffer is not filled before the read timeout expires, all
+ * data that has been received so far will be returned.
+ *
+ * @param size The read buffer size.
+ */
+void SerialPort::SetReadBufferSize(uint32_t size) {
+  int32_t status = 0;
+  serialSetReadBufferSize(m_port, size, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Specify the size of the output buffer.
+ *
+ * Specify the amount of data that can be stored before being
+ * transmitted to the device.
+ *
+ * @param size The write buffer size.
+ */
+void SerialPort::SetWriteBufferSize(uint32_t size) {
+  int32_t status = 0;
+  serialSetWriteBufferSize(m_port, size, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Specify the flushing behavior of the output buffer.
+ *
+ * When set to kFlushOnAccess, data is synchronously written to the serial port
+ *   after each call to either Printf() or Write().
+ *
+ * When set to kFlushWhenFull, data will only be written to the serial port when
+ *   the buffer is full or when Flush() is called.
+ *
+ * @param mode The write buffer mode.
+ */
+void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
+  int32_t status = 0;
+  serialSetWriteMode(m_port, mode, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Force the output buffer to be written to the port.
+ *
+ * This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
+ * flush before the buffer is full.
+ */
+void SerialPort::Flush() {
+  int32_t status = 0;
+  serialFlush(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Reset the serial port driver to a known state.
+ *
+ * Empty the transmit and receive buffers in the device and formatted I/O.
+ */
+void SerialPort::Reset() {
+  int32_t status = 0;
+  serialClear(m_port, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
diff --git a/wpilibc/Athena/src/Servo.cpp b/wpilibc/Athena/src/Servo.cpp
new file mode 100644
index 0000000..4300cc4
--- /dev/null
+++ b/wpilibc/Athena/src/Servo.cpp
@@ -0,0 +1,132 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Servo.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+constexpr float Servo::kMaxServoAngle;
+constexpr float Servo::kMinServoAngle;
+
+constexpr float Servo::kDefaultMaxServoPWM;
+constexpr float Servo::kDefaultMinServoPWM;
+
+/**
+ * @param channel The PWM channel to which the servo is attached. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+Servo::Servo(uint32_t channel) : SafePWM(channel) {
+  // Set minimum and maximum PWM values supported by the servo
+  SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
+
+  // Assign defaults for period multiplier for the servo PWM control signal
+  SetPeriodMultiplier(kPeriodMultiplier_4X);
+
+  //	printf("Done initializing servo %d\n", channel);
+}
+
+Servo::~Servo() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+/**
+ * Set the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to
+ * full right.
+ *
+ * @param value Position from 0.0 to 1.0.
+ */
+void Servo::Set(float value) { SetPosition(value); }
+
+/**
+ * Set the servo to offline.
+ *
+ * Set the servo raw value to 0 (undriven)
+ */
+void Servo::SetOffline() { SetRaw(0); }
+
+/**
+ * Get the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to
+ * full right.
+ *
+ * @return Position from 0.0 to 1.0.
+ */
+float Servo::Get() const { return GetPosition(); }
+
+/**
+ * Set the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big
+ * assumption, need to test).
+ *
+ * Servo angles that are out of the supported range of the servo simply
+ * "saturate" in that direction
+ * In other words, if the servo has a range of (X degrees to Y degrees) than
+ * angles of less than X
+ * result in an angle of X being set and angles of more than Y degrees result in
+ * an angle of Y being set.
+ *
+ * @param degrees The angle in degrees to set the servo.
+ */
+void Servo::SetAngle(float degrees) {
+  if (degrees < kMinServoAngle) {
+    degrees = kMinServoAngle;
+  } else if (degrees > kMaxServoAngle) {
+    degrees = kMaxServoAngle;
+  }
+
+  SetPosition(((float)(degrees - kMinServoAngle)) / GetServoAngleRange());
+}
+
+/**
+ * Get the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big
+ * assumption, need to test).
+ * @return The angle in degrees to which the servo is set.
+ */
+float Servo::GetAngle() const {
+  return (float)GetPosition() * GetServoAngleRange() + kMinServoAngle;
+}
+
+void Servo::ValueChanged(ITable* source, llvm::StringRef key,
+                         std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsDouble()) return;
+  Set(value->GetDouble());
+}
+
+void Servo::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+void Servo::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void Servo::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string Servo::GetSmartDashboardType() const { return "Servo"; }
+
+void Servo::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Servo::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/Solenoid.cpp b/wpilibc/Athena/src/Solenoid.cpp
new file mode 100644
index 0000000..5174f98
--- /dev/null
+++ b/wpilibc/Athena/src/Solenoid.cpp
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Solenoid.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+#include <sstream>
+
+/**
+ * Constructor using the default PCM ID (0).
+ *
+ * @param channel The channel on the PCM to control (0..7).
+ */
+Solenoid::Solenoid(uint32_t channel)
+    : Solenoid(GetDefaultSolenoidModule(), channel) {}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The CAN ID of the PCM the solenoid is attached to
+ * @param channel The channel on the PCM to control (0..7).
+ */
+Solenoid::Solenoid(uint8_t moduleNumber, uint32_t channel)
+    : SolenoidBase(moduleNumber), m_channel(channel) {
+  std::stringstream buf;
+  if (!CheckSolenoidModule(m_moduleNumber)) {
+    buf << "Solenoid Module " << m_moduleNumber;
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf.str());
+    return;
+  }
+  if (!CheckSolenoidChannel(m_channel)) {
+    buf << "Solenoid Module " << m_channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+  Resource::CreateResourceObject(m_allocated, m_maxModules * m_maxPorts);
+  buf << "Solenoid " << m_channel << " (Module: " << m_moduleNumber << ")";
+  if (m_allocated->Allocate(m_moduleNumber * kSolenoidChannels + m_channel,
+                            buf.str()) ==
+      std::numeric_limits<uint32_t>::max()) {
+    CloneError(*m_allocated);
+    return;
+  }
+
+  LiveWindow::GetInstance()->AddActuator("Solenoid", m_moduleNumber, m_channel,
+                                         this);
+  HALReport(HALUsageReporting::kResourceType_Solenoid, m_channel,
+            m_moduleNumber);
+}
+
+/**
+ * Destructor.
+ */
+Solenoid::~Solenoid() {
+  if (CheckSolenoidModule(m_moduleNumber)) {
+    m_allocated->Free(m_moduleNumber * kSolenoidChannels + m_channel);
+  }
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param on Turn the solenoid output off or on.
+ */
+void Solenoid::Set(bool on) {
+  if (StatusIsFatal()) return;
+  uint8_t value = on ? 0xFF : 0x00;
+  uint8_t mask = 1 << m_channel;
+
+  SolenoidBase::Set(value, mask, m_moduleNumber);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+bool Solenoid::Get() const {
+  if (StatusIsFatal()) return false;
+  uint8_t value = GetAll(m_moduleNumber) & (1 << m_channel);
+  return (value != 0);
+}
+/**
+ * Check if solenoid is blacklisted.
+ * 		If a solenoid is shorted, it is added to the blacklist and
+ * 		disabled until power cycle, or until faults are cleared.
+ * 		@see ClearAllPCMStickyFaults()
+ *
+ * @return If solenoid is disabled due to short.
+ */
+bool Solenoid::IsBlackListed() const {
+  int value = GetPCMSolenoidBlackList(m_moduleNumber) & (1 << m_channel);
+  return (value != 0);
+}
+
+void Solenoid::ValueChanged(ITable* source, llvm::StringRef key,
+                            std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsBoolean()) return;
+  Set(value->GetBoolean());
+}
+
+void Solenoid::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutBoolean("Value", Get());
+  }
+}
+
+void Solenoid::StartLiveWindowMode() {
+  Set(false);
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void Solenoid::StopLiveWindowMode() {
+  Set(false);
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string Solenoid::GetSmartDashboardType() const { return "Solenoid"; }
+
+void Solenoid::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Solenoid::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/SolenoidBase.cpp b/wpilibc/Athena/src/SolenoidBase.cpp
new file mode 100644
index 0000000..dfdf1eb
--- /dev/null
+++ b/wpilibc/Athena/src/SolenoidBase.cpp
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "SolenoidBase.h"
+
+void* SolenoidBase::m_ports[m_maxModules][m_maxPorts];
+std::unique_ptr<Resource> SolenoidBase::m_allocated;
+
+/**
+ * Constructor
+ *
+ * @param moduleNumber The CAN PCM ID.
+ */
+SolenoidBase::SolenoidBase(uint8_t moduleNumber)
+    : m_moduleNumber(moduleNumber) {
+  for (uint32_t i = 0; i < kSolenoidChannels; i++) {
+    void* port = getPortWithModule(moduleNumber, i);
+    int32_t status = 0;
+    SolenoidBase::m_ports[moduleNumber][i] =
+        initializeSolenoidPort(port, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+    freePort(port);
+  }
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param value The value you want to set on the module.
+ * @param mask The channels you want to be affected.
+ */
+void SolenoidBase::Set(uint8_t value, uint8_t mask, int module) {
+  int32_t status = 0;
+  for (int i = 0; i < m_maxPorts; i++) {
+    uint8_t local_mask = 1 << i;
+    if (mask & local_mask)
+      setSolenoid(m_ports[module][i], value & local_mask, &status);
+  }
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+}
+
+/**
+ * Read all 8 solenoids as a single byte
+ *
+ * @return The current value of all 8 solenoids on the module.
+ */
+uint8_t SolenoidBase::GetAll(int module) const {
+  uint8_t value = 0;
+  int32_t status = 0;
+  value = getAllSolenoids(m_ports[module][0], &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+  return value;
+}
+/**
+ * Reads complete solenoid blacklist for all 8 solenoids as a single byte.
+ *
+ * 		If a solenoid is shorted, it is added to the blacklist and
+ * 		disabled until power cycle, or until faults are cleared.
+ * 		@see ClearAllPCMStickyFaults()
+ *
+ * @return The solenoid blacklist of all 8 solenoids on the module.
+ */
+uint8_t SolenoidBase::GetPCMSolenoidBlackList(int module) const {
+  int32_t status = 0;
+  return getPCMSolenoidBlackList(m_ports[module][0], &status);
+}
+/**
+ * @return true if PCM sticky fault is set : The common
+ * 			highside solenoid voltage rail is too low,
+ * 	 		most likely a solenoid channel is shorted.
+ */
+bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) const {
+  int32_t status = 0;
+  return getPCMSolenoidVoltageStickyFault(m_ports[module][0], &status);
+}
+/**
+ * @return true if PCM is in fault state : The common
+ * 			highside solenoid voltage rail is too low,
+ * 	 		most likely a solenoid channel is shorted.
+ */
+bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) const {
+  int32_t status = 0;
+  return getPCMSolenoidVoltageFault(m_ports[module][0], &status);
+}
+/**
+ * Clear ALL sticky faults inside PCM that Compressor is wired to.
+ *
+ * If a sticky fault is set, then it will be persistently cleared.  Compressor
+ * drive
+ * 		maybe momentarily disable while flags are being cleared. Care
+ * should be
+ * 		taken to not call this too frequently, otherwise normal
+ * compressor
+ * 		functionality may be prevented.
+ *
+ * If no sticky faults are set then this call will have no effect.
+ */
+void SolenoidBase::ClearAllPCMStickyFaults(int module) {
+  int32_t status = 0;
+  return clearAllPCMStickyFaults_sol(m_ports[module][0], &status);
+}
diff --git a/wpilibc/Athena/src/Talon.cpp b/wpilibc/Athena/src/Talon.cpp
new file mode 100644
index 0000000..dc1cf3b
--- /dev/null
+++ b/wpilibc/Athena/src/Talon.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Talon.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Constructor for a Talon (original or Talon SR)
+ * @param channel The PWM channel number that the Talon is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+Talon::Talon(uint32_t channel) : SafePWM(channel) {
+  /* Note that the Talon uses the following bounds for PWM values. These values
+   * should work reasonably well for most controllers, but if users experience
+   * issues such as asymmetric behavior around the deadband or inability to
+   * saturate the controller in either direction, calibration is recommended.
+   * The calibration procedure can be found in the Talon User Manual available
+   * from CTRE.
+   *
+   *   2.037ms = full "forward"
+   *   1.539ms = the "high end" of the deadband range
+   *   1.513ms = center of the deadband range (off)
+   *   1.487ms = the "low end" of the deadband range
+   *   0.989ms = full "reverse"
+   */
+  SetBounds(2.037, 1.539, 1.513, 1.487, .989);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  HALReport(HALUsageReporting::kResourceType_Talon, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void Talon::Set(float speed, uint8_t syncGroup) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float Talon::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Talon::Disable() { SetRaw(kPwmDisabled); }
+
+/**
+* common interface for inverting direction of a speed controller
+* @param isInverted The state of inversion true is inverted
+*/
+void Talon::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool Talon::GetInverted() const { return m_isInverted; }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void Talon::PIDWrite(float output) { Set(output); }
diff --git a/wpilibc/Athena/src/TalonSRX.cpp b/wpilibc/Athena/src/TalonSRX.cpp
new file mode 100644
index 0000000..07438c4
--- /dev/null
+++ b/wpilibc/Athena/src/TalonSRX.cpp
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "TalonSRX.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Construct a TalonSRX connected via PWM
+ * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+TalonSRX::TalonSRX(uint32_t channel) : SafePWM(channel) {
+  /* Note that the TalonSRX uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the TalonSRX User
+   * Manual available from Cross The Road Electronics.
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  HALReport(HALUsageReporting::kResourceType_TalonSRX, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void TalonSRX::Set(float speed, uint8_t syncGroup) { SetSpeed(speed); }
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float TalonSRX::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void TalonSRX::Disable() { SetRaw(kPwmDisabled); }
+
+/**
+* Common interface for inverting direction of a speed controller.
+* @param isInverted The state of inversion, true is inverted.
+*/
+void TalonSRX::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool TalonSRX::GetInverted() const { return m_isInverted; }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void TalonSRX::PIDWrite(float output) { Set(output); }
diff --git a/wpilibc/Athena/src/Task.cpp b/wpilibc/Athena/src/Task.cpp
new file mode 100644
index 0000000..9157dca
--- /dev/null
+++ b/wpilibc/Athena/src/Task.cpp
@@ -0,0 +1,114 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Task.h"
+
+#include "WPIErrors.h"
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+
+#ifndef OK
+#define OK 0
+#endif /* OK */
+#ifndef ERROR
+#define ERROR (-1)
+#endif /* ERROR */
+
+const uint32_t Task::kDefaultPriority;
+
+Task& Task::operator=(Task&& task) {
+  m_thread.swap(task.m_thread);
+  m_taskName = std::move(task.m_taskName);
+
+  return *this;
+}
+
+Task::~Task() {
+  if (m_thread.joinable()) {
+    std::cout << "[HAL] Exited task " << m_taskName << std::endl;
+  }
+}
+
+bool Task::joinable() const noexcept {
+  return m_thread.joinable();
+}
+
+void Task::join() {
+  m_thread.join();
+}
+
+void Task::detach() {
+  m_thread.detach();
+}
+
+std::thread::id Task::get_id() const noexcept {
+  return m_thread.get_id();
+}
+
+std::thread::native_handle_type Task::native_handle() {
+  return m_thread.native_handle();
+}
+
+/**
+ * Verifies a task still exists.
+ *
+ * @return true on success.
+ */
+bool Task::Verify() {
+  TASK id = (TASK)m_thread.native_handle();
+  return verifyTaskID(id) == OK;
+}
+
+/**
+ * Gets the priority of a task.
+ *
+ * @return task priority or 0 if an error occured
+ */
+int32_t Task::GetPriority() {
+  int priority;
+  auto id = m_thread.native_handle();
+  if (HandleError(getTaskPriority(&id, &priority)))
+    return priority;
+  else
+    return 0;
+}
+
+/**
+ * This routine changes a task's priority to a specified priority.
+ * Priorities range from 1, the lowest priority, to 99, the highest priority.
+ * Default task priority is 60.
+ *
+ * @param priority The priority at which the internal thread should run.
+ * @return true on success.
+ */
+bool Task::SetPriority(int32_t priority) {
+  auto id = m_thread.native_handle();
+  return HandleError(setTaskPriority(&id, priority));
+}
+
+/**
+ * Returns the name of the task.
+ *
+ * @return The name of the task.
+ */
+std::string Task::GetName() const { return m_taskName; }
+
+/**
+ * Handles errors generated by task related code.
+ */
+bool Task::HandleError(STATUS results) {
+  if (results != ERROR) return true;
+  int errsv = errno;
+  if (errsv == HAL_taskLib_ILLEGAL_PRIORITY) {
+    wpi_setWPIErrorWithContext(TaskPriorityError, m_taskName.c_str());
+  } else {
+    printf("ERROR: errno=%i", errsv);
+    wpi_setWPIErrorWithContext(TaskError, m_taskName.c_str());
+  }
+  return false;
+}
diff --git a/wpilibc/Athena/src/Timer.cpp b/wpilibc/Athena/src/Timer.cpp
new file mode 100644
index 0000000..53631e7
--- /dev/null
+++ b/wpilibc/Athena/src/Timer.cpp
@@ -0,0 +1,177 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Timer.h"
+
+#include <time.h>
+
+#include "HAL/HAL.hpp"
+#include "Utility.h"
+#include <iostream>
+
+/**
+ * Pause the task for a specified time.
+ *
+ * Pause the execution of the program for a specified period of time given in
+ * seconds.
+ * Motors will continue to run at their last assigned values, and sensors will
+ * continue to
+ * update. Only the task containing the wait will pause until the wait time is
+ * expired.
+ *
+ * @param seconds Length of time to pause, in seconds.
+ */
+void Wait(double seconds) {
+  if (seconds < 0.0) return;
+  delaySeconds(seconds);
+}
+
+/**
+ * Return the FPGA system clock time in seconds.
+ * This is deprecated and just forwards to Timer::GetFPGATimestamp().
+ * @return Robot running time in seconds.
+ */
+double GetClock() { return Timer::GetFPGATimestamp(); }
+
+/**
+ * @brief Gives real-time clock system time with nanosecond resolution
+ * @return The time, just in case you want the robot to start autonomous at 8pm
+ * on Saturday.
+*/
+double GetTime() {
+  struct timespec tp;
+
+  clock_gettime(CLOCK_REALTIME, &tp);
+  double realTime = (double)tp.tv_sec + (double)((double)tp.tv_nsec * 1e-9);
+
+  return (realTime);
+}
+
+//for compatibility with msvc12--see C2864
+const double Timer::kRolloverTime = (1ll << 32) / 1e6;
+/**
+ * Create a new timer object.
+ *
+ * Create a new timer object and reset the time to zero. The timer is initially
+ * not running and
+ * must be started.
+ */
+Timer::Timer() {
+  // Creates a semaphore to control access to critical regions.
+  // Initially 'open'
+  Reset();
+}
+
+/**
+ * Get the current time from the timer. If the clock is running it is derived
+ * from
+ * the current system clock the start time stored in the timer class. If the
+ * clock
+ * is not running, then return the time when it was last stopped.
+ *
+ * @return Current time value for this timer in seconds
+ */
+double Timer::Get() const {
+  double result;
+  double currentTime = GetFPGATimestamp();
+
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  if (m_running) {
+    // If the current time is before the start time, then the FPGA clock
+    // rolled over.  Compensate by adding the ~71 minutes that it takes
+    // to roll over to the current time.
+    if (currentTime < m_startTime) {
+      currentTime += kRolloverTime;
+    }
+
+    result = (currentTime - m_startTime) + m_accumulatedTime;
+  } else {
+    result = m_accumulatedTime;
+  }
+
+  return result;
+}
+
+/**
+ * Reset the timer by setting the time to 0.
+ *
+ * Make the timer startTime the current time so new requests will be relative to
+ * now
+ */
+void Timer::Reset() {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  m_accumulatedTime = 0;
+  m_startTime = GetFPGATimestamp();
+}
+
+/**
+ * Start the timer running.
+ * Just set the running flag to true indicating that all time requests should be
+ * relative to the system clock.
+ */
+void Timer::Start() {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  if (!m_running) {
+    m_startTime = GetFPGATimestamp();
+    m_running = true;
+  }
+}
+
+/**
+ * Stop the timer.
+ * This computes the time as of now and clears the running flag, causing all
+ * subsequent time requests to be read from the accumulated time rather than
+ * looking at the system clock.
+ */
+void Timer::Stop() {
+  double temp = Get();
+
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  if (m_running) {
+    m_accumulatedTime = temp;
+    m_running = false;
+  }
+}
+
+/**
+ * Check if the period specified has passed and if it has, advance the start
+ * time by that period. This is useful to decide if it's time to do periodic
+ * work without drifting later by the time it took to get around to checking.
+ *
+ * @param period The period to check for (in seconds).
+ * @return True if the period has passed.
+ */
+bool Timer::HasPeriodPassed(double period) {
+  if (Get() > period) {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    // Advance the start time by the period.
+    m_startTime += period;
+    // Don't set it to the current time... we want to avoid drift.
+    return true;
+  }
+  return false;
+}
+
+/**
+ * Return the FPGA system clock time in seconds.
+ *
+ * Return the time from the FPGA hardware clock in seconds since the FPGA
+ * started.
+ * Rolls over after 71 minutes.
+ * @returns Robot running time in seconds.
+ */
+double Timer::GetFPGATimestamp() {
+  // FPGA returns the timestamp in microseconds
+  // Call the helper GetFPGATime() in Utility.cpp
+  return GetFPGATime() * 1.0e-6;
+}
+
+// Internal function that reads the PPC timestamp counter.
+extern "C" {
+uint32_t niTimestamp32(void);
+uint64_t niTimestamp64(void);
+}
diff --git a/wpilibc/Athena/src/USBCamera.cpp b/wpilibc/Athena/src/USBCamera.cpp
new file mode 100644
index 0000000..0c57d85
--- /dev/null
+++ b/wpilibc/Athena/src/USBCamera.cpp
@@ -0,0 +1,323 @@
+#include "USBCamera.h"
+
+#include "Utility.h"
+
+#include <regex>
+#include <chrono>
+#include <thread>
+#include <memory>
+#include <iostream>
+#include <iomanip>
+
+// This macro expands the given imaq function to ensure that it is called and
+// properly checked for an error, calling the wpi_setImaqErrorWithContext
+// macro
+// To call it, just give the name of the function and the arguments
+#define SAFE_IMAQ_CALL(funName, ...)                \
+  {                                                 \
+    unsigned int error = funName(__VA_ARGS__);      \
+    if (error != IMAQdxErrorSuccess)                \
+      wpi_setImaqErrorWithContext(error, #funName); \
+  }
+
+/**
+ * Helper function to determine the size of a jpeg. The general structure of
+ * how to parse a jpeg for length can be found in this stackoverflow article:
+ * http://stackoverflow.com/a/1602428. Be sure to also read the comments for
+ * the SOS flag explanation.
+ */
+unsigned int USBCamera::GetJpegSize(void* buffer, unsigned int buffSize) {
+  uint8_t* data = (uint8_t*)buffer;
+  if (!wpi_assert(data[0] == 0xff && data[1] == 0xd8)) return 0;
+  unsigned int pos = 2;
+  while (pos < buffSize) {
+    // All control markers start with 0xff, so if this isn't present,
+    // the JPEG is not valid
+    if (!wpi_assert(data[pos] == 0xff)) return 0;
+    unsigned char t = data[pos + 1];
+    // These are RST markers. We just skip them and move onto the next marker
+    if (t == 0x01 || (t >= 0xd0 && t <= 0xd7)) {
+      pos += 2;
+    } else if (t == 0xd9) {
+      // End of Image, add 2 for this and 0-indexed
+      return pos + 2;
+    } else if (!wpi_assert(t != 0xd8)) {
+      // Another start of image, invalid image
+      return 0;
+    } else if (t == 0xda) {
+      // SOS marker. The next two bytes are a 16-bit big-endian int that is
+      // the length of the SOS header, skip that
+      unsigned int len = (((unsigned int)(data[pos + 2] & 0xff)) << 8 |
+                          ((unsigned int)data[pos + 3] & 0xff));
+      pos += len + 2;
+      // The next marker is the first marker that is 0xff followed by a non-RST
+      // element. 0xff followed by 0x00 is an escaped 0xff. 0xd0-0xd7 are RST
+      // markers
+      while (data[pos] != 0xff || data[pos + 1] == 0x00 ||
+             (data[pos + 1] >= 0xd0 && data[pos + 1] <= 0xd7)) {
+        pos += 1;
+        if (pos >= buffSize) return 0;
+      }
+    } else {
+      // This is one of several possible markers. The next two bytes are a
+      // 16-bit
+      // big-endian int with the length of the marker header, skip that then
+      // continue searching
+      unsigned int len = (((unsigned int)(data[pos + 2] & 0xff)) << 8 |
+                          ((unsigned int)data[pos + 3] & 0xff));
+      pos += len + 2;
+    }
+  }
+
+  return 0;
+}
+
+USBCamera::USBCamera(std::string name, bool useJpeg)
+    : m_name(name),
+      m_useJpeg(useJpeg) {}
+
+void USBCamera::OpenCamera() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  for (unsigned int i = 0; i < 3; i++) {
+    uInt32 id = 0;
+    // Can't use SAFE_IMAQ_CALL here because we only error on the third time
+    IMAQdxError error = IMAQdxOpenCamera(
+        m_name.c_str(), IMAQdxCameraControlModeController, &id);
+    if (error != IMAQdxErrorSuccess) {
+      // Only error on the 3rd try
+      if (i >= 2) wpi_setImaqErrorWithContext(error, "IMAQdxOpenCamera");
+      // Sleep for a few seconds to ensure the error has been dealt with
+      std::this_thread::sleep_for(std::chrono::milliseconds(2000));
+    } else {
+      m_id = id;
+      m_open = true;
+      return;
+    }
+  }
+}
+
+void USBCamera::CloseCamera() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (!m_open) return;
+  SAFE_IMAQ_CALL(IMAQdxCloseCamera, m_id);
+  m_id = 0;
+  m_open = false;
+}
+
+void USBCamera::StartCapture() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (!m_open || m_active) return;
+  SAFE_IMAQ_CALL(IMAQdxConfigureGrab, m_id);
+  SAFE_IMAQ_CALL(IMAQdxStartAcquisition, m_id);
+  m_active = true;
+}
+
+void USBCamera::StopCapture() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (!m_open || !m_active) return;
+  SAFE_IMAQ_CALL(IMAQdxStopAcquisition, m_id);
+  SAFE_IMAQ_CALL(IMAQdxUnconfigureAcquisition, m_id);
+  m_active = false;
+}
+
+void USBCamera::UpdateSettings() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  bool wasActive = m_active;
+
+  if (wasActive) StopCapture();
+  if (m_open) CloseCamera();
+  OpenCamera();
+
+  uInt32 count = 0;
+  uInt32 currentMode = 0;
+  SAFE_IMAQ_CALL(IMAQdxEnumerateVideoModes, m_id, nullptr, &count, &currentMode);
+  auto modes = std::make_unique<IMAQdxVideoMode[]>(count);
+  SAFE_IMAQ_CALL(IMAQdxEnumerateVideoModes, m_id, modes.get(), &count, &currentMode);
+
+  // Groups are:
+  //   0 - width
+  //   1 - height
+  //   2 - format
+  //   3 - fps
+  std::regex reMode("([0-9]+)\\s*x\\s*([0-9]+)\\s+(.*?)\\s+([0-9.]+)\\s*fps");
+  IMAQdxVideoMode* foundMode = nullptr;
+  IMAQdxVideoMode* currentModePtr = &modes[currentMode];
+  double foundFps = 1000.0;
+
+  // Loop through the modes, and find the match with the lowest fps
+  for (unsigned int i = 0; i < count; i++) {
+    std::cmatch m;
+    if (!std::regex_match(modes[i].Name, m, reMode)) continue;
+    unsigned int width = (unsigned int)std::stoul(m[1].str());
+    unsigned int height = (unsigned int)std::stoul(m[2].str());
+    if (width != m_width) continue;
+    if (height != m_height) continue;
+    double fps = atof(m[4].str().c_str());
+    if (fps < m_fps) continue;
+    if (fps > foundFps) continue;
+    bool isJpeg =
+        m[3].str().compare("jpeg") == 0 || m[3].str().compare("JPEG") == 0;
+    if ((m_useJpeg && !isJpeg) || (!m_useJpeg && isJpeg)) continue;
+    foundMode = &modes[i];
+    foundFps = fps;
+  }
+  if (foundMode != nullptr) {
+    if (foundMode->Value != currentModePtr->Value) {
+      SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, IMAQdxAttributeVideoMode,
+                     IMAQdxValueTypeU32, foundMode->Value);
+    }
+  }
+
+  if (m_whiteBalance.compare(AUTO) == 0) {
+    SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_WB_MODE,
+                   IMAQdxValueTypeString, AUTO);
+  } else {
+    SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_WB_MODE,
+                   IMAQdxValueTypeString, MANUAL);
+    if (m_whiteBalanceValuePresent)
+      SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_WB_VALUE,
+                     IMAQdxValueTypeU32, m_whiteBalanceValue);
+  }
+
+  if (m_exposure.compare(AUTO) == 0) {
+    SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_EX_MODE,
+                   IMAQdxValueTypeString,
+                   std::string("AutoAperaturePriority").c_str());
+  } else {
+    SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_EX_MODE,
+                   IMAQdxValueTypeString, MANUAL);
+    if (m_exposureValuePresent) {
+      double minv = 0.0;
+      double maxv = 0.0;
+      SAFE_IMAQ_CALL(IMAQdxGetAttributeMinimum, m_id, ATTR_EX_VALUE,
+                     IMAQdxValueTypeF64, &minv);
+      SAFE_IMAQ_CALL(IMAQdxGetAttributeMaximum, m_id, ATTR_EX_VALUE,
+                     IMAQdxValueTypeF64, &maxv);
+      double val = minv + ((maxv - minv) * ((double)m_exposureValue / 100.0));
+      SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_EX_VALUE,
+                     IMAQdxValueTypeF64, val);
+    }
+  }
+
+  SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_BR_MODE, IMAQdxValueTypeString,
+                 MANUAL);
+  double minv = 0.0;
+  double maxv = 0.0;
+  SAFE_IMAQ_CALL(IMAQdxGetAttributeMinimum, m_id, ATTR_BR_VALUE,
+                 IMAQdxValueTypeF64, &minv);
+  SAFE_IMAQ_CALL(IMAQdxGetAttributeMaximum, m_id, ATTR_BR_VALUE,
+                 IMAQdxValueTypeF64, &maxv);
+  double val = minv + ((maxv - minv) * ((double)m_brightness / 100.0));
+  SAFE_IMAQ_CALL(IMAQdxSetAttribute, m_id, ATTR_BR_VALUE, IMAQdxValueTypeF64,
+                 val);
+
+  if (wasActive) StartCapture();
+}
+
+void USBCamera::SetFPS(double fps) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (m_fps != fps) {
+    m_needSettingsUpdate = true;
+    m_fps = fps;
+  }
+}
+
+void USBCamera::SetSize(unsigned int width, unsigned int height) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (m_width != width || m_height != height) {
+    m_needSettingsUpdate = true;
+    m_width = width;
+    m_height = height;
+  }
+}
+
+void USBCamera::SetBrightness(unsigned int brightness) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (m_brightness != brightness) {
+    m_needSettingsUpdate = true;
+    m_brightness = brightness;
+  }
+}
+
+unsigned int USBCamera::GetBrightness() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  return m_brightness;
+}
+
+void USBCamera::SetWhiteBalanceAuto() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  m_whiteBalance = AUTO;
+  m_whiteBalanceValue = 0;
+  m_whiteBalanceValuePresent = false;
+  m_needSettingsUpdate = true;
+}
+
+void USBCamera::SetWhiteBalanceHoldCurrent() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  m_whiteBalance = MANUAL;
+  m_whiteBalanceValue = 0;
+  m_whiteBalanceValuePresent = false;
+  m_needSettingsUpdate = true;
+}
+
+void USBCamera::SetWhiteBalanceManual(unsigned int whiteBalance) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  m_whiteBalance = MANUAL;
+  m_whiteBalanceValue = whiteBalance;
+  m_whiteBalanceValuePresent = true;
+  m_needSettingsUpdate = true;
+}
+
+void USBCamera::SetExposureAuto() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  m_exposure = AUTO;
+  m_exposureValue = 0;
+  m_exposureValuePresent = false;
+  m_needSettingsUpdate = true;
+}
+
+void USBCamera::SetExposureHoldCurrent() {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  m_exposure = MANUAL;
+  m_exposureValue = 0;
+  m_exposureValuePresent = false;
+  m_needSettingsUpdate = true;
+}
+
+void USBCamera::SetExposureManual(unsigned int level) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  m_exposure = MANUAL;
+  if (level > 100)
+    m_exposureValue = 100;
+  else
+    m_exposureValue = level;
+  m_exposureValuePresent = true;
+  m_needSettingsUpdate = true;
+}
+
+void USBCamera::GetImage(Image* image) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (m_needSettingsUpdate || m_useJpeg) {
+    m_needSettingsUpdate = false;
+    m_useJpeg = false;
+    UpdateSettings();
+  }
+  // BufNum is not actually used for anything at our level, since we are
+  // waiting until the next image is ready anyway
+  uInt32 bufNum;
+  SAFE_IMAQ_CALL(IMAQdxGrab, m_id, image, 1, &bufNum);
+}
+
+unsigned int USBCamera::GetImageData(void* buffer, unsigned int bufferSize) {
+  std::lock_guard<priority_recursive_mutex> lock(m_mutex);
+  if (m_needSettingsUpdate || !m_useJpeg) {
+    m_needSettingsUpdate = false;
+    m_useJpeg = true;
+    UpdateSettings();
+  }
+  // BufNum is not actually used for anything at our level
+  uInt32 bufNum;
+  SAFE_IMAQ_CALL(IMAQdxGetImageData, m_id, buffer, bufferSize,
+                 IMAQdxBufferNumberModeLast, 0, &bufNum);
+  return GetJpegSize(buffer, bufferSize);
+}
diff --git a/wpilibc/Athena/src/Ultrasonic.cpp b/wpilibc/Athena/src/Ultrasonic.cpp
new file mode 100644
index 0000000..ba25a04
--- /dev/null
+++ b/wpilibc/Athena/src/Ultrasonic.cpp
@@ -0,0 +1,354 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Ultrasonic.h"
+
+#include "Counter.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include "LiveWindow/LiveWindow.h"
+
+constexpr double
+    Ultrasonic::kPingTime;  ///< Time (sec) for the ping trigger pulse.
+const uint32_t Ultrasonic::kPriority;  ///< Priority that the ultrasonic round
+                                       ///robin task runs.
+constexpr double
+    Ultrasonic::kMaxUltrasonicTime;  ///< Max time (ms) between readings.
+constexpr double Ultrasonic::kSpeedOfSoundInchesPerSec;
+Ultrasonic *Ultrasonic::m_firstSensor =
+    nullptr;  // head of the ultrasonic sensor list
+Task Ultrasonic::m_task;
+std::atomic<bool> Ultrasonic::m_automaticEnabled{false}; // automatic round robin mode
+priority_mutex Ultrasonic::m_mutex;
+
+/**
+ * Background task that goes through the list of ultrasonic sensors and pings
+ * each one in turn. The counter
+ * is configured to read the timing of the returned echo pulse.
+ *
+ * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
+ * This code runs as a task and assumes that none of the ultrasonic sensors will
+ * change while it's
+ * running. If one does, then this will certainly break. Make sure to disable
+ * automatic mode before changing
+ * anything with the sensors!!
+ */
+void Ultrasonic::UltrasonicChecker() {
+  Ultrasonic *u = nullptr;
+  while (m_automaticEnabled) {
+    if (u == nullptr) u = m_firstSensor;
+    if (u == nullptr) return;
+    if (u->IsEnabled()) u->m_pingChannel->Pulse(kPingTime);  // do the ping
+    u = u->m_nextSensor;
+    Wait(0.1);  // wait for ping to return
+  }
+}
+
+/**
+ * Initialize the Ultrasonic Sensor.
+ * This is the common code that initializes the ultrasonic sensor given that
+ * there
+ * are two digital I/O channels allocated. If the system was running in
+ * automatic mode (round robin)
+ * when the new sensor is added, it is stopped, the sensor is added, then
+ * automatic mode is
+ * restored.
+ */
+void Ultrasonic::Initialize() {
+  bool originalMode = m_automaticEnabled;
+  SetAutomaticMode(false);     // kill task when adding a new sensor
+  // link this instance on the list
+  {
+    std::lock_guard<priority_mutex> lock(m_mutex);
+    m_nextSensor = m_firstSensor;
+    m_firstSensor = this;
+  }
+
+  m_counter.SetMaxPeriod(1.0);
+  m_counter.SetSemiPeriodMode(true);
+  m_counter.Reset();
+  m_enabled = true;  // make it available for round robin scheduling
+  SetAutomaticMode(originalMode);
+
+  static int instances = 0;
+  instances++;
+  HALReport(HALUsageReporting::kResourceType_Ultrasonic, instances);
+  LiveWindow::GetInstance()->AddSensor("Ultrasonic",
+                                       m_echoChannel->GetChannel(), this);
+}
+
+/**
+ * Create an instance of the Ultrasonic Sensor
+ * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic
+ * sensors.
+ * @param pingChannel The digital output channel that sends the pulse to
+ * initiate the sensor sending
+ * the ping.
+ * @param echoChannel The digital input channel that receives the echo. The
+ * length of time that the
+ * echo is high represents the round trip time of the ping, and the distance.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(uint32_t pingChannel, uint32_t echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
+      m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+ * channel and a DigitalOutput
+ * for the ping channel.
+ * @param pingChannel The digital output object that starts the sensor doing a
+ * ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to
+ * determine the range.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  if (pingChannel == nullptr || echoChannel == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_nextSensor = nullptr;
+    m_units = units;
+    return;
+  }
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+ * channel and a DigitalOutput
+ * for the ping channel.
+ * @param pingChannel The digital output object that starts the sensor doing a
+ * ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to
+ * determine the range.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(&pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(&echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+ * channel and a DigitalOutput
+ * for the ping channel.
+ * @param pingChannel The digital output object that starts the sensor doing a
+ * ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to
+ * determine the range.
+ * @param units The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+                       std::shared_ptr<DigitalInput> echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel),
+      m_echoChannel(echoChannel),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Destructor for the ultrasonic sensor.
+ * Delete the instance of the ultrasonic sensor by freeing the allocated digital
+ * channels.
+ * If the system was in automatic mode (round robin), then it is stopped, then
+ * started again
+ * after this sensor is removed (provided this wasn't the last sensor).
+ */
+Ultrasonic::~Ultrasonic() {
+  bool wasAutomaticMode = m_automaticEnabled;
+  SetAutomaticMode(false);
+  wpi_assert(m_firstSensor != nullptr);
+
+  {
+    std::lock_guard<priority_mutex> lock(m_mutex);
+    if (this == m_firstSensor) {
+      m_firstSensor = m_nextSensor;
+      if (m_firstSensor == nullptr) {
+        SetAutomaticMode(false);
+      }
+    } else {
+      wpi_assert(m_firstSensor->m_nextSensor != nullptr);
+      for (Ultrasonic *s = m_firstSensor; s != nullptr; s = s->m_nextSensor) {
+        if (this == s->m_nextSensor) {
+          s->m_nextSensor = s->m_nextSensor->m_nextSensor;
+          break;
+        }
+      }
+    }
+  }
+  if (m_firstSensor != nullptr && wasAutomaticMode) SetAutomaticMode(true);
+}
+
+/**
+ * Turn Automatic mode on/off.
+ * When in Automatic mode, all sensors will fire in round robin, waiting a set
+ * time between each sensor.
+ * @param enabling Set to true if round robin scheduling should start for all
+ * the ultrasonic sensors. This
+ * scheduling method assures that the sensors are non-interfering because no two
+ * sensors fire at the same time.
+ * If another scheduling algorithm is prefered, it can be implemented by
+ * pinging the sensors manually and waiting
+ * for the results to come back.
+ */
+void Ultrasonic::SetAutomaticMode(bool enabling) {
+  if (enabling == m_automaticEnabled) return;  // ignore the case of no change
+
+  m_automaticEnabled = enabling;
+  if (enabling) {
+    // enabling automatic mode.
+    // Clear all the counters so no data is valid
+    for (Ultrasonic *u = m_firstSensor; u != nullptr; u = u->m_nextSensor) {
+      u->m_counter.Reset();
+    }
+    // Start round robin task
+    wpi_assert(m_task.Verify() ==
+               false);  // should be false since was previously disabled
+    m_task = Task("UltrasonicChecker", &Ultrasonic::UltrasonicChecker);
+
+    // TODO: Currently, lvuser does not have permissions to set task priorities.
+    // Until that is the case, uncommenting this will break user code that calls
+    // Ultrasonic::SetAutomicMode().
+    //m_task.SetPriority(kPriority);
+  } else {
+    // disabling automatic mode. Wait for background task to stop running.
+    while (m_task.Verify())
+      Wait(0.15);  // just a little longer than the ping time for round-robin to
+                   // stop
+
+    // clear all the counters (data now invalid) since automatic mode is stopped
+    for (Ultrasonic *u = m_firstSensor; u != nullptr; u = u->m_nextSensor) {
+      u->m_counter.Reset();
+    }
+    m_automaticEnabled = false;
+    m_task.join();
+  }
+}
+
+/**
+ * Single ping to ultrasonic sensor.
+ * Send out a single ping to the ultrasonic sensor. This only works if automatic
+ * (round robin)
+ * mode is disabled. A single ping is sent out, and the counter should count the
+ * semi-period
+ * when it comes in. The counter is reset to make the current value invalid.
+ */
+void Ultrasonic::Ping() {
+  wpi_assert(!m_automaticEnabled);
+  m_counter.Reset();  // reset the counter to zero (invalid data now)
+  m_pingChannel->Pulse(
+      kPingTime);  // do the ping to start getting a single range
+}
+
+/**
+ * Check if there is a valid range measurement.
+ * The ranges are accumulated in a counter that will increment on each edge of
+ * the echo (return)
+ * signal. If the count is not at least 2, then the range has not yet been
+ * measured, and is invalid.
+ */
+bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; }
+
+/**
+ * Get the range in inches from the ultrasonic sensor.
+ * @return double Range in inches of the target returned from the ultrasonic
+ * sensor. If there is
+ * no valid value yet, i.e. at least one measurement hasn't completed, then
+ * return 0.
+ */
+double Ultrasonic::GetRangeInches() const {
+  if (IsRangeValid())
+    return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+  else
+    return 0;
+}
+
+/**
+ * Get the range in millimeters from the ultrasonic sensor.
+ * @return double Range in millimeters of the target returned by the ultrasonic
+ * sensor.
+ * If there is no valid value yet, i.e. at least one measurement hasn't
+ * complted, then return 0.
+ */
+double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
+
+/**
+ * Get the range in the current DistanceUnit for the PIDSource base object.
+ *
+ * @return The range in DistanceUnit
+ */
+double Ultrasonic::PIDGet() {
+  switch (m_units) {
+    case Ultrasonic::kInches:
+      return GetRangeInches();
+    case Ultrasonic::kMilliMeters:
+      return GetRangeMM();
+    default:
+      return 0.0;
+  }
+}
+
+void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) {
+  if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
+    m_pidSource = pidSource;
+  }
+}
+
+/**
+ * Set the current DistanceUnit that should be used for the PIDSource base
+ * object.
+ *
+ * @param units The DistanceUnit that should be used.
+ */
+void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
+
+/**
+ * Get the current DistanceUnit that is used for the PIDSource base object.
+ *
+ * @return The type of DistanceUnit that is being used.
+ */
+Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
+  return m_units;
+}
+
+void Ultrasonic::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetRangeInches());
+  }
+}
+
+void Ultrasonic::StartLiveWindowMode() {}
+
+void Ultrasonic::StopLiveWindowMode() {}
+
+std::string Ultrasonic::GetSmartDashboardType() const { return "Ultrasonic"; }
+
+void Ultrasonic::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Ultrasonic::GetTable() const { return m_table; }
diff --git a/wpilibc/Athena/src/Utility.cpp b/wpilibc/Athena/src/Utility.cpp
new file mode 100644
index 0000000..5998f0f
--- /dev/null
+++ b/wpilibc/Athena/src/Utility.cpp
@@ -0,0 +1,222 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Utility.h"
+
+//#include "NetworkCommunication/FRCComm.h"
+#include "HAL/HAL.hpp"
+#include "Task.h"
+#include <iostream>
+#include <sstream>
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+#include <execinfo.h>
+#include <cxxabi.h>
+#include "nivision.h"
+
+/**
+ * Assert implementation.
+ * This allows breakpoints to be set on an assert.
+ * The users don't call this, but instead use the wpi_assert macros in
+ * Utility.h.
+ */
+bool wpi_assert_impl(bool conditionValue, const char *conditionText,
+                     const char *message, const char *fileName,
+                     uint32_t lineNumber, const char *funcName) {
+  if (!conditionValue) {
+    std::stringstream errorStream;
+
+    errorStream << "Assertion \"" << conditionText << "\" ";
+    errorStream << "on line " << lineNumber << " ";
+    errorStream << "of " << basename(fileName) << " ";
+
+    if (message[0] != '\0') {
+      errorStream << "failed: " << message << std::endl;
+    } else {
+      errorStream << "failed." << std::endl;
+    }
+
+    errorStream << GetStackTrace(2);
+
+    std::string error = errorStream.str();
+
+    // Print the error and send it to the DriverStation
+    std::cout << error << std::endl;
+    HALSetErrorData(error.c_str(), error.size(), 100);
+  }
+
+  return conditionValue;
+}
+
+/**
+ * Common error routines for wpi_assertEqual_impl and wpi_assertNotEqual_impl
+ * This should not be called directly; it should only be used by
+ * wpi_assertEqual_impl
+ * and wpi_assertNotEqual_impl.
+ */
+void wpi_assertEqual_common_impl(const char *valueA, const char *valueB,
+                                 const char *equalityType,
+                                 const char *message,
+                                 const char *fileName,
+                                 uint32_t lineNumber,
+                                 const char *funcName) {
+  std::stringstream errorStream;
+
+  errorStream << "Assertion \"" << valueA << " " << equalityType << " "
+              << valueB << "\" ";
+  errorStream << "on line " << lineNumber << " ";
+  errorStream << "of " << basename(fileName) << " ";
+
+  if (message[0] != '\0') {
+    errorStream << "failed: " << message << std::endl;
+  } else {
+    errorStream << "failed." << std::endl;
+  }
+
+  errorStream << GetStackTrace(3);
+
+  std::string error = errorStream.str();
+
+  // Print the error and send it to the DriverStation
+  std::cout << error << std::endl;
+  HALSetErrorData(error.c_str(), error.size(), 100);
+}
+
+/**
+ * Assert equal implementation.
+ * This determines whether the two given integers are equal. If not,
+ * the value of each is printed along with an optional message string.
+ * The users don't call this, but instead use the wpi_assertEqual macros in
+ * Utility.h.
+ */
+bool wpi_assertEqual_impl(int valueA, int valueB, const char *valueAString,
+                          const char *valueBString, const char *message,
+                          const char *fileName, uint32_t lineNumber,
+                          const char *funcName) {
+  if (!(valueA == valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "==", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA == valueB;
+}
+
+/**
+ * Assert not equal implementation.
+ * This determines whether the two given integers are equal. If so,
+ * the value of each is printed along with an optional message string.
+ * The users don't call this, but instead use the wpi_assertNotEqual macros in
+ * Utility.h.
+ */
+bool wpi_assertNotEqual_impl(int valueA, int valueB, const char *valueAString,
+                             const char *valueBString, const char *message,
+                             const char *fileName, uint32_t lineNumber,
+                             const char *funcName) {
+  if (!(valueA != valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "!=", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA != valueB;
+}
+
+/**
+ * Return the FPGA Version number.
+ * For now, expect this to be competition year.
+ * @return FPGA Version number.
+ */
+uint16_t GetFPGAVersion() {
+  int32_t status = 0;
+  uint16_t version = getFPGAVersion(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return version;
+}
+
+/**
+ * Return the FPGA Revision number.
+ * The format of the revision is 3 numbers.
+ * The 12 most significant bits are the Major Revision.
+ * the next 8 bits are the Minor Revision.
+ * The 12 least significant bits are the Build Number.
+ * @return FPGA Revision number.
+ */
+uint32_t GetFPGARevision() {
+  int32_t status = 0;
+  uint32_t revision = getFPGARevision(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return revision;
+}
+
+/**
+ * Read the microsecond-resolution timer on the FPGA.
+ *
+ * @return The current time in microseconds according to the FPGA (since FPGA
+ * reset).
+ */
+uint32_t GetFPGATime() {
+  int32_t status = 0;
+  uint32_t time = getFPGATime(&status);
+  wpi_setGlobalErrorWithContext(status, getHALErrorMessage(status));
+  return time;
+}
+
+/**
+ * Get the state of the "USER" button on the RoboRIO
+ * @return True if the button is currently pressed down
+ */
+bool GetUserButton() {
+  int32_t status = 0;
+
+  bool value = getFPGAButton(&status);
+  wpi_setGlobalError(status);
+
+  return value;
+}
+
+/**
+ * Demangle a C++ symbol, used for printing stack traces.
+ */
+static std::string demangle(char const *mangledSymbol) {
+  char buffer[256];
+  size_t length;
+  int status;
+
+  if (sscanf(mangledSymbol, "%*[^(]%*[(]%255[^)+]", buffer)) {
+    char *symbol = abi::__cxa_demangle(buffer, nullptr, &length, &status);
+    if (status == 0) {
+      return symbol;
+    } else {
+      // If the symbol couldn't be demangled, it's probably a C function,
+      // so just return it as-is.
+      return buffer;
+    }
+  }
+
+  // If everything else failed, just return the mangled symbol
+  return mangledSymbol;
+}
+
+/**
+ * Get a stack trace, ignoring the first "offset" symbols.
+ * @param offset The number of symbols at the top of the stack to ignore
+ */
+std::string GetStackTrace(uint32_t offset) {
+  void *stackTrace[128];
+  int stackSize = backtrace(stackTrace, 128);
+  char **mangledSymbols = backtrace_symbols(stackTrace, stackSize);
+  std::stringstream trace;
+
+  for (int i = offset; i < stackSize; i++) {
+    // Only print recursive functions once in a row.
+    if (i == 0 || stackTrace[i] != stackTrace[i - 1]) {
+      trace << "\tat " << demangle(mangledSymbols[i]) << std::endl;
+    }
+  }
+
+  free(mangledSymbols);
+
+  return trace.str();
+}
diff --git a/wpilibc/Athena/src/Victor.cpp b/wpilibc/Athena/src/Victor.cpp
new file mode 100644
index 0000000..f8a4970
--- /dev/null
+++ b/wpilibc/Athena/src/Victor.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Victor.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Constructor for a Victor
+ * @param channel The PWM channel number that the Victor is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+Victor::Victor(uint32_t channel) : SafePWM(channel) {
+  /* Note that the Victor uses the following bounds for PWM values.  These
+   * values were determined empirically and optimized for the Victor 888. These
+   * values should work reasonably well for Victor 884 controllers as well but
+   * if users experience issues such as asymmetric behaviour around the deadband
+   * or inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the Victor 884 User
+   * Manual available from IFI.
+   *
+   *   2.027ms = full "forward"
+   *   1.525ms = the "high end" of the deadband range
+   *   1.507ms = center of the deadband range (off)
+   *   1.49ms = the "low end" of the deadband range
+   *   1.026ms = full "reverse"
+   */
+  SetBounds(2.027, 1.525, 1.507, 1.49, 1.026);
+  SetPeriodMultiplier(kPeriodMultiplier_2X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this);
+  HALReport(HALUsageReporting::kResourceType_Victor, GetChannel());
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void Victor::Set(float speed, uint8_t syncGroup) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float Victor::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Victor::Disable() { SetRaw(kPwmDisabled); }
+/**
+* Common interface for inverting direction of a speed controller.
+* @param isInverted The state of inversion, true is inverted.
+*/
+void Victor::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool Victor::GetInverted() const { return m_isInverted; }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void Victor::PIDWrite(float output) { Set(output); }
diff --git a/wpilibc/Athena/src/VictorSP.cpp b/wpilibc/Athena/src/VictorSP.cpp
new file mode 100644
index 0000000..ccbc163
--- /dev/null
+++ b/wpilibc/Athena/src/VictorSP.cpp
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "VictorSP.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+/**
+ * Note that the VictorSP uses the following bounds for PWM values. These values
+ * should work reasonably well for
+ * most controllers, but if users experience issues such as asymmetric behavior
+ * around
+ * the deadband or inability to saturate the controller in either direction,
+ * calibration is recommended.
+ * The calibration procedure can be found in the VictorSP User Manual available
+ * from Vex.
+ *
+ *   2.004ms = full "forward"
+ *   1.52ms = the "high end" of the deadband range
+ *   1.50ms = center of the deadband range (off)
+ *   1.48ms = the "low end" of the deadband range
+ *   0.997ms = full "reverse"
+ */
+
+/**
+ * Constructor for a VictorSP
+ * @param channel The PWM channel that the VictorSP is attached to. 0-9 are
+ * on-board, 10-19 are on the MXP port
+ */
+VictorSP::VictorSP(uint32_t channel) : SafePWM(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetRaw(m_centerPwm);
+  SetZeroLatch();
+
+  HALReport(HALUsageReporting::kResourceType_VictorSP, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("VictorSP", GetChannel(), this);
+}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ * @param syncGroup Unused interface.
+ */
+void VictorSP::Set(float speed, uint8_t syncGroup) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+float VictorSP::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for inverting direction of a speed controller.
+ * @param isInverted The state of inversion, true is inverted.
+ */
+void VictorSP::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool VictorSP::GetInverted() const { return m_isInverted; }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void VictorSP::Disable() { SetRaw(kPwmDisabled); }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void VictorSP::PIDWrite(float output) { Set(output); }
diff --git a/wpilibc/Athena/src/Vision/AxisCamera.cpp b/wpilibc/Athena/src/Vision/AxisCamera.cpp
new file mode 100644
index 0000000..990c68a
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/AxisCamera.cpp
@@ -0,0 +1,597 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/AxisCamera.h"
+
+#include "WPIErrors.h"
+
+#include <cstring>
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <unistd.h>
+#include <netdb.h>
+#include <Timer.h>
+#include <iostream>
+#include <sstream>
+
+static const unsigned int kMaxPacketSize = 1536;
+static const unsigned int kImageBufferAllocationIncrement = 1000;
+
+static const std::string kWhiteBalanceStrings[] = {
+    "auto",         "hold",         "fixed_outdoor1", "fixed_outdoor2",
+    "fixed_indoor", "fixed_fluor1", "fixed_fluor2",
+};
+
+static const std::string kExposureControlStrings[] = {
+    "auto", "hold", "flickerfree50", "flickerfree60",
+};
+
+static const std::string kResolutionStrings[] = {
+    "640x480", "480x360", "320x240", "240x180", "176x144", "160x120",
+};
+
+static const std::string kRotationStrings[] = {
+    "0", "180",
+};
+
+/**
+ * AxisCamera constructor
+ * @param cameraHost The host to find the camera at, typically an IP address
+ */
+AxisCamera::AxisCamera(std::string const &cameraHost)
+    : m_cameraHost(cameraHost) {
+  m_captureThread = std::thread(&AxisCamera::Capture, this);
+}
+
+AxisCamera::~AxisCamera() {
+  m_done = true;
+  m_captureThread.join();
+}
+
+/*
+ * Return true if the latest image from the camera has not been retrieved by
+ * calling GetImage() yet.
+ * @return true if the image has not been retrieved yet.
+ */
+bool AxisCamera::IsFreshImage() const { return m_freshImage; }
+
+/**
+ * Get an image from the camera and store it in the provided image.
+ * @param image The imaq image to store the result in. This must be an HSL or
+ * RGB image.
+ * @return 1 upon success, zero on a failure
+ */
+int AxisCamera::GetImage(Image *image) {
+  if (m_imageData.size() == 0) {
+    return 0;
+  }
+
+  std::lock_guard<priority_mutex> lock(m_imageDataMutex);
+
+  Priv_ReadJPEGString_C(image, m_imageData.data(), m_imageData.size());
+
+  m_freshImage = false;
+
+  return 1;
+}
+
+/**
+ * Get an image from the camera and store it in the provided image.
+ * @param image The image to store the result in. This must be an HSL or RGB
+ * image
+ * @return 1 upon success, zero on a failure
+ */
+int AxisCamera::GetImage(ColorImage *image) {
+  return GetImage(image->GetImaqImage());
+}
+
+/**
+ * Instantiate a new image object and fill it with the latest image from the
+ * camera.
+ *
+ * The returned pointer is owned by the caller and is their responsibility to
+ * delete.
+ * @return a pointer to an HSLImage object
+ */
+HSLImage *AxisCamera::GetImage() {
+  auto image = new HSLImage();
+  GetImage(image);
+  return image;
+}
+
+/**
+ * Copy an image into an existing buffer.
+ * This copies an image into an existing buffer rather than creating a new image
+ * in memory. That way a new image is only allocated when the image being copied
+ * is
+ * larger than the destination.
+ * This method is called by the PCVideoServer class.
+ * @param imageData The destination image.
+ * @param numBytes The size of the destination image.
+ * @return 0 if failed (no source image or no memory), 1 if success.
+ */
+int AxisCamera::CopyJPEG(char **destImage, unsigned int &destImageSize,
+                         unsigned int &destImageBufferSize) {
+  std::lock_guard<priority_mutex> lock(m_imageDataMutex);
+  if (destImage == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "destImage must not be nullptr");
+    return 0;
+  }
+
+  if (m_imageData.size() == 0) return 0;  // if no source image
+
+  if (destImageBufferSize <
+      m_imageData.size())  // if current destination buffer too small
+  {
+    if (*destImage != nullptr) delete[] * destImage;
+    destImageBufferSize = m_imageData.size() + kImageBufferAllocationIncrement;
+    *destImage = new char[destImageBufferSize];
+    if (*destImage == nullptr) return 0;
+  }
+  // copy this image into destination buffer
+  if (*destImage == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "*destImage must not be nullptr");
+  }
+
+  std::copy(m_imageData.begin(), m_imageData.end(), *destImage);
+  destImageSize = m_imageData.size();
+  ;
+  return 1;
+}
+
+/**
+ * Request a change in the brightness of the camera images.
+ * @param brightness valid values 0 .. 100
+ */
+void AxisCamera::WriteBrightness(int brightness) {
+  if (brightness < 0 || brightness > 100) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                               "Brightness must be from 0 to 100");
+    return;
+  }
+
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_brightness != brightness) {
+    m_brightness = brightness;
+    m_parametersDirty = true;
+  }
+}
+
+/**
+ * @return The configured brightness of the camera images
+ */
+int AxisCamera::GetBrightness() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_brightness;
+}
+
+/**
+ * Request a change in the white balance on the camera.
+ * @param whiteBalance Valid values from the <code>WhiteBalance</code> enum.
+ */
+void AxisCamera::WriteWhiteBalance(AxisCamera::WhiteBalance whiteBalance) {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_whiteBalance != whiteBalance) {
+    m_whiteBalance = whiteBalance;
+    m_parametersDirty = true;
+  }
+}
+
+/**
+ * @return The configured white balances of the camera images
+ */
+AxisCamera::WhiteBalance AxisCamera::GetWhiteBalance() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_whiteBalance;
+}
+
+/**
+ * Request a change in the color level of the camera images.
+ * @param colorLevel valid values are 0 .. 100
+ */
+void AxisCamera::WriteColorLevel(int colorLevel) {
+  if (colorLevel < 0 || colorLevel > 100) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                               "Color level must be from 0 to 100");
+    return;
+  }
+
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_colorLevel != colorLevel) {
+    m_colorLevel = colorLevel;
+    m_parametersDirty = true;
+  }
+}
+
+/**
+ * @return The configured color level of the camera images
+ */
+int AxisCamera::GetColorLevel() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_colorLevel;
+}
+
+/**
+ * Request a change in the camera's exposure mode.
+ * @param exposureControl A mode to write in the <code>Exposure</code> enum.
+ */
+void AxisCamera::WriteExposureControl(
+    AxisCamera::ExposureControl exposureControl) {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_exposureControl != exposureControl) {
+    m_exposureControl = exposureControl;
+    m_parametersDirty = true;
+  }
+}
+
+/**
+ * @return The configured exposure control mode of the camera
+ */
+AxisCamera::ExposureControl AxisCamera::GetExposureControl() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_exposureControl;
+}
+
+/**
+ * Request a change in the exposure priority of the camera.
+ * @param exposurePriority Valid values are 0, 50, 100.
+ * 0 = Prioritize image quality
+ * 50 = None
+ * 100 = Prioritize frame rate
+ */
+void AxisCamera::WriteExposurePriority(int exposurePriority) {
+  if (exposurePriority != 0 && exposurePriority != 50 &&
+      exposurePriority != 100) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                               "Exposure priority must be from 0, 50, or 100");
+    return;
+  }
+
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_exposurePriority != exposurePriority) {
+    m_exposurePriority = exposurePriority;
+    m_parametersDirty = true;
+  }
+}
+
+/**
+ * @return The configured exposure priority of the camera
+ */
+int AxisCamera::GetExposurePriority() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_exposurePriority;
+}
+
+/**
+ * Write the maximum frames per second that the camera should send
+ * Write 0 to send as many as possible.
+ * @param maxFPS The number of frames the camera should send in a second,
+ * exposure permitting.
+ */
+void AxisCamera::WriteMaxFPS(int maxFPS) {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_maxFPS != maxFPS) {
+    m_maxFPS = maxFPS;
+    m_parametersDirty = true;
+    m_streamDirty = true;
+  }
+}
+
+/**
+ * @return The configured maximum FPS of the camera
+ */
+int AxisCamera::GetMaxFPS() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_maxFPS;
+}
+
+/**
+ * Write resolution value to camera.
+ * @param resolution The camera resolution value to write to the camera.
+ */
+void AxisCamera::WriteResolution(AxisCamera::Resolution resolution) {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_resolution != resolution) {
+    m_resolution = resolution;
+    m_parametersDirty = true;
+    m_streamDirty = true;
+  }
+}
+
+/**
+ * @return The configured resolution of the camera (not necessarily the same
+ * resolution as the most recent image, if it was changed recently.)
+ */
+AxisCamera::Resolution AxisCamera::GetResolution() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_resolution;
+}
+
+/**
+ * Write the rotation value to the camera.
+ * If you mount your camera upside down, use this to adjust the image for you.
+ * @param rotation The angle to rotate the camera
+ * (<code>AxisCamera::Rotation::k0</code>
+ * or <code>AxisCamera::Rotation::k180</code>)
+ */
+void AxisCamera::WriteRotation(AxisCamera::Rotation rotation) {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_rotation != rotation) {
+    m_rotation = rotation;
+    m_parametersDirty = true;
+    m_streamDirty = true;
+  }
+}
+
+/**
+ * @return The configured rotation mode of the camera
+ */
+AxisCamera::Rotation AxisCamera::GetRotation() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_rotation;
+}
+
+/**
+ * Write the compression value to the camera.
+ * @param compression Values between 0 and 100.
+ */
+void AxisCamera::WriteCompression(int compression) {
+  if (compression < 0 || compression > 100) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                               "Compression must be from 0 to 100");
+    return;
+  }
+
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+
+  if (m_compression != compression) {
+    m_compression = compression;
+    m_parametersDirty = true;
+    m_streamDirty = true;
+  }
+}
+
+/**
+ * @return The configured compression level of the camera
+ */
+int AxisCamera::GetCompression() {
+  std::lock_guard<priority_mutex> lock(m_parametersMutex);
+  return m_compression;
+}
+
+/**
+ * Method called in the capture thread to receive images from the camera
+ */
+void AxisCamera::Capture() {
+  int consecutiveErrors = 0;
+
+  // Loop on trying to setup the camera connection. This happens in a background
+  // thread so it shouldn't effect the operation of user programs.
+  while (!m_done) {
+    std::string requestString =
+        "GET /mjpg/video.mjpg HTTP/1.1\n"
+        "User-Agent: HTTPStreamClient\n"
+        "Connection: Keep-Alive\n"
+        "Cache-Control: no-cache\n"
+        "Authorization: Basic RlJDOkZSQw==\n\n";
+    m_captureMutex.lock();
+    m_cameraSocket = CreateCameraSocket(requestString, consecutiveErrors > 5);
+    if (m_cameraSocket != -1) {
+      ReadImagesFromCamera();
+      consecutiveErrors = 0;
+    } else {
+      consecutiveErrors++;
+    }
+    m_captureMutex.unlock();
+    Wait(0.5);
+  }
+}
+
+/**
+ * This function actually reads the images from the camera.
+ */
+void AxisCamera::ReadImagesFromCamera() {
+  char *imgBuffer = nullptr;
+  int imgBufferLength = 0;
+
+  // TODO: these recv calls must be non-blocking. Otherwise if the camera
+  // fails during a read, the code hangs and never retries when the camera comes
+  // back up.
+
+  int counter = 2;
+  while (!m_done) {
+    char initialReadBuffer[kMaxPacketSize] = "";
+    char intermediateBuffer[1];
+    char *trailingPtr = initialReadBuffer;
+    int trailingCounter = 0;
+    while (counter) {
+      // TODO: fix me... this cannot be the most efficient way to approach this,
+      // reading one byte at a time.
+      if (recv(m_cameraSocket, intermediateBuffer, 1, 0) == -1) {
+        wpi_setErrnoErrorWithContext("Failed to read image header");
+        close(m_cameraSocket);
+        return;
+      }
+      strncat(initialReadBuffer, intermediateBuffer, 1);
+      // trailingCounter ensures that we start looking for the 4 byte string
+      // after
+      // there is at least 4 bytes total. Kind of obscure.
+      // look for 2 blank lines (\r\n)
+      if (nullptr != strstr(trailingPtr, "\r\n\r\n")) {
+        --counter;
+      }
+      if (++trailingCounter >= 4) {
+        trailingPtr++;
+      }
+    }
+    counter = 1;
+    char *contentLength = strstr(initialReadBuffer, "Content-Length: ");
+    if (contentLength == nullptr) {
+      wpi_setWPIErrorWithContext(IncompatibleMode,
+                                 "No content-length token found in packet");
+      close(m_cameraSocket);
+      if (imgBuffer) delete[] imgBuffer;
+      return;
+    }
+    contentLength = contentLength + 16;    // skip past "content length"
+    int readLength = atol(contentLength);  // get the image byte count
+
+    // Make sure buffer is large enough
+    if (imgBufferLength < readLength) {
+      if (imgBuffer) delete[] imgBuffer;
+      imgBufferLength = readLength + kImageBufferAllocationIncrement;
+      imgBuffer = new char[imgBufferLength];
+      if (imgBuffer == nullptr) {
+        imgBufferLength = 0;
+        continue;
+      }
+    }
+
+    // Read the image data for "Content-Length" bytes
+    int bytesRead = 0;
+    int remaining = readLength;
+    while (bytesRead < readLength) {
+      int bytesThisRecv =
+          recv(m_cameraSocket, &imgBuffer[bytesRead], remaining, 0);
+      bytesRead += bytesThisRecv;
+      remaining -= bytesThisRecv;
+    }
+
+    // Update image
+    {
+      std::lock_guard<priority_mutex> lock(m_imageDataMutex);
+
+      m_imageData.assign(imgBuffer, imgBuffer + imgBufferLength);
+      m_freshImage = true;
+    }
+
+    if (WriteParameters()) {
+      break;
+    }
+  }
+
+  close(m_cameraSocket);
+}
+
+/**
+ * Send a request to the camera to set all of the parameters.  This is called
+ * in the capture thread between each frame. This strategy avoids making lots
+ * of redundant HTTP requests, accounts for failed initial requests, and
+ * avoids blocking calls in the main thread unless necessary.
+ *
+ * This method does nothing if no parameters have been modified since it last
+ * completely successfully.
+ *
+ * @return <code>true</code> if the stream should be restarted due to a
+ * parameter changing.
+ */
+bool AxisCamera::WriteParameters() {
+  if (m_parametersDirty) {
+    std::stringstream request;
+    request << "GET /axis-cgi/admin/param.cgi?action=update";
+
+    m_parametersMutex.lock();
+    request << "&ImageSource.I0.Sensor.Brightness=" << m_brightness;
+    request << "&ImageSource.I0.Sensor.WhiteBalance="
+            << kWhiteBalanceStrings[m_whiteBalance];
+    request << "&ImageSource.I0.Sensor.ColorLevel=" << m_colorLevel;
+    request << "&ImageSource.I0.Sensor.Exposure="
+            << kExposureControlStrings[m_exposureControl];
+    request << "&ImageSource.I0.Sensor.ExposurePriority=" << m_exposurePriority;
+    request << "&Image.I0.Stream.FPS=" << m_maxFPS;
+    request << "&Image.I0.Appearance.Resolution="
+            << kResolutionStrings[m_resolution];
+    request << "&Image.I0.Appearance.Compression=" << m_compression;
+    request << "&Image.I0.Appearance.Rotation=" << kRotationStrings[m_rotation];
+    m_parametersMutex.unlock();
+
+    request << " HTTP/1.1" << std::endl;
+    request << "User-Agent: HTTPStreamClient" << std::endl;
+    request << "Connection: Keep-Alive" << std::endl;
+    request << "Cache-Control: no-cache" << std::endl;
+    request << "Authorization: Basic RlJDOkZSQw==" << std::endl;
+    request << std::endl;
+
+    int socket = CreateCameraSocket(request.str(), false);
+    if (socket == -1) {
+      wpi_setErrnoErrorWithContext("Error setting camera parameters");
+    } else {
+      close(socket);
+      m_parametersDirty = false;
+
+      if (m_streamDirty) {
+        m_streamDirty = false;
+        return true;
+      }
+    }
+  }
+
+  return false;
+}
+
+/**
+ * Create a socket connected to camera
+ * Used to create a connection to the camera for both capturing images and
+ * setting parameters.
+ * @param requestString The initial request string to send upon successful
+ * connection.
+ * @param setError If true, rais an error if there's a problem creating the
+ * connection.
+ * This is only enabled after several unsucessful connections, so a single one
+ * doesn't
+ * cause an error message to be printed if it immediately recovers.
+ * @return -1 if failed, socket handle if successful.
+ */
+int AxisCamera::CreateCameraSocket(std::string const &requestString,
+                                   bool setError) {
+  struct addrinfo *address = nullptr;
+  int camSocket;
+
+  /* create socket */
+  if ((camSocket = socket(AF_INET, SOCK_STREAM, 0)) == -1) {
+    if (setError)
+      wpi_setErrnoErrorWithContext("Failed to create the camera socket");
+    return -1;
+  }
+
+  if (getaddrinfo(m_cameraHost.c_str(), "80", nullptr, &address) == -1) {
+    if (setError) {
+      wpi_setErrnoErrorWithContext("Failed to create the camera socket");
+      close(camSocket);
+    }
+    return -1;
+  }
+
+  /* connect to server */
+  if (connect(camSocket, address->ai_addr, address->ai_addrlen) == -1) {
+    if (setError)
+      wpi_setErrnoErrorWithContext("Failed to connect to the camera");
+    freeaddrinfo(address);
+    close(camSocket);
+    return -1;
+  }
+
+  freeaddrinfo(address);
+
+  int sent = send(camSocket, requestString.c_str(), requestString.size(), 0);
+  if (sent == -1) {
+    if (setError)
+      wpi_setErrnoErrorWithContext("Failed to send a request to the camera");
+    close(camSocket);
+    return -1;
+  }
+
+  return camSocket;
+}
diff --git a/wpilibc/Athena/src/Vision/BaeUtilities.cpp b/wpilibc/Athena/src/Vision/BaeUtilities.cpp
new file mode 100644
index 0000000..f09ec64
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/BaeUtilities.cpp
@@ -0,0 +1,369 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+#include <stdio.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <unistd.h>
+#include <string.h>
+#include <math.h>
+#include <stdlib.h>
+#include <stdarg.h>
+
+#include "Vision/BaeUtilities.h"
+#include "Servo.h"
+#include "Timer.h"
+
+/** @file
+ *   Utility functions
+ */
+
+/**
+ * debug output flag options:
+ * DEBUG_OFF, DEBUG_MOSTLY_OFF, DEBUG_SCREEN_ONLY, DEBUG_FILE_ONLY,
+ * DEBUG_SCREEN_AND_FILE
+ */
+static DebugOutputType dprintfFlag = DEBUG_OFF;
+
+/**
+ * Set the debug flag to print to screen, file on cRIO, both or neither
+ * @param tempString The format string.
+ */
+void SetDebugFlag(DebugOutputType flag) { dprintfFlag = flag; }
+
+/**
+ * Debug print to a file and/or a terminal window.
+ * Call like you would call printf.
+ * Set functionName in the function if you want the correct function name to
+ * print out.
+ * The file line number will also be printed.
+ * @param tempString The format string.
+ */
+void dprintf(const char *tempString, ...) /* Variable argument list */
+{
+  va_list args;    /* Input argument list */
+  int line_number; /* Line number passed in argument */
+  int type;
+  const char *functionName; /* Format passed in argument */
+  const char *fmt;          /* Format passed in argument */
+  char text[512];           /* Text string */
+  char outtext[512];        /* Text string */
+  FILE *outfile_fd;         /* Output file pointer */
+  char filepath[128];       /* Text string */
+  int fatalFlag = 0;
+  const char *filename;
+  int index;
+  int tempStringLen;
+
+  if (dprintfFlag == DEBUG_OFF) {
+    return;
+  }
+
+  va_start(args, tempString);
+
+  tempStringLen = strlen(tempString);
+  filename = tempString;
+  for (index = 0; index < tempStringLen; index++) {
+    if (tempString[index] == ' ') {
+      printf("ERROR in dprintf: malformed calling sequence (%s)\n", tempString);
+      va_end(args);
+      return;
+    }
+    if (tempString[index] == '\\' || tempString[index] == '/')
+      filename = tempString + index + 1;
+  }
+
+  /* Extract function name */
+  functionName = va_arg(args, const char *);
+
+  /* Extract line number from argument list */
+  line_number = va_arg(args, int);
+
+  /* Extract information type from argument list */
+  type = va_arg(args, int);
+
+  /* Extract format from argument list */
+  fmt = va_arg(args, const char *);
+
+  vsprintf(text, fmt, args);
+
+  va_end(args);
+
+  /* Format output statement */
+  switch (type) {
+    case DEBUG_TYPE:
+      sprintf(outtext, "[%s:%s@%04d] DEBUG %s\n", filename, functionName,
+              line_number, text);
+      break;
+    case INFO_TYPE:
+      sprintf(outtext, "[%s:%s@%04d] INFO %s\n", filename, functionName,
+              line_number, text);
+      break;
+    case ERROR_TYPE:
+      sprintf(outtext, "[%s:%s@%04d] ERROR %s\n", filename, functionName,
+              line_number, text);
+      break;
+    case CRITICAL_TYPE:
+      sprintf(outtext, "[%s:%s@%04d] CRITICAL %s\n", filename, functionName,
+              line_number, text);
+      break;
+    case FATAL_TYPE:
+      fatalFlag = 1;
+      sprintf(outtext, "[%s:%s@%04d] FATAL %s\n", filename, functionName,
+              line_number, text);
+      break;
+    default:
+      printf("ERROR in dprintf: malformed calling sequence\n");
+      return;
+      break;
+  }
+
+  sprintf(filepath, "%s.debug", filename);
+
+  /* Write output statement */
+  switch (dprintfFlag) {
+    default:
+    case DEBUG_OFF:
+      break;
+    case DEBUG_MOSTLY_OFF:
+      if (fatalFlag) {
+        if ((outfile_fd = fopen(filepath, "a+")) != nullptr) {
+          fwrite(outtext, sizeof(char), strlen(outtext), outfile_fd);
+          fclose(outfile_fd);
+        }
+      }
+      break;
+    case DEBUG_SCREEN_ONLY:
+      printf("%s", outtext);
+      break;
+    case DEBUG_FILE_ONLY:
+      if ((outfile_fd = fopen(filepath, "a+")) != nullptr) {
+        fwrite(outtext, sizeof(char), strlen(outtext), outfile_fd);
+        fclose(outfile_fd);
+      }
+      break;
+    case DEBUG_SCREEN_AND_FILE:  // BOTH
+      printf("%s", outtext);
+      if ((outfile_fd = fopen(filepath, "a+")) != nullptr) {
+        fwrite(outtext, sizeof(char), strlen(outtext), outfile_fd);
+        fclose(outfile_fd);
+      }
+      break;
+  }
+}
+
+/**
+ * @brief Normalizes a value in a range, used for drive input
+ * @param position The position in the range, starting at 0
+ * @param range The size of the range that position is in
+ * @return The normalized position from -1 to +1
+ */
+double RangeToNormalized(double position, int range) {
+  return (((position * 2.0) / (double)range) - 1.0);
+}
+
+/**
+ * @brief Convert a normalized value to the corresponding value in a range.
+ * This is used to convert normalized values to the servo command range.
+ * @param normalizedValue The normalized value (in the -1 to +1 range)
+ * @param minRange The minimum of the range (0 is default)
+ * @param maxRange The maximum of the range (1 is default)
+ * @return The value in the range corresponding to the input normalized value
+ */
+float NormalizeToRange(float normalizedValue, float minRange, float maxRange) {
+  float range = maxRange - minRange;
+  float temp = (float)((normalizedValue / 2.0) + 0.5) * range;
+  return (temp + minRange);
+}
+float NormalizeToRange(float normalizedValue) {
+  return (float)((normalizedValue / 2.0) + 0.5);
+}
+
+/**
+ * @brief Displays an activity indicator to console.
+ * Call this function like you would call printf.
+ * @param fmt The format string
+*/
+void ShowActivity(char *fmt, ...) {
+  static char activity_indication_string[] = "|/-\\";
+  static int ai = 3;
+  va_list args;
+  char text[1024];
+
+  va_start(args, fmt);
+
+  vsprintf(text, fmt, args);
+
+  ai = ai == 3 ? 0 : ai + 1;
+
+  printf("%c %s \r", activity_indication_string[ai], text);
+  fflush(stdout);
+
+  va_end(args);
+}
+
+#define PI 3.14159265358979
+/**
+ * @brief Calculate sine wave increments (-1.0 to 1.0).
+ * The first time this is called, it sets up the time increment. Subsequent
+ * calls
+ * will give values along the sine wave depending on current time. If the wave
+ * is
+ * stopped and restarted, it must be reinitialized with a new "first call".
+ *
+ * @param period length of time to complete a complete wave
+ * @param sinStart Where to start the sine wave (0.0 = 2 pi, pi/2 = 1.0, etc.)
+ */
+double SinPosition(double *period, double sinStart) {
+  double rtnVal;
+  static double sinePeriod = 0.0;
+  static double timestamp;
+  double sinArg;
+
+  // 1st call
+  if (period != nullptr) {
+    sinePeriod = *period;
+    timestamp = GetTime();
+    return 0.0;
+  }
+
+  // Multiplying by 2*pi to the time difference makes sinePeriod work if it's
+  // measured in seconds.
+  // Adding sinStart to the part multiplied by PI, but not by 2, allows it to
+  // work as described in the comments.
+  sinArg = PI * ((2.0 * (GetTime() - timestamp)) + sinStart) / sinePeriod;
+  rtnVal = sin(sinArg);
+  return (rtnVal);
+}
+
+/**
+ * @brief Find the elapsed time since a specified time.
+ * @param startTime The starting time
+ * @return How long it has been since the starting time
+ */
+double ElapsedTime(double startTime) {
+  double realTime = GetTime();
+  return (realTime - startTime);
+}
+
+/**
+ * @brief Initialize pan parameters
+ * @param period The number of seconds to complete one pan
+ */
+void panInit() {
+  double period = 3.0;        // number of seconds for one complete pan
+  SinPosition(&period, 0.0);  // initial call to set up time
+}
+
+void panInit(double period) {
+  if (period < 0.0) period = 3.0;
+  SinPosition(&period, 0.0);  // initial call to set up time
+}
+
+/**
+ * @brief Move the horizontal servo back and forth.
+ * @param panServo The servo object to move
+ * @param sinStart The position on the sine wave to begin the pan
+ */
+void panForTarget(Servo *panServo) { panForTarget(panServo, 0.0); }
+
+void panForTarget(Servo *panServo, double sinStart) {
+  float normalizedSinPosition = (float)SinPosition(nullptr, sinStart);
+  float newServoPosition = NormalizeToRange(normalizedSinPosition);
+  panServo->Set(newServoPosition);
+  // ShowActivity ("pan x: normalized %f newServoPosition = %f" ,
+  //		normalizedSinPosition, newServoPosition );
+}
+
+/** @brief Read a file and return non-comment output string
+
+Call the first time with 0 lineNumber to get the number of lines to read
+Then call with each lineNumber to get one camera parameter. There should
+be one property=value entry on each line, i.e. "exposure=auto"
+
+ * @param inputFile filename to read
+ * @param outputString one string
+ * @param lineNumber if 0, return number of lines; else return that line number
+ * @return int number of lines or -1 if error
+ **/
+int processFile(char *inputFile, char *outputString, int lineNumber) {
+  FILE *infile;
+  const int stringSize = 80;  // max size of one line in file
+  char inputStr[stringSize];
+  inputStr[0] = '\0';
+  int lineCount = 0;
+
+  if (lineNumber < 0) return (-1);
+
+  if ((infile = fopen(inputFile, "r")) == nullptr) {
+    printf("Fatal error opening file %s\n", inputFile);
+    return (0);
+  }
+
+  while (!feof(infile)) {
+    if (fgets(inputStr, stringSize, infile) != nullptr) {
+      // Skip empty lines
+      if (emptyString(inputStr)) continue;
+      // Skip comment lines
+      if (inputStr[0] == '#' || inputStr[0] == '!') continue;
+
+      lineCount++;
+      if (lineNumber == 0)
+        continue;
+      else {
+        if (lineCount == lineNumber) break;
+      }
+    }
+  }
+
+  // close file
+  fclose(infile);
+  // if number lines requested return the count
+  if (lineNumber == 0) return (lineCount);
+  // check for input out of range
+  if (lineNumber > lineCount) return (-1);
+  // return the line selected; lineCount guaranteed to be greater than zero
+  stripString(inputStr);
+  strcpy(outputString, inputStr);
+  return (lineCount);
+}
+
+/** Ignore empty string
+ * @param string to check if empty
+ **/
+int emptyString(char *string) {
+  int i, len;
+
+  if (string == nullptr) return (1);
+
+  len = strlen(string);
+  for (i = 0; i < len; i++) {
+    // Ignore the following characters
+    if (string[i] == '\n' || string[i] == '\r' || string[i] == '\t' ||
+        string[i] == ' ')
+      continue;
+    return (0);
+  }
+  return (1);
+}
+
+/** Remove special characters from string
+ * @param string to process
+ **/
+void stripString(char *string) {
+  int i, j, len;
+
+  if (string == nullptr) return;
+
+  len = strlen(string);
+  for (i = 0, j = 0; i < len; i++) {
+    // Remove the following characters from the string
+    if (string[i] == '\n' || string[i] == '\r' || string[i] == '\"') continue;
+    // Copy anything else
+    string[j++] = string[i];
+  }
+  string[j] = '\0';
+}
diff --git a/wpilibc/Athena/src/Vision/BinaryImage.cpp b/wpilibc/Athena/src/Vision/BinaryImage.cpp
new file mode 100644
index 0000000..ea14cbc
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/BinaryImage.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/BinaryImage.h"
+#include "WPIErrors.h"
+#include <cstring>
+
+using namespace std;
+
+/**
+ * Get then number of particles for the image.
+ * @returns the number of particles found for the image.
+ */
+int BinaryImage::GetNumberParticles() {
+  int numParticles = 0;
+  int success = imaqCountParticles(m_imaqImage, 1, &numParticles);
+  wpi_setImaqErrorWithContext(success, "Error counting particles");
+  return numParticles;
+}
+
+/**
+ * Get a single particle analysis report.
+ * Get one (of possibly many) particle analysis reports for an image.
+ * @param particleNumber Which particle analysis report to return.
+ * @returns the selected particle analysis report
+ */
+ParticleAnalysisReport BinaryImage::GetParticleAnalysisReport(
+    int particleNumber) {
+  ParticleAnalysisReport par;
+  GetParticleAnalysisReport(particleNumber, &par);
+  return par;
+}
+
+/**
+ * Get a single particle analysis report.
+ * Get one (of possibly many) particle analysis reports for an image.
+ * This version could be more efficient when copying many reports.
+ * @param particleNumber Which particle analysis report to return.
+ * @param par the selected particle analysis report
+ */
+void BinaryImage::GetParticleAnalysisReport(int particleNumber,
+                                            ParticleAnalysisReport *par) {
+  int success;
+  int numParticles = 0;
+
+  success = imaqGetImageSize(m_imaqImage, &par->imageWidth, &par->imageHeight);
+  wpi_setImaqErrorWithContext(success, "Error getting image size");
+  if (StatusIsFatal()) return;
+
+  success = imaqCountParticles(m_imaqImage, 1, &numParticles);
+  wpi_setImaqErrorWithContext(success, "Error counting particles");
+  if (StatusIsFatal()) return;
+
+  if (particleNumber >= numParticles) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "particleNumber");
+    return;
+  }
+
+  par->particleIndex = particleNumber;
+  // Don't bother measuring the rest of the particle if one fails
+  bool good = ParticleMeasurement(particleNumber, IMAQ_MT_CENTER_OF_MASS_X,
+                                  &par->center_mass_x);
+  good = good && ParticleMeasurement(particleNumber, IMAQ_MT_CENTER_OF_MASS_Y,
+                                     &par->center_mass_y);
+  good = good &&
+         ParticleMeasurement(particleNumber, IMAQ_MT_AREA, &par->particleArea);
+  good = good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_TOP,
+                                     &par->boundingRect.top);
+  good = good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_LEFT,
+                                     &par->boundingRect.left);
+  good =
+      good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_HEIGHT,
+                                  &par->boundingRect.height);
+  good =
+      good && ParticleMeasurement(particleNumber, IMAQ_MT_BOUNDING_RECT_WIDTH,
+                                  &par->boundingRect.width);
+  good = good && ParticleMeasurement(particleNumber, IMAQ_MT_AREA_BY_IMAGE_AREA,
+                                     &par->particleToImagePercent);
+  good = good && ParticleMeasurement(particleNumber,
+                                     IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA,
+                                     &par->particleQuality);
+
+  if (good) {
+    /* normalized position (-1 to 1) */
+    par->center_mass_x_normalized =
+        NormalizeFromRange(par->center_mass_x, par->imageWidth);
+    par->center_mass_y_normalized =
+        NormalizeFromRange(par->center_mass_y, par->imageHeight);
+  }
+}
+
+/**
+ * Get an ordered vector of particles for the image.
+ * Create a vector of particle analysis reports sorted by size for an image.
+ * The vector contains the actual report structures.
+ * @returns a pointer to the vector of particle analysis reports. The caller
+ * must delete the
+ * vector when finished using it.
+ */
+vector<ParticleAnalysisReport> *
+BinaryImage::GetOrderedParticleAnalysisReports() {
+  auto particles = new vector<ParticleAnalysisReport>;
+  int particleCount = GetNumberParticles();
+  for (int particleIndex = 0; particleIndex < particleCount; particleIndex++) {
+    particles->push_back(GetParticleAnalysisReport(particleIndex));
+  }
+  // TODO: This is pretty inefficient since each compare in the sort copies
+  //   both reports being compared... do it manually instead... while we're
+  //   at it, we should provide a version that allows a preallocated buffer of
+  //   ParticleAnalysisReport structures
+  sort(particles->begin(), particles->end(), CompareParticleSizes);
+  return particles;
+}
+
+/**
+ * Write a binary image to flash.
+ * Writes the binary image to flash on the cRIO for later inspection.
+ * @param fileName the name of the image file written to the flash.
+ */
+void BinaryImage::Write(const char *fileName) {
+  RGBValue colorTable[256];
+  memset(colorTable, 0, sizeof(colorTable));
+  colorTable[0].R = 0;
+  colorTable[1].R = 255;
+  colorTable[0].G = colorTable[1].G = 0;
+  colorTable[0].B = colorTable[1].B = 0;
+  colorTable[0].alpha = colorTable[1].alpha = 0;
+  imaqWriteFile(m_imaqImage, fileName, colorTable);
+}
+
+/**
+ * Measure a single parameter for an image.
+ * Get the measurement for a single parameter about an image by calling the
+ * imaqMeasureParticle
+ * function for the selected parameter.
+ * @param particleNumber which particle in the set of particles
+ * @param whatToMeasure the imaq MeasurementType (what to measure)
+ * @param result the value of the measurement
+ * @returns false on failure, true on success
+ */
+bool BinaryImage::ParticleMeasurement(int particleNumber,
+                                      MeasurementType whatToMeasure,
+                                      int *result) {
+  double resultDouble;
+  bool success =
+      ParticleMeasurement(particleNumber, whatToMeasure, &resultDouble);
+  *result = (int)resultDouble;
+  return success;
+}
+
+/**
+ * Measure a single parameter for an image.
+ * Get the measurement for a single parameter about an image by calling the
+ * imaqMeasureParticle
+ * function for the selected parameter.
+ * @param particleNumber which particle in the set of particles
+ * @param whatToMeasure the imaq MeasurementType (what to measure)
+ * @param result the value of the measurement
+ * @returns true on failure, false on success
+ */
+bool BinaryImage::ParticleMeasurement(int particleNumber,
+                                      MeasurementType whatToMeasure,
+                                      double *result) {
+  int success;
+  success = imaqMeasureParticle(m_imaqImage, particleNumber, 0, whatToMeasure,
+                                result);
+  wpi_setImaqErrorWithContext(success, "Error measuring particle");
+  return !StatusIsFatal();
+}
+
+// Normalizes to [-1,1]
+double BinaryImage::NormalizeFromRange(double position, int range) {
+  return (position * 2.0 / (double)range) - 1.0;
+}
+
+/**
+ * The compare helper function for sort.
+ * This function compares two particle analysis reports as a helper for the sort
+ * function.
+ * @param particle1 The first particle to compare
+ * @param particle2 the second particle to compare
+ * @returns true if particle1 is greater than particle2
+ */
+bool BinaryImage::CompareParticleSizes(ParticleAnalysisReport particle1,
+                                       ParticleAnalysisReport particle2) {
+  // we want descending sort order
+  return particle1.particleToImagePercent > particle2.particleToImagePercent;
+}
+
+BinaryImage *BinaryImage::RemoveSmallObjects(bool connectivity8, int erosions) {
+  auto result = new BinaryImage();
+  int success = imaqSizeFilter(result->GetImaqImage(), m_imaqImage,
+                               connectivity8, erosions, IMAQ_KEEP_LARGE, nullptr);
+  wpi_setImaqErrorWithContext(success, "Error in RemoveSmallObjects");
+  return result;
+}
+
+BinaryImage *BinaryImage::RemoveLargeObjects(bool connectivity8, int erosions) {
+  auto result = new BinaryImage();
+  int success = imaqSizeFilter(result->GetImaqImage(), m_imaqImage,
+                               connectivity8, erosions, IMAQ_KEEP_SMALL, nullptr);
+  wpi_setImaqErrorWithContext(success, "Error in RemoveLargeObjects");
+  return result;
+}
+
+BinaryImage *BinaryImage::ConvexHull(bool connectivity8) {
+  auto result = new BinaryImage();
+  int success =
+      imaqConvexHull(result->GetImaqImage(), m_imaqImage, connectivity8);
+  wpi_setImaqErrorWithContext(success, "Error in convex hull operation");
+  return result;
+}
+
+BinaryImage *BinaryImage::ParticleFilter(ParticleFilterCriteria2 *criteria,
+                                         int criteriaCount) {
+  auto result = new BinaryImage();
+  int numParticles;
+  ParticleFilterOptions2 filterOptions = {0, 0, 0, 1};
+  int success =
+      imaqParticleFilter4(result->GetImaqImage(), m_imaqImage, criteria,
+                          criteriaCount, &filterOptions, nullptr, &numParticles);
+  wpi_setImaqErrorWithContext(success, "Error in particle filter operation");
+  return result;
+}
diff --git a/wpilibc/Athena/src/Vision/ColorImage.cpp b/wpilibc/Athena/src/Vision/ColorImage.cpp
new file mode 100644
index 0000000..bbbc242
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/ColorImage.cpp
@@ -0,0 +1,444 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/ColorImage.h"
+
+#include "WPIErrors.h"
+
+ColorImage::ColorImage(ImageType type) : ImageBase(type) {}
+
+/**
+ * Perform a threshold operation on a ColorImage.
+ * Perform a threshold operation on a ColorImage using the ColorMode supplied
+ * as a parameter.
+ * @param colorMode The type of colorspace this operation should be performed in
+ * @returns a pointer to a binary image
+ */
+BinaryImage *ColorImage::ComputeThreshold(ColorMode colorMode, int low1,
+                                          int high1, int low2, int high2,
+                                          int low3, int high3) {
+  auto result = new BinaryImage();
+  Range range1 = {low1, high1}, range2 = {low2, high2}, range3 = {low3, high3};
+
+  int success = imaqColorThreshold(result->GetImaqImage(), m_imaqImage, 1,
+                                   colorMode, &range1, &range2, &range3);
+  wpi_setImaqErrorWithContext(success, "ImaqThreshold error");
+  return result;
+}
+
+/**
+ * Perform a threshold in RGB space.
+ * @param redLow Red low value
+ * @param redHigh Red high value
+ * @param greenLow Green low value
+ * @param greenHigh Green high value
+ * @param blueLow Blue low value
+ * @param blueHigh Blue high value
+ * @returns A pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdRGB(int redLow, int redHigh, int greenLow,
+                                      int greenHigh, int blueLow,
+                                      int blueHigh) {
+  return ComputeThreshold(IMAQ_RGB, redLow, redHigh, greenLow, greenHigh,
+                          blueLow, blueHigh);
+}
+
+/**
+ * Perform a threshold in RGB space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdRGB(Threshold &t) {
+  return ComputeThreshold(IMAQ_RGB, t.plane1Low, t.plane1High, t.plane2Low,
+                          t.plane2High, t.plane3Low, t.plane3High);
+}
+
+/**
+ * Perform a threshold in HSL space.
+ * @param hueLow Low value for hue
+ * @param hueHigh High value for hue
+ * @param saturationLow Low value for saturation
+ * @param saturationHigh High value for saturation
+ * @param luminenceLow Low value for luminence
+ * @param luminenceHigh High value for luminence
+ * @returns a pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSL(int hueLow, int hueHigh,
+                                      int saturationLow, int saturationHigh,
+                                      int luminenceLow, int luminenceHigh) {
+  return ComputeThreshold(IMAQ_HSL, hueLow, hueHigh, saturationLow,
+                          saturationHigh, luminenceLow, luminenceHigh);
+}
+
+/**
+ * Perform a threshold in HSL space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSL(Threshold &t) {
+  return ComputeThreshold(IMAQ_HSL, t.plane1Low, t.plane1High, t.plane2Low,
+                          t.plane2High, t.plane3Low, t.plane3High);
+}
+
+/**
+ * Perform a threshold in HSV space.
+ * @param hueLow Low value for hue
+ * @param hueHigh High value for hue
+ * @param saturationLow Low value for saturation
+ * @param saturationHigh High value for saturation
+ * @param valueLow Low value
+ * @param valueHigh High value
+ * @returns a pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSV(int hueLow, int hueHigh,
+                                      int saturationLow, int saturationHigh,
+                                      int valueLow, int valueHigh) {
+  return ComputeThreshold(IMAQ_HSV, hueLow, hueHigh, saturationLow,
+                          saturationHigh, valueLow, valueHigh);
+}
+
+/**
+ * Perform a threshold in HSV space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSV(Threshold &t) {
+  return ComputeThreshold(IMAQ_HSV, t.plane1Low, t.plane1High, t.plane2Low,
+                          t.plane2High, t.plane3Low, t.plane3High);
+}
+
+/**
+ * Perform a threshold in HSI space.
+ * @param hueLow Low value for hue
+ * @param hueHigh High value for hue
+ * @param saturationLow Low value for saturation
+ * @param saturationHigh High value for saturation
+ * @param valueLow Low intensity
+ * @param valueHigh High intensity
+ * @returns a pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSI(int hueLow, int hueHigh,
+                                      int saturationLow, int saturationHigh,
+                                      int intensityLow, int intensityHigh) {
+  return ComputeThreshold(IMAQ_HSI, hueLow, hueHigh, saturationLow,
+                          saturationHigh, intensityLow, intensityHigh);
+}
+
+/**
+ * Perform a threshold in HSI space.
+ * @param threshold a reference to the Threshold object to use.
+ * @returns A pointer to a BinaryImage that represents the result of the
+ * threshold operation.
+ */
+BinaryImage *ColorImage::ThresholdHSI(Threshold &t) {
+  return ComputeThreshold(IMAQ_HSI, t.plane1Low, t.plane1High, t.plane2Low,
+                          t.plane2High, t.plane3Low, t.plane3High);
+}
+
+/**
+ * Extract a color plane from the image
+ * @param mode The ColorMode to use for the plane extraction
+ * @param planeNumber Which plane is to be extracted
+ * @returns A pointer to a MonoImage that represents the extracted plane.
+ */
+MonoImage *ColorImage::ExtractColorPlane(ColorMode mode, int planeNumber) {
+  auto result = new MonoImage();
+  if (m_imaqImage == nullptr) wpi_setWPIError(NullParameter);
+  int success = imaqExtractColorPlanes(
+      m_imaqImage, mode, (planeNumber == 1) ? result->GetImaqImage() : nullptr,
+      (planeNumber == 2) ? result->GetImaqImage() : nullptr,
+      (planeNumber == 3) ? result->GetImaqImage() : nullptr);
+  wpi_setImaqErrorWithContext(success, "Imaq ExtractColorPlanes failed");
+  return result;
+}
+
+/*
+ * Extract the first color plane for an image.
+ * @param mode The color mode in which to operate
+ * @returns a pointer to a MonoImage that is the extracted plane.
+ */
+MonoImage *ColorImage::ExtractFirstColorPlane(ColorMode mode) {
+  return ExtractColorPlane(mode, 1);
+}
+
+/*
+ * Extract the second color plane for an image.
+ * @param mode The color mode in which to operate
+ * @returns a pointer to a MonoImage that is the extracted plane.
+ */
+MonoImage *ColorImage::ExtractSecondColorPlane(ColorMode mode) {
+  return ExtractColorPlane(mode, 2);
+}
+
+/*
+ * Extract the third color plane for an image.
+ * @param mode The color mode in which to operate
+ * @returns a pointer to a MonoImage that is the extracted plane.
+ */
+MonoImage *ColorImage::ExtractThirdColorPlane(ColorMode mode) {
+  return ExtractColorPlane(mode, 3);
+}
+
+/*
+ * Extract the red plane from an RGB image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetRedPlane() {
+  return ExtractFirstColorPlane(IMAQ_RGB);
+}
+
+/*
+ * Extract the green plane from an RGB image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetGreenPlane() {
+  return ExtractSecondColorPlane(IMAQ_RGB);
+}
+
+/*
+ * Extract the blue plane from an RGB image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetBluePlane() {
+  return ExtractThirdColorPlane(IMAQ_RGB);
+}
+
+/*
+ * Extract the Hue plane from an HSL image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetHSLHuePlane() {
+  return ExtractFirstColorPlane(IMAQ_HSL);
+}
+
+/*
+ * Extract the Hue plane from an HSV image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetHSVHuePlane() {
+  return ExtractFirstColorPlane(IMAQ_HSV);
+}
+
+/*
+ * Extract the Hue plane from an HSI image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetHSIHuePlane() {
+  return ExtractFirstColorPlane(IMAQ_HSI);
+}
+
+/*
+ * Extract the Luminance plane from an HSL image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetLuminancePlane() {
+  return ExtractThirdColorPlane(IMAQ_HSL);
+}
+
+/*
+ * Extract the Value plane from an HSV image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetValuePlane() {
+  return ExtractThirdColorPlane(IMAQ_HSV);
+}
+
+/*
+ * Extract the Intensity plane from an HSI image.
+ * @returns a pointer to a MonoImage that is the extraced plane.
+ */
+MonoImage *ColorImage::GetIntensityPlane() {
+  return ExtractThirdColorPlane(IMAQ_HSI);
+}
+
+/**
+ * Replace a plane in the ColorImage with a MonoImage
+ * Replaces a single plane in the image with a MonoImage
+ * @param mode The ColorMode in which to operate
+ * @param plane The pointer to the replacement plane as a MonoImage
+ * @param planeNumber The plane number (1, 2, 3) to replace
+ */
+void ColorImage::ReplacePlane(ColorMode mode, MonoImage *plane,
+                              int planeNumber) {
+  int success =
+      imaqReplaceColorPlanes(m_imaqImage, (const Image *)m_imaqImage, mode,
+                             (planeNumber == 1) ? plane->GetImaqImage() : nullptr,
+                             (planeNumber == 2) ? plane->GetImaqImage() : nullptr,
+                             (planeNumber == 3) ? plane->GetImaqImage() : nullptr);
+  wpi_setImaqErrorWithContext(success, "Imaq ReplaceColorPlanes failed");
+}
+
+/**
+ * Replace the first color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceFirstColorPlane(ColorMode mode, MonoImage *plane) {
+  ReplacePlane(mode, plane, 1);
+}
+
+/**
+ * Replace the second color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceSecondColorPlane(ColorMode mode, MonoImage *plane) {
+  ReplacePlane(mode, plane, 2);
+}
+
+/**
+ * Replace the third color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceThirdColorPlane(ColorMode mode, MonoImage *plane) {
+  ReplacePlane(mode, plane, 3);
+}
+
+/**
+ * Replace the red color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceRedPlane(MonoImage *plane) {
+  ReplaceFirstColorPlane(IMAQ_RGB, plane);
+}
+
+/**
+ * Replace the green color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceGreenPlane(MonoImage *plane) {
+  ReplaceSecondColorPlane(IMAQ_RGB, plane);
+}
+
+/**
+ * Replace the blue color plane with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceBluePlane(MonoImage *plane) {
+  ReplaceThirdColorPlane(IMAQ_RGB, plane);
+}
+
+/**
+ * Replace the Hue color plane in a HSL image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceHSLHuePlane(MonoImage *plane) {
+  return ReplaceFirstColorPlane(IMAQ_HSL, plane);
+}
+
+/**
+ * Replace the Hue color plane in a HSV image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceHSVHuePlane(MonoImage *plane) {
+  return ReplaceFirstColorPlane(IMAQ_HSV, plane);
+}
+
+/**
+ * Replace the first Hue plane in a HSI image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceHSIHuePlane(MonoImage *plane) {
+  return ReplaceFirstColorPlane(IMAQ_HSI, plane);
+}
+
+/**
+ * Replace the Saturation color plane in an HSL image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceHSLSaturationPlane(MonoImage *plane) {
+  return ReplaceSecondColorPlane(IMAQ_HSL, plane);
+}
+
+/**
+ * Replace the Saturation color plane in a HSV image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceHSVSaturationPlane(MonoImage *plane) {
+  return ReplaceSecondColorPlane(IMAQ_HSV, plane);
+}
+
+/**
+ * Replace the Saturation color plane in a HSI image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceHSISaturationPlane(MonoImage *plane) {
+  return ReplaceSecondColorPlane(IMAQ_HSI, plane);
+}
+
+/**
+ * Replace the Luminance color plane in an HSL image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceLuminancePlane(MonoImage *plane) {
+  return ReplaceThirdColorPlane(IMAQ_HSL, plane);
+}
+
+/**
+ * Replace the Value color plane in an HSV with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceValuePlane(MonoImage *plane) {
+  return ReplaceThirdColorPlane(IMAQ_HSV, plane);
+}
+
+/**
+ * Replace the Intensity color plane in a HSI image with a MonoImage.
+ * @param mode The color mode in which to operate.
+ * @param plane A pointer to a MonoImage that will replace the specified color
+ * plane.
+ */
+void ColorImage::ReplaceIntensityPlane(MonoImage *plane) {
+  return ReplaceThirdColorPlane(IMAQ_HSI, plane);
+}
+
+// TODO: frcColorEqualize(Image* dest, const Image* source, int
+// colorEqualization) needs to be modified
+// The colorEqualization parameter is discarded and is set to TRUE in the call
+// to imaqColorEqualize.
+void ColorImage::Equalize(bool allPlanes) {
+  // Note that this call uses NI-defined TRUE and FALSE
+  int success = imaqColorEqualize(m_imaqImage, (const Image *)m_imaqImage,
+                                  (allPlanes) ? TRUE : FALSE);
+  wpi_setImaqErrorWithContext(success, "Imaq ColorEqualize error");
+}
+
+void ColorImage::ColorEqualize() { Equalize(true); }
+
+void ColorImage::LuminanceEqualize() { Equalize(false); }
diff --git a/wpilibc/Athena/src/Vision/FrcError.cpp b/wpilibc/Athena/src/Vision/FrcError.cpp
new file mode 100644
index 0000000..f0b4725
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/FrcError.cpp
@@ -0,0 +1,2403 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "nivision.h"
+#include "Vision/FrcError.h"
+
+/**
+ * Get the error code returned from the NI Vision library
+ * @return The last error code.
+ */
+int GetLastVisionError() {
+  // int errorCode = imaqGetLastVisionError();     // error code: 0 = no error
+  // char* errorText = GetVisionErrorText(errorCode);
+  // dprintf (LOG_DEBUG, "Error = %i  %s ", errorCode, errorText);
+  return imaqGetLastError();
+}
+
+/**
+* Get the error text for an NI Vision error code.
+* Note: imaqGetErrorText() is not supported on real time system, so
+* so relevant strings are hardcoded here - the maintained version is
+* in the LabWindows/CVI help file.
+* @param errorCode The error code to find the text for.
+* @return The error text
+*/
+const char* GetVisionErrorText(int errorCode) {
+  const char* errorText;
+
+  switch (errorCode) {
+    default: {
+      errorText = "UNKNOWN_ERROR";
+      break;
+    }
+    case -1074395138: {
+      errorText = "ERR_OCR_REGION_TOO_SMALL";
+      break;
+    }
+    case -1074395139: {
+      errorText = "ERR_IMAQ_QR_DIMENSION_INVALID";
+      break;
+    }
+    case -1074395140: {
+      errorText = "ERR_OCR_CHAR_REPORT_CORRUPTED";
+      break;
+    }
+    case -1074395141: {
+      errorText = "ERR_OCR_NO_TEXT_FOUND";
+      break;
+    }
+    case -1074395142: {
+      errorText = "ERR_QR_DETECTION_MODELTYPE";
+      break;
+    }
+    case -1074395143: {
+      errorText = "ERR_QR_DETECTION_MODE";
+      break;
+    }
+    case -1074395144: {
+      errorText = "ERR_QR_INVALID_BARCODE";
+      break;
+    }
+    case -1074395145: {
+      errorText = "ERR_QR_INVALID_READ";
+      break;
+    }
+    case -1074395146: {
+      errorText = "ERR_QR_DETECTION_VERSION";
+      break;
+    }
+    case -1074395147: {
+      errorText = "ERR_BARCODE_RSSLIMITED";
+      break;
+    }
+    case -1074395148: {
+      errorText = "ERR_OVERLAY_GROUP_NOT_FOUND";
+      break;
+    }
+    case -1074395149: {
+      errorText = "ERR_DUPLICATE_TRANSFORM_TYPE";
+      break;
+    }
+    case -1074395151: {
+      errorText = "ERR_OCR_CORRECTION_FAILED";
+      break;
+    }
+    case -1074395155: {
+      errorText = "ERR_OCR_ORIENT_DETECT_FAILED";
+      break;
+    }
+    case -1074395156: {
+      errorText = "ERR_OCR_SKEW_DETECT_FAILED";
+      break;
+    }
+    case -1074395158: {
+      errorText = "ERR_OCR_INVALID_CONTRASTMODE";
+      break;
+    }
+    case -1074395159: {
+      errorText = "ERR_OCR_INVALID_TOLERANCE";
+      break;
+    }
+    case -1074395160: {
+      errorText = "ERR_OCR_INVALID_MAXPOINTSIZE";
+      break;
+    }
+    case -1074395161: {
+      errorText = "ERR_OCR_INVALID_CORRECTIONLEVEL";
+      break;
+    }
+    case -1074395162: {
+      errorText = "ERR_OCR_INVALID_CORRECTIONMODE";
+      break;
+    }
+    case -1074395163: {
+      errorText = "ERR_OCR_INVALID_CHARACTERPREFERENCE";
+      break;
+    }
+    case -1074395164: {
+      errorText = "ERR_OCR_ADD_WORD_FAILED";
+      break;
+    }
+    case -1074395165: {
+      errorText = "ERR_OCR_WTS_DIR_NOT_FOUND";
+      break;
+    }
+    case -1074395166: {
+      errorText = "ERR_OCR_BIN_DIR_NOT_FOUND";
+      break;
+    }
+    case -1074395167: {
+      errorText = "ERR_OCR_INVALID_OUTPUTDELIMITER";
+      break;
+    }
+    case -1074395168: {
+      errorText = "ERR_OCR_INVALID_AUTOCORRECTIONMODE";
+      break;
+    }
+    case -1074395169: {
+      errorText = "ERR_OCR_INVALID_RECOGNITIONMODE";
+      break;
+    }
+    case -1074395170: {
+      errorText = "ERR_OCR_INVALID_CHARACTERTYPE";
+      break;
+    }
+    case -1074395171: {
+      errorText = "ERR_OCR_INI_FILE_NOT_FOUND";
+      break;
+    }
+    case -1074395172: {
+      errorText = "ERR_OCR_INVALID_CHARACTERSET";
+      break;
+    }
+    case -1074395173: {
+      errorText = "ERR_OCR_INVALID_LANGUAGE";
+      break;
+    }
+    case -1074395174: {
+      errorText = "ERR_OCR_INVALID_AUTOORIENTMODE";
+      break;
+    }
+    case -1074395175: {
+      errorText = "ERR_OCR_BAD_USER_DICTIONARY";
+      break;
+    }
+    case -1074395178: {
+      errorText = "ERR_OCR_RECOGNITION_FAILED";
+      break;
+    }
+    case -1074395179: {
+      errorText = "ERR_OCR_PREPROCESSING_FAILED";
+      break;
+    }
+    case -1074395200: {
+      errorText = "ERR_OCR_INVALID_PARAMETER";
+      break;
+    }
+    case -1074395201: {
+      errorText = "ERR_OCR_LOAD_LIBRARY";
+      break;
+    }
+    case -1074395203: {
+      errorText = "ERR_OCR_LIB_INIT";
+      break;
+    }
+    case -1074395210: {
+      errorText = "ERR_OCR_CANNOT_MATCH_TEXT_TEMPLATE";
+      break;
+    }
+    case -1074395211: {
+      errorText = "ERR_OCR_BAD_TEXT_TEMPLATE";
+      break;
+    }
+    case -1074395212: {
+      errorText = "ERR_OCR_TEMPLATE_WRONG_SIZE";
+      break;
+    }
+    case -1074395233: {
+      errorText = "ERR_TEMPLATE_IMAGE_TOO_LARGE";
+      break;
+    }
+    case -1074395234: {
+      errorText = "ERR_TEMPLATE_IMAGE_TOO_SMALL";
+      break;
+    }
+    case -1074395235: {
+      errorText = "ERR_TEMPLATE_IMAGE_CONTRAST_TOO_LOW";
+      break;
+    }
+    case -1074395237: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_SHIFT_1";
+      break;
+    }
+    case -1074395238: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_NOSHIFT";
+      break;
+    }
+    case -1074395239: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_SHIFT";
+      break;
+    }
+    case -1074395240: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_ROTATION_1";
+      break;
+    }
+    case -1074395241: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_NOROTATION";
+      break;
+    }
+    case -1074395242: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_ROTATION";
+      break;
+    }
+    case -1074395243: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_4";
+      break;
+    }
+    case -1074395244: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_3";
+      break;
+    }
+    case -1074395245: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_2";
+      break;
+    }
+    case -1074395246: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR_1";
+      break;
+    }
+    case -1074395247: {
+      errorText = "ERR_TEMPLATE_DESCRIPTOR";
+      break;
+    }
+    case -1074395248: {
+      errorText = "ERR_TOO_MANY_ROTATION_ANGLE_RANGES";
+      break;
+    }
+    case -1074395249: {
+      errorText = "ERR_ROTATION_ANGLE_RANGE_TOO_LARGE";
+      break;
+    }
+    case -1074395250: {
+      errorText = "ERR_MATCH_SETUP_DATA";
+      break;
+    }
+    case -1074395251: {
+      errorText = "ERR_INVALID_MATCH_MODE";
+      break;
+    }
+    case -1074395252: {
+      errorText = "ERR_LEARN_SETUP_DATA";
+      break;
+    }
+    case -1074395253: {
+      errorText = "ERR_INVALID_LEARN_MODE";
+      break;
+    }
+    case -1074395256: {
+      errorText = "ERR_EVEN_WINDOW_SIZE";
+      break;
+    }
+    case -1074395257: {
+      errorText = "ERR_INVALID_EDGE_DIR";
+      break;
+    }
+    case -1074395258: {
+      errorText = "ERR_BAD_FILTER_WIDTH";
+      break;
+    }
+    case -1074395260: {
+      errorText = "ERR_HEAP_TRASHED";
+      break;
+    }
+    case -1074395261: {
+      errorText = "ERR_GIP_RANGE";
+      break;
+    }
+    case -1074395262: {
+      errorText = "ERR_LCD_BAD_MATCH";
+      break;
+    }
+    case -1074395263: {
+      errorText = "ERR_LCD_NO_SEGMENTS";
+      break;
+    }
+    case -1074395265: {
+      errorText = "ERR_BARCODE";
+      break;
+    }
+    case -1074395267: {
+      errorText = "ERR_COMPLEX_ROOT";
+      break;
+    }
+    case -1074395268: {
+      errorText = "ERR_LINEAR_COEFF";
+      break;
+    }
+    case -1074395269: {
+      errorText = "ERR_nullptr_POINTER";
+      break;
+    }
+    case -1074395270: {
+      errorText = "ERR_DIV_BY_ZERO";
+      break;
+    }
+    case -1074395275: {
+      errorText = "ERR_INVALID_BROWSER_IMAGE";
+      break;
+    }
+    case -1074395276: {
+      errorText = "ERR_LINES_PARALLEL";
+      break;
+    }
+    case -1074395277: {
+      errorText = "ERR_BARCODE_CHECKSUM";
+      break;
+    }
+    case -1074395278: {
+      errorText = "ERR_LCD_NOT_NUMERIC";
+      break;
+    }
+    case -1074395279: {
+      errorText = "ERR_ROI_NOT_POLYGON";
+      break;
+    }
+    case -1074395280: {
+      errorText = "ERR_ROI_NOT_RECT";
+      break;
+    }
+    case -1074395281: {
+      errorText = "ERR_IMAGE_SMALLER_THAN_BORDER";
+      break;
+    }
+    case -1074395282: {
+      errorText = "ERR_CANT_DRAW_INTO_VIEWER";
+      break;
+    }
+    case -1074395283: {
+      errorText = "ERR_INVALID_RAKE_DIRECTION";
+      break;
+    }
+    case -1074395284: {
+      errorText = "ERR_INVALID_EDGE_PROCESS";
+      break;
+    }
+    case -1074395285: {
+      errorText = "ERR_INVALID_SPOKE_DIRECTION";
+      break;
+    }
+    case -1074395286: {
+      errorText = "ERR_INVALID_CONCENTRIC_RAKE_DIRECTION";
+      break;
+    }
+    case -1074395287: {
+      errorText = "ERR_INVALID_LINE";
+      break;
+    }
+    case -1074395290: {
+      errorText = "ERR_SHAPEMATCH_BADTEMPLATE";
+      break;
+    }
+    case -1074395291: {
+      errorText = "ERR_SHAPEMATCH_BADIMAGEDATA";
+      break;
+    }
+    case -1074395292: {
+      errorText = "ERR_POINTS_ARE_COLLINEAR";
+      break;
+    }
+    case -1074395293: {
+      errorText = "ERR_CONTOURID_NOT_FOUND";
+      break;
+    }
+    case -1074395294: {
+      errorText = "ERR_CONTOUR_INDEX_OUT_OF_RANGE";
+      break;
+    }
+    case -1074395295: {
+      errorText = "ERR_INVALID_INTERPOLATIONMETHOD_INTERPOLATEPOINTS";
+      break;
+    }
+    case -1074395296: {
+      errorText = "ERR_INVALID_BARCODETYPE";
+      break;
+    }
+    case -1074395297: {
+      errorText = "ERR_INVALID_PARTICLEINFOMODE";
+      break;
+    }
+    case -1074395298: {
+      errorText = "ERR_COMPLEXPLANE_NOT_REAL_OR_IMAGINARY";
+      break;
+    }
+    case -1074395299: {
+      errorText = "ERR_INVALID_COMPLEXPLANE";
+      break;
+    }
+    case -1074395300: {
+      errorText = "ERR_INVALID_METERARCMODE";
+      break;
+    }
+    case -1074395301: {
+      errorText = "ERR_ROI_NOT_2_LINES";
+      break;
+    }
+    case -1074395302: {
+      errorText = "ERR_INVALID_THRESHOLDMETHOD";
+      break;
+    }
+    case -1074395303: {
+      errorText = "ERR_INVALID_NUM_OF_CLASSES";
+      break;
+    }
+    case -1074395304: {
+      errorText = "ERR_INVALID_MATHTRANSFORMMETHOD";
+      break;
+    }
+    case -1074395305: {
+      errorText = "ERR_INVALID_REFERENCEMODE";
+      break;
+    }
+    case -1074395306: {
+      errorText = "ERR_INVALID_TOOL";
+      break;
+    }
+    case -1074395307: {
+      errorText = "ERR_PRECISION_NOT_GTR_THAN_0";
+      break;
+    }
+    case -1074395308: {
+      errorText = "ERR_INVALID_COLORSENSITIVITY";
+      break;
+    }
+    case -1074395309: {
+      errorText = "ERR_INVALID_WINDOW_THREAD_POLICY";
+      break;
+    }
+    case -1074395310: {
+      errorText = "ERR_INVALID_PALETTE_TYPE";
+      break;
+    }
+    case -1074395311: {
+      errorText = "ERR_INVALID_COLOR_SPECTRUM";
+      break;
+    }
+    case -1074395312: {
+      errorText = "ERR_LCD_CALIBRATE";
+      break;
+    }
+    case -1074395313: {
+      errorText = "ERR_WRITE_FILE_NOT_SUPPORTED";
+      break;
+    }
+    case -1074395316: {
+      errorText = "ERR_INVALID_KERNEL_CODE";
+      break;
+    }
+    case -1074395317: {
+      errorText = "ERR_UNDEF_POINT";
+      break;
+    }
+    case -1074395318: {
+      errorText = "ERR_INSF_POINTS";
+      break;
+    }
+    case -1074395319: {
+      errorText = "ERR_INVALID_SUBPIX_TYPE";
+      break;
+    }
+    case -1074395320: {
+      errorText = "ERR_TEMPLATE_EMPTY";
+      break;
+    }
+    case -1074395321: {
+      errorText = "ERR_INVALID_MORPHOLOGYMETHOD";
+      break;
+    }
+    case -1074395322: {
+      errorText = "ERR_INVALID_TEXTALIGNMENT";
+      break;
+    }
+    case -1074395323: {
+      errorText = "ERR_INVALID_FONTCOLOR";
+      break;
+    }
+    case -1074395324: {
+      errorText = "ERR_INVALID_SHAPEMODE";
+      break;
+    }
+    case -1074395325: {
+      errorText = "ERR_INVALID_DRAWMODE";
+      break;
+    }
+    case -1074395326: {
+      errorText = "ERR_INVALID_DRAWMODE_FOR_LINE";
+      break;
+    }
+    case -1074395327: {
+      errorText = "ERR_INVALID_SCALINGMODE";
+      break;
+    }
+    case -1074395328: {
+      errorText = "ERR_INVALID_INTERPOLATIONMETHOD";
+      break;
+    }
+    case -1074395329: {
+      errorText = "ERR_INVALID_OUTLINEMETHOD";
+      break;
+    }
+    case -1074395330: {
+      errorText = "ERR_INVALID_BORDER_SIZE";
+      break;
+    }
+    case -1074395331: {
+      errorText = "ERR_INVALID_BORDERMETHOD";
+      break;
+    }
+    case -1074395332: {
+      errorText = "ERR_INVALID_COMPAREFUNCTION";
+      break;
+    }
+    case -1074395333: {
+      errorText = "ERR_INVALID_VERTICAL_TEXT_ALIGNMENT";
+      break;
+    }
+    case -1074395334: {
+      errorText = "ERR_INVALID_CONVERSIONSTYLE";
+      break;
+    }
+    case -1074395335: {
+      errorText = "ERR_DISPATCH_STATUS_CONFLICT";
+      break;
+    }
+    case -1074395336: {
+      errorText = "ERR_UNKNOWN_ALGORITHM";
+      break;
+    }
+    case -1074395340: {
+      errorText = "ERR_INVALID_SIZETYPE";
+      break;
+    }
+    case -1074395343: {
+      errorText = "ERR_FILE_FILENAME_nullptr";
+      break;
+    }
+    case -1074395345: {
+      errorText = "ERR_INVALID_FLIPAXIS";
+      break;
+    }
+    case -1074395346: {
+      errorText = "ERR_INVALID_INTERPOLATIONMETHOD_FOR_ROTATE";
+      break;
+    }
+    case -1074395347: {
+      errorText = "ERR_INVALID_3DDIRECTION";
+      break;
+    }
+    case -1074395348: {
+      errorText = "ERR_INVALID_3DPLANE";
+      break;
+    }
+    case -1074395349: {
+      errorText = "ERR_INVALID_SKELETONMETHOD";
+      break;
+    }
+    case -1074395350: {
+      errorText = "ERR_INVALID_VISION_INFO";
+      break;
+    }
+    case -1074395351: {
+      errorText = "ERR_INVALID_RECT";
+      break;
+    }
+    case -1074395352: {
+      errorText = "ERR_INVALID_FEATURE_MODE";
+      break;
+    }
+    case -1074395353: {
+      errorText = "ERR_INVALID_SEARCH_STRATEGY";
+      break;
+    }
+    case -1074395354: {
+      errorText = "ERR_INVALID_COLOR_WEIGHT";
+      break;
+    }
+    case -1074395355: {
+      errorText = "ERR_INVALID_NUM_MATCHES_REQUESTED";
+      break;
+    }
+    case -1074395356: {
+      errorText = "ERR_INVALID_MIN_MATCH_SCORE";
+      break;
+    }
+    case -1074395357: {
+      errorText = "ERR_INVALID_COLOR_IGNORE_MODE";
+      break;
+    }
+    case -1074395360: {
+      errorText = "ERR_COMPLEX_PLANE";
+      break;
+    }
+    case -1074395361: {
+      errorText = "ERR_INVALID_STEEPNESS";
+      break;
+    }
+    case -1074395362: {
+      errorText = "ERR_INVALID_WIDTH";
+      break;
+    }
+    case -1074395363: {
+      errorText = "ERR_INVALID_SUBSAMPLING_RATIO";
+      break;
+    }
+    case -1074395364: {
+      errorText = "ERR_IGNORE_COLOR_SPECTRUM_SET";
+      break;
+    }
+    case -1074395365: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSPECTRUM";
+      break;
+    }
+    case -1074395366: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHAPE";
+      break;
+    }
+    case -1074395367: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_5";
+      break;
+    }
+    case -1074395368: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_4";
+      break;
+    }
+    case -1074395369: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_3";
+      break;
+    }
+    case -1074395370: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_2";
+      break;
+    }
+    case -1074395371: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION_1";
+      break;
+    }
+    case -1074395372: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOROTATION";
+      break;
+    }
+    case -1074395373: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_ROTATION";
+      break;
+    }
+    case -1074395374: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_2";
+      break;
+    }
+    case -1074395375: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT_1";
+      break;
+    }
+    case -1074395376: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_NOSHIFT";
+      break;
+    }
+    case -1074395377: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_SHIFT";
+      break;
+    }
+    case -1074395378: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_6";
+      break;
+    }
+    case -1074395379: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_5";
+      break;
+    }
+    case -1074395380: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_4";
+      break;
+    }
+    case -1074395381: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_3";
+      break;
+    }
+    case -1074395382: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_2";
+      break;
+    }
+    case -1074395383: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR_1";
+      break;
+    }
+    case -1074395384: {
+      errorText = "ERR_COLOR_TEMPLATE_DESCRIPTOR";
+      break;
+    }
+    case -1074395385: {
+      errorText = "ERR_COLOR_ROTATION_REQUIRES_SHAPE_FEATURE";
+      break;
+    }
+    case -1074395386: {
+      errorText = "ERR_COLOR_MATCH_SETUP_DATA_SHAPE";
+      break;
+    }
+    case -1074395387: {
+      errorText = "ERR_COLOR_MATCH_SETUP_DATA";
+      break;
+    }
+    case -1074395388: {
+      errorText = "ERR_COLOR_LEARN_SETUP_DATA_SHAPE";
+      break;
+    }
+    case -1074395389: {
+      errorText = "ERR_COLOR_LEARN_SETUP_DATA";
+      break;
+    }
+    case -1074395390: {
+      errorText = "ERR_COLOR_TEMPLATE_IMAGE_LUMINANCE_CONTRAST_TOO_LOW";
+      break;
+    }
+    case -1074395391: {
+      errorText = "ERR_COLOR_TEMPLATE_IMAGE_HUE_CONTRAST_TOO_LOW";
+      break;
+    }
+    case -1074395392: {
+      errorText = "ERR_COLOR_TEMPLATE_IMAGE_TOO_LARGE";
+      break;
+    }
+    case -1074395393: {
+      errorText = "ERR_COLOR_TEMPLATE_IMAGE_TOO_SMALL";
+      break;
+    }
+    case -1074395394: {
+      errorText = "ERR_COLOR_SPECTRUM_MASK";
+      break;
+    }
+    case -1074395395: {
+      errorText = "ERR_COLOR_IMAGE_REQUIRED";
+      break;
+    }
+    case -1074395397: {
+      errorText = "ERR_COMPLEX_IMAGE_REQUIRED";
+      break;
+    }
+    case -1074395399: {
+      errorText = "ERR_MULTICORE_INVALID_ARGUMENT";
+      break;
+    }
+    case -1074395400: {
+      errorText = "ERR_MULTICORE_OPERATION";
+      break;
+    }
+    case -1074395401: {
+      errorText = "ERR_INVALID_MATCHFACTOR";
+      break;
+    }
+    case -1074395402: {
+      errorText = "ERR_INVALID_MAXPOINTS";
+      break;
+    }
+    case -1074395403: {
+      errorText = "ERR_EXTRAINFO_VERSION";
+      break;
+    }
+    case -1074395404: {
+      errorText = "ERR_INVALID_INTERPOLATIONMETHOD_FOR_UNWRAP";
+      break;
+    }
+    case -1074395405: {
+      errorText = "ERR_INVALID_TEXTORIENTATION";
+      break;
+    }
+    case -1074395406: {
+      errorText = "ERR_COORDSYS_NOT_FOUND";
+      break;
+    }
+    case -1074395407: {
+      errorText = "ERR_INVALID_CONTRAST";
+      break;
+    }
+    case -1074395408: {
+      errorText = "ERR_INVALID_DETECTION_MODE";
+      break;
+    }
+    case -1074395409: {
+      errorText = "ERR_INVALID_SUBPIXEL_DIVISIONS";
+      break;
+    }
+    case -1074395410: {
+      errorText = "ERR_INVALID_ICONS_PER_LINE";
+      break;
+    }
+    case -1074395549: {
+      errorText = "ERR_NIOCR_INVALID_NUMBER_OF_OBJECTS_TO_VERIFY";
+      break;
+    }
+    case -1074395550: {
+      errorText = "ERR_NIOCR_INVALID_CHARACTER_VALUE";
+      break;
+    }
+    case -1074395551: {
+      errorText = "ERR_NIOCR_RENAME_REFCHAR";
+      break;
+    }
+    case -1074395552: {
+      errorText = "ERR_NIOCR_NOT_A_VALID_CHARACTER_SET";
+      break;
+    }
+    case -1074395553: {
+      errorText = "ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_HEIGHT";
+      break;
+    }
+    case -1074395554: {
+      errorText = "ERR_NIOCR_INVALID_READ_RESOLUTION";
+      break;
+    }
+    case -1074395555: {
+      errorText = "ERR_NIOCR_INVALID_SPACING_RANGE";
+      break;
+    }
+    case -1074395556: {
+      errorText = "ERR_NIOCR_INVALID_BOUNDING_RECT_HEIGHT_RANGE";
+      break;
+    }
+    case -1074395557: {
+      errorText = "ERR_NIOCR_INVALID_BOUNDING_RECT_WIDTH_RANGE";
+      break;
+    }
+    case -1074395558: {
+      errorText = "ERR_NIOCR_INVALID_CHARACTER_SIZE_RANGE";
+      break;
+    }
+    case -1074395559: {
+      errorText = "ERR_NIOCR_INVALID_READ_OPTION";
+      break;
+    }
+    case -1074395560: {
+      errorText = "ERR_NIOCR_INVALID_OBJECT_INDEX";
+      break;
+    }
+    case -1074395561: {
+      errorText = "ERR_NIOCR_INVALID_NUMBER_OF_CHARACTERS";
+      break;
+    }
+    case -1074395562: {
+      errorText = "ERR_NIOCR_BOOLEAN_VALUE_FOR_STRING_ATTRIBUTE";
+      break;
+    }
+    case -1074395563: {
+      errorText = "ERR_NIOCR_UNLICENSED";
+      break;
+    }
+    case -1074395564: {
+      errorText = "ERR_NIOCR_INVALID_PREDEFINED_CHARACTER";
+      break;
+    }
+    case -1074395565: {
+      errorText = "ERR_NIOCR_MUST_BE_SINGLE_CHARACTER";
+      break;
+    }
+    case -1074395566: {
+      errorText = "ERR_NIOCR_BOOLEAN_VALUE_FOR_INTEGER_ATTRIBUTE";
+      break;
+    }
+    case -1074395567: {
+      errorText = "ERR_NIOCR_STRING_VALUE_FOR_BOOLEAN_ATTRIBUTE";
+      break;
+    }
+    case -1074395568: {
+      errorText = "ERR_NIOCR_STRING_VALUE_FOR_INTEGER_ATTRIBUTE";
+      break;
+    }
+    case -1074395569: {
+      errorText = "ERR_NIOCR_INVALID_ATTRIBUTE";
+      break;
+    }
+    case -1074395570: {
+      errorText = "ERR_NIOCR_INTEGER_VALUE_FOR_BOOLEAN_ATTRIBUTE";
+      break;
+    }
+    case -1074395571: {
+      errorText = "ERR_NIOCR_GET_ONLY_ATTRIBUTE";
+      break;
+    }
+    case -1074395572: {
+      errorText = "ERR_NIOCR_INTEGER_VALUE_FOR_STRING_ATTRIBUTE";
+      break;
+    }
+    case -1074395573: {
+      errorText = "ERR_NIOCR_INVALID_CHARACTER_SET_FILE_VERSION";
+      break;
+    }
+    case -1074395574: {
+      errorText = "ERR_NIOCR_CHARACTER_SET_DESCRIPTION_TOO_LONG";
+      break;
+    }
+    case -1074395575: {
+      errorText = "ERR_NIOCR_INVALID_NUMBER_OF_EROSIONS";
+      break;
+    }
+    case -1074395576: {
+      errorText = "ERR_NIOCR_CHARACTER_VALUE_TOO_LONG";
+      break;
+    }
+    case -1074395577: {
+      errorText = "ERR_NIOCR_CHARACTER_VALUE_CANNOT_BE_EMPTYSTRING";
+      break;
+    }
+    case -1074395578: {
+      errorText = "ERR_NIOCR_INVALID_CHARACTER_SET_FILE";
+      break;
+    }
+    case -1074395579: {
+      errorText = "ERR_NIOCR_INVALID_ASPECT_RATIO";
+      break;
+    }
+    case -1074395580: {
+      errorText = "ERR_NIOCR_INVALID_MIN_BOUNDING_RECT_WIDTH";
+      break;
+    }
+    case -1074395581: {
+      errorText = "ERR_NIOCR_INVALID_MAX_VERT_ELEMENT_SPACING";
+      break;
+    }
+    case -1074395582: {
+      errorText = "ERR_NIOCR_INVALID_MAX_HORIZ_ELEMENT_SPACING";
+      break;
+    }
+    case -1074395583: {
+      errorText = "ERR_NIOCR_INVALID_MIN_CHAR_SPACING";
+      break;
+    }
+    case -1074395584: {
+      errorText = "ERR_NIOCR_INVALID_THRESHOLD_LIMITS";
+      break;
+    }
+    case -1074395585: {
+      errorText = "ERR_NIOCR_INVALID_UPPER_THRESHOLD_LIMIT";
+      break;
+    }
+    case -1074395586: {
+      errorText = "ERR_NIOCR_INVALID_LOWER_THRESHOLD_LIMIT";
+      break;
+    }
+    case -1074395587: {
+      errorText = "ERR_NIOCR_INVALID_THRESHOLD_RANGE";
+      break;
+    }
+    case -1074395588: {
+      errorText = "ERR_NIOCR_INVALID_HIGH_THRESHOLD_VALUE";
+      break;
+    }
+    case -1074395589: {
+      errorText = "ERR_NIOCR_INVALID_LOW_THRESHOLD_VALUE";
+      break;
+    }
+    case -1074395590: {
+      errorText = "ERR_NIOCR_INVALID_NUMBER_OF_VALID_CHARACTER_POSITIONS";
+      break;
+    }
+    case -1074395591: {
+      errorText = "ERR_NIOCR_INVALID_CHARACTER_INDEX";
+      break;
+    }
+    case -1074395592: {
+      errorText = "ERR_NIOCR_INVALID_READ_STRATEGY";
+      break;
+    }
+    case -1074395593: {
+      errorText = "ERR_NIOCR_INVALID_NUMBER_OF_BLOCKS";
+      break;
+    }
+    case -1074395594: {
+      errorText = "ERR_NIOCR_INVALID_SUBSTITUTION_CHARACTER";
+      break;
+    }
+    case -1074395595: {
+      errorText = "ERR_NIOCR_INVALID_THRESHOLD_MODE";
+      break;
+    }
+    case -1074395596: {
+      errorText = "ERR_NIOCR_INVALID_CHARACTER_SIZE";
+      break;
+    }
+    case -1074395597: {
+      errorText = "ERR_NIOCR_NOT_A_VALID_SESSION";
+      break;
+    }
+    case -1074395598: {
+      errorText = "ERR_NIOCR_INVALID_ACCEPTANCE_LEVEL";
+      break;
+    }
+    case -1074395600: {
+      errorText = "ERR_INFO_NOT_FOUND";
+      break;
+    }
+    case -1074395601: {
+      errorText = "ERR_INVALID_EDGE_THRESHOLD";
+      break;
+    }
+    case -1074395602: {
+      errorText = "ERR_INVALID_MINIMUM_CURVE_LENGTH";
+      break;
+    }
+    case -1074395603: {
+      errorText = "ERR_INVALID_ROW_STEP";
+      break;
+    }
+    case -1074395604: {
+      errorText = "ERR_INVALID_COLUMN_STEP";
+      break;
+    }
+    case -1074395605: {
+      errorText = "ERR_INVALID_MAXIMUM_END_POINT_GAP";
+      break;
+    }
+    case -1074395606: {
+      errorText = "ERR_INVALID_MINIMUM_FEATURES_TO_MATCH";
+      break;
+    }
+    case -1074395607: {
+      errorText = "ERR_INVALID_MAXIMUM_FEATURES_PER_MATCH";
+      break;
+    }
+    case -1074395608: {
+      errorText = "ERR_INVALID_SUBPIXEL_ITERATIONS";
+      break;
+    }
+    case -1074395609: {
+      errorText = "ERR_INVALID_SUBPIXEL_TOLERANCE";
+      break;
+    }
+    case -1074395610: {
+      errorText = "ERR_INVALID_INITIAL_MATCH_LIST_LENGTH";
+      break;
+    }
+    case -1074395611: {
+      errorText = "ERR_INVALID_MINIMUM_RECTANGLE_DIMENSION";
+      break;
+    }
+    case -1074395612: {
+      errorText = "ERR_INVALID_MINIMUM_FEATURE_RADIUS";
+      break;
+    }
+    case -1074395613: {
+      errorText = "ERR_INVALID_MINIMUM_FEATURE_LENGTH";
+      break;
+    }
+    case -1074395614: {
+      errorText = "ERR_INVALID_MINIMUM_FEATURE_ASPECT_RATIO";
+      break;
+    }
+    case -1074395615: {
+      errorText = "ERR_INVALID_MINIMUM_FEATURE_STRENGTH";
+      break;
+    }
+    case -1074395616: {
+      errorText = "ERR_INVALID_EDGE_FILTER_SIZE";
+      break;
+    }
+    case -1074395617: {
+      errorText = "ERR_INVALID_NUMBER_OF_FEATURES_RANGE";
+      break;
+    }
+    case -1074395618: {
+      errorText = "ERR_TOO_MANY_SCALE_RANGES";
+      break;
+    }
+    case -1074395619: {
+      errorText = "ERR_TOO_MANY_OCCLUSION_RANGES";
+      break;
+    }
+    case -1074395620: {
+      errorText = "ERR_INVALID_CURVE_EXTRACTION_MODE";
+      break;
+    }
+    case -1074395621: {
+      errorText = "ERR_INVALID_LEARN_GEOMETRIC_PATTERN_SETUP_DATA";
+      break;
+    }
+    case -1074395622: {
+      errorText = "ERR_INVALID_MATCH_GEOMETRIC_PATTERN_SETUP_DATA";
+      break;
+    }
+    case -1074395623: {
+      errorText = "ERR_INVALID_SCALE_RANGE";
+      break;
+    }
+    case -1074395624: {
+      errorText = "ERR_INVALID_OCCLUSION_RANGE";
+      break;
+    }
+    case -1074395625: {
+      errorText = "ERR_INVALID_MATCH_CONSTRAINT_TYPE";
+      break;
+    }
+    case -1074395626: {
+      errorText = "ERR_NOT_ENOUGH_TEMPLATE_FEATURES";
+      break;
+    }
+    case -1074395627: {
+      errorText = "ERR_NOT_ENOUGH_TEMPLATE_FEATURES_1";
+      break;
+    }
+    case -1074395628: {
+      errorText = "ERR_INVALID_GEOMETRIC_MATCHING_TEMPLATE";
+      break;
+    }
+    case -1074395629: {
+      errorText = "ERR_INVALID_MAXIMUM_PIXEL_DISTANCE_FROM_LINE";
+      break;
+    }
+    case -1074395630: {
+      errorText = "ERR_INVALID_MAXIMUM_FEATURES_LEARNED";
+      break;
+    }
+    case -1074395631: {
+      errorText = "ERR_INVALID_MIN_MATCH_SEPARATION_DISTANCE";
+      break;
+    }
+    case -1074395632: {
+      errorText = "ERR_INVALID_MIN_MATCH_SEPARATION_ANGLE";
+      break;
+    }
+    case -1074395633: {
+      errorText = "ERR_INVALID_MIN_MATCH_SEPARATION_SCALE";
+      break;
+    }
+    case -1074395634: {
+      errorText = "ERR_INVALID_MAX_MATCH_OVERLAP";
+      break;
+    }
+    case -1074395635: {
+      errorText = "ERR_INVALID_SHAPE_DESCRIPTOR";
+      break;
+    }
+    case -1074395636: {
+      errorText = "ERR_DIRECTX_NOT_FOUND";
+      break;
+    }
+    case -1074395637: {
+      errorText = "ERR_HARDWARE_DOESNT_SUPPORT_NONTEARING";
+      break;
+    }
+    case -1074395638: {
+      errorText = "ERR_INVALID_FILL_STYLE";
+      break;
+    }
+    case -1074395639: {
+      errorText = "ERR_INVALID_HATCH_STYLE";
+      break;
+    }
+    case -1074395640: {
+      errorText = "ERR_TOO_MANY_ZONES";
+      break;
+    }
+    case -1074395641: {
+      errorText = "ERR_DUPLICATE_LABEL";
+      break;
+    }
+    case -1074395642: {
+      errorText = "ERR_LABEL_NOT_FOUND";
+      break;
+    }
+    case -1074395643: {
+      errorText = "ERR_INVALID_NUMBER_OF_MATCH_OPTIONS";
+      break;
+    }
+    case -1074395644: {
+      errorText = "ERR_LABEL_TOO_LONG";
+      break;
+    }
+    case -1074395645: {
+      errorText = "ERR_INVALID_NUMBER_OF_LABELS";
+      break;
+    }
+    case -1074395646: {
+      errorText = "ERR_NO_TEMPLATE_TO_LEARN";
+      break;
+    }
+    case -1074395647: {
+      errorText = "ERR_INVALID_MULTIPLE_GEOMETRIC_TEMPLATE";
+      break;
+    }
+    case -1074395648: {
+      errorText = "ERR_TEMPLATE_NOT_LEARNED";
+      break;
+    }
+    case -1074395649: {
+      errorText = "ERR_INVALID_GEOMETRIC_FEATURE_TYPE";
+      break;
+    }
+    case -1074395650: {
+      errorText = "ERR_CURVE_EXTRACTION_MODE_MUST_BE_SAME";
+      break;
+    }
+    case -1074395651: {
+      errorText = "ERR_EDGE_FILTER_SIZE_MUST_BE_SAME";
+      break;
+    }
+    case -1074395652: {
+      errorText = "ERR_OPENING_NEWER_GEOMETRIC_MATCHING_TEMPLATE";
+      break;
+    }
+    case -1074395653: {
+      errorText = "ERR_OPENING_NEWER_MULTIPLE_GEOMETRIC_TEMPLATE";
+      break;
+    }
+    case -1074395654: {
+      errorText = "ERR_GRADING_INFORMATION_NOT_FOUND";
+      break;
+    }
+    case -1074395655: {
+      errorText = "ERR_ENABLE_CALIBRATION_SUPPORT_MUST_BE_SAME";
+      break;
+    }
+    case -1074395656: {
+      errorText = "ERR_SMOOTH_CONTOURS_MUST_BE_SAME";
+      break;
+    }
+    case -1074395700: {
+      errorText = "ERR_REQUIRES_WIN2000_OR_NEWER";
+      break;
+    }
+    case -1074395701: {
+      errorText = "ERR_INVALID_MATRIX_SIZE_RANGE";
+      break;
+    }
+    case -1074395702: {
+      errorText = "ERR_INVALID_LENGTH";
+      break;
+    }
+    case -1074395703: {
+      errorText = "ERR_INVALID_TYPE_OF_FLATTEN";
+      break;
+    }
+    case -1074395704: {
+      errorText = "ERR_INVALID_COMPRESSION_TYPE";
+      break;
+    }
+    case -1074395705: {
+      errorText = "ERR_DATA_CORRUPTED";
+      break;
+    }
+    case -1074395706: {
+      errorText = "ERR_AVI_SESSION_ALREADY_OPEN";
+      break;
+    }
+    case -1074395707: {
+      errorText = "ERR_AVI_WRITE_SESSION_REQUIRED";
+      break;
+    }
+    case -1074395708: {
+      errorText = "ERR_AVI_READ_SESSION_REQUIRED";
+      break;
+    }
+    case -1074395709: {
+      errorText = "ERR_AVI_UNOPENED_SESSION";
+      break;
+    }
+    case -1074395710: {
+      errorText = "ERR_TOO_MANY_PARTICLES";
+      break;
+    }
+    case -1074395711: {
+      errorText = "ERR_NOT_ENOUGH_REGIONS";
+      break;
+    }
+    case -1074395712: {
+      errorText = "ERR_WRONG_REGION_TYPE";
+      break;
+    }
+    case -1074395713: {
+      errorText = "ERR_VALUE_NOT_IN_ENUM";
+      break;
+    }
+    case -1074395714: {
+      errorText = "ERR_INVALID_AXIS_ORIENTATION";
+      break;
+    }
+    case -1074395715: {
+      errorText = "ERR_INVALID_CALIBRATION_UNIT";
+      break;
+    }
+    case -1074395716: {
+      errorText = "ERR_INVALID_SCALING_METHOD";
+      break;
+    }
+    case -1074395717: {
+      errorText = "ERR_INVALID_RANGE";
+      break;
+    }
+    case -1074395718: {
+      errorText = "ERR_LAB_VERSION";
+      break;
+    }
+    case -1074395719: {
+      errorText = "ERR_BAD_ROI_BOX";
+      break;
+    }
+    case -1074395720: {
+      errorText = "ERR_BAD_ROI";
+      break;
+    }
+    case -1074395721: {
+      errorText = "ERR_INVALID_BIT_DEPTH";
+      break;
+    }
+    case -1074395722: {
+      errorText = "ERR_CLASSIFIER_CLASSIFY_IMAGE_WITH_CUSTOM_SESSION";
+      break;
+    }
+    case -1074395723: {
+      errorText = "ERR_CUSTOMDATA_KEY_NOT_FOUND";
+      break;
+    }
+    case -1074395724: {
+      errorText = "ERR_CUSTOMDATA_INVALID_SIZE";
+      break;
+    }
+    case -1074395725: {
+      errorText = "ERR_DATA_VERSION";
+      break;
+    }
+    case -1074395726: {
+      errorText = "ERR_MATCHFACTOR_OBSOLETE";
+      break;
+    }
+    case -1074395727: {
+      errorText = "ERR_UNSUPPORTED_2D_BARCODE_SEARCH_MODE";
+      break;
+    }
+    case -1074395728: {
+      errorText = "ERR_INVALID_2D_BARCODE_SEARCH_MODE";
+      break;
+    }
+    case -1074395754: {
+      errorText = "ERR_TRIG_TIMEOUT";
+      break;
+    }
+    case -1074395756: {
+      errorText = "ERR_DLL_FUNCTION_NOT_FOUND";
+      break;
+    }
+    case -1074395757: {
+      errorText = "ERR_DLL_NOT_FOUND";
+      break;
+    }
+    case -1074395758: {
+      errorText = "ERR_BOARD_NOT_OPEN";
+      break;
+    }
+    case -1074395760: {
+      errorText = "ERR_BOARD_NOT_FOUND";
+      break;
+    }
+    case -1074395762: {
+      errorText = "ERR_INVALID_NIBLACK_DEVIATION_FACTOR";
+      break;
+    }
+    case -1074395763: {
+      errorText = "ERR_INVALID_NORMALIZATION_METHOD";
+      break;
+    }
+    case -1074395766: {
+      errorText = "ERR_DEPRECATED_FUNCTION";
+      break;
+    }
+    case -1074395767: {
+      errorText = "ERR_INVALID_ALIGNMENT";
+      break;
+    }
+    case -1074395768: {
+      errorText = "ERR_INVALID_SCALE";
+      break;
+    }
+    case -1074395769: {
+      errorText = "ERR_INVALID_EDGE_THICKNESS";
+      break;
+    }
+    case -1074395770: {
+      errorText = "ERR_INVALID_INSPECTION_TEMPLATE";
+      break;
+    }
+    case -1074395771: {
+      errorText = "ERR_OPENING_NEWER_INSPECTION_TEMPLATE";
+      break;
+    }
+    case -1074395772: {
+      errorText = "ERR_INVALID_REGISTRATION_METHOD";
+      break;
+    }
+    case -1074395773: {
+      errorText = "ERR_NO_DEST_IMAGE";
+      break;
+    }
+    case -1074395774: {
+      errorText = "ERR_NO_LABEL";
+      break;
+    }
+    case -1074395775: {
+      errorText = "ERR_ROI_HAS_OPEN_CONTOURS";
+      break;
+    }
+    case -1074395776: {
+      errorText = "ERR_INVALID_USE_OF_COMPACT_SESSION_FILE";
+      break;
+    }
+    case -1074395777: {
+      errorText = "ERR_INCOMPATIBLE_CLASSIFIER_TYPES";
+      break;
+    }
+    case -1074395778: {
+      errorText = "ERR_INVALID_KERNEL_SIZE";
+      break;
+    }
+    case -1074395779: {
+      errorText = "ERR_CANNOT_COMPACT_UNTRAINED";
+      break;
+    }
+    case -1074395780: {
+      errorText = "ERR_INVALID_PARTICLE_TYPE";
+      break;
+    }
+    case -1074395781: {
+      errorText = "ERR_CLASSIFIER_INVALID_ENGINE_TYPE";
+      break;
+    }
+    case -1074395782: {
+      errorText = "ERR_DESCRIPTION_TOO_LONG";
+      break;
+    }
+    case -1074395783: {
+      errorText = "ERR_BAD_SAMPLE_INDEX";
+      break;
+    }
+    case -1074395784: {
+      errorText = "ERR_INVALID_LIMITS";
+      break;
+    }
+    case -1074395785: {
+      errorText = "ERR_NO_PARTICLE";
+      break;
+    }
+    case -1074395786: {
+      errorText = "ERR_INVALID_PARTICLE_OPTIONS";
+      break;
+    }
+    case -1074395787: {
+      errorText = "ERR_INVALID_CLASSIFIER_TYPE";
+      break;
+    }
+    case -1074395788: {
+      errorText = "ERR_NO_SAMPLES";
+      break;
+    }
+    case -1074395789: {
+      errorText = "ERR_OPENING_NEWER_CLASSIFIER_SESSION";
+      break;
+    }
+    case -1074395790: {
+      errorText = "ERR_INVALID_DISTANCE_METRIC";
+      break;
+    }
+    case -1074395791: {
+      errorText = "ERR_CLASSIFIER_INVALID_SESSION_TYPE";
+      break;
+    }
+    case -1074395792: {
+      errorText = "ERR_CLASSIFIER_SESSION_NOT_TRAINED";
+      break;
+    }
+    case -1074395793: {
+      errorText = "ERR_INVALID_OPERATION_ON_COMPACT_SESSION_ATTEMPTED";
+      break;
+    }
+    case -1074395794: {
+      errorText = "ERR_K_TOO_HIGH";
+      break;
+    }
+    case -1074395795: {
+      errorText = "ERR_K_TOO_LOW";
+      break;
+    }
+    case -1074395796: {
+      errorText = "ERR_INVALID_KNN_METHOD";
+      break;
+    }
+    case -1074395797: {
+      errorText = "ERR_INVALID_CLASSIFIER_SESSION";
+      break;
+    }
+    case -1074395798: {
+      errorText = "ERR_INVALID_CUSTOM_SAMPLE";
+      break;
+    }
+    case -1074395799: {
+      errorText = "ERR_INTERNAL";
+      break;
+    }
+    case -1074395800: {
+      errorText = "ERR_PROTECTION";
+      break;
+    }
+    case -1074395801: {
+      errorText = "ERR_TOO_MANY_CONTOURS";
+      break;
+    }
+    case -1074395837: {
+      errorText = "ERR_INVALID_COMPRESSION_RATIO";
+      break;
+    }
+    case -1074395840: {
+      errorText = "ERR_BAD_INDEX";
+      break;
+    }
+    case -1074395875: {
+      errorText = "ERR_BARCODE_PHARMACODE";
+      break;
+    }
+    case -1074395876: {
+      errorText = "ERR_UNSUPPORTED_COLOR_MODE";
+      break;
+    }
+    case -1074395877: {
+      errorText = "ERR_COLORMODE_REQUIRES_CHANGECOLORSPACE2";
+      break;
+    }
+    case -1074395878: {
+      errorText = "ERR_PROP_NODE_WRITE_NOT_SUPPORTED";
+      break;
+    }
+    case -1074395879: {
+      errorText = "ERR_BAD_MEASURE";
+      break;
+    }
+    case -1074395880: {
+      errorText = "ERR_PARTICLE";
+      break;
+    }
+    case -1074395920: {
+      errorText = "ERR_NUMBER_CLASS";
+      break;
+    }
+    case -1074395953: {
+      errorText = "ERR_INVALID_WAVELET_TRANSFORM_MODE";
+      break;
+    }
+    case -1074395954: {
+      errorText = "ERR_INVALID_QUANTIZATION_STEP_SIZE";
+      break;
+    }
+    case -1074395955: {
+      errorText = "ERR_INVALID_MAX_WAVELET_TRANSFORM_LEVEL";
+      break;
+    }
+    case -1074395956: {
+      errorText = "ERR_INVALID_QUALITY";
+      break;
+    }
+    case -1074395957: {
+      errorText = "ERR_ARRAY_SIZE_MISMATCH";
+      break;
+    }
+    case -1074395958: {
+      errorText = "ERR_WINDOW_ID";
+      break;
+    }
+    case -1074395959: {
+      errorText = "ERR_CREATE_WINDOW";
+      break;
+    }
+    case -1074395960: {
+      errorText = "ERR_INIT";
+      break;
+    }
+    case -1074395971: {
+      errorText = "ERR_INVALID_OFFSET";
+      break;
+    }
+    case -1074395972: {
+      errorText = "ERR_DIRECTX_ENUMERATE_FILTERS";
+      break;
+    }
+    case -1074395973: {
+      errorText = "ERR_JPEG2000_UNSUPPORTED_MULTIPLE_LAYERS";
+      break;
+    }
+    case -1074395974: {
+      errorText = "ERR_UNSUPPORTED_JPEG2000_COLORSPACE_METHOD";
+      break;
+    }
+    case -1074395975: {
+      errorText = "ERR_AVI_TIMEOUT";
+      break;
+    }
+    case -1074395976: {
+      errorText = "ERR_NUMBER_OF_PALETTE_COLORS";
+      break;
+    }
+    case -1074395977: {
+      errorText = "ERR_AVI_VERSION";
+      break;
+    }
+    case -1074395978: {
+      errorText = "ERR_INVALID_PARTICLE_NUMBER";
+      break;
+    }
+    case -1074395979: {
+      errorText = "ERR_INVALID_PARTICLE_INFO";
+      break;
+    }
+    case -1074395980: {
+      errorText = "ERR_COM_INITIALIZE";
+      break;
+    }
+    case -1074395981: {
+      errorText = "ERR_INSUFFICIENT_BUFFER_SIZE";
+      break;
+    }
+    case -1074395982: {
+      errorText = "ERR_INVALID_FRAMES_PER_SECOND";
+      break;
+    }
+    case -1074395983: {
+      errorText = "ERR_FILE_NO_SPACE";
+      break;
+    }
+    case -1074395984: {
+      errorText = "ERR_FILE_INVALID_DATA_TYPE";
+      break;
+    }
+    case -1074395985: {
+      errorText = "ERR_FILE_OPERATION";
+      break;
+    }
+    case -1074395986: {
+      errorText = "ERR_FILE_FORMAT";
+      break;
+    }
+    case -1074395987: {
+      errorText = "ERR_FILE_EOF";
+      break;
+    }
+    case -1074395988: {
+      errorText = "ERR_FILE_WRITE";
+      break;
+    }
+    case -1074395989: {
+      errorText = "ERR_FILE_READ";
+      break;
+    }
+    case -1074395990: {
+      errorText = "ERR_FILE_GET_INFO";
+      break;
+    }
+    case -1074395991: {
+      errorText = "ERR_FILE_INVALID_TYPE";
+      break;
+    }
+    case -1074395992: {
+      errorText = "ERR_FILE_PERMISSION";
+      break;
+    }
+    case -1074395993: {
+      errorText = "ERR_FILE_IO_ERR";
+      break;
+    }
+    case -1074395994: {
+      errorText = "ERR_FILE_TOO_MANY_OPEN";
+      break;
+    }
+    case -1074395995: {
+      errorText = "ERR_FILE_NOT_FOUND";
+      break;
+    }
+    case -1074395996: {
+      errorText = "ERR_FILE_OPEN";
+      break;
+    }
+    case -1074395997: {
+      errorText = "ERR_FILE_ARGERR";
+      break;
+    }
+    case -1074395998: {
+      errorText = "ERR_FILE_COLOR_TABLE";
+      break;
+    }
+    case -1074395999: {
+      errorText = "ERR_FILE_FILE_TYPE";
+      break;
+    }
+    case -1074396000: {
+      errorText = "ERR_FILE_FILE_HEADER";
+      break;
+    }
+    case -1074396001: {
+      errorText = "ERR_TOO_MANY_AVI_SESSIONS";
+      break;
+    }
+    case -1074396002: {
+      errorText = "ERR_INVALID_LINEGAUGEMETHOD";
+      break;
+    }
+    case -1074396003: {
+      errorText = "ERR_AVI_DATA_EXCEEDS_BUFFER_SIZE";
+      break;
+    }
+    case -1074396004: {
+      errorText = "ERR_DIRECTX_CERTIFICATION_FAILURE";
+      break;
+    }
+    case -1074396005: {
+      errorText = "ERR_INVALID_AVI_SESSION";
+      break;
+    }
+    case -1074396006: {
+      errorText = "ERR_DIRECTX_UNKNOWN_COMPRESSION_FILTER";
+      break;
+    }
+    case -1074396007: {
+      errorText = "ERR_DIRECTX_INCOMPATIBLE_COMPRESSION_FILTER";
+      break;
+    }
+    case -1074396008: {
+      errorText = "ERR_DIRECTX_NO_FILTER";
+      break;
+    }
+    case -1074396009: {
+      errorText = "ERR_DIRECTX";
+      break;
+    }
+    case -1074396010: {
+      errorText = "ERR_INVALID_FRAME_NUMBER";
+      break;
+    }
+    case -1074396011: {
+      errorText = "ERR_RPC_BIND";
+      break;
+    }
+    case -1074396012: {
+      errorText = "ERR_RPC_EXECUTE";
+      break;
+    }
+    case -1074396013: {
+      errorText = "ERR_INVALID_VIDEO_MODE";
+      break;
+    }
+    case -1074396014: {
+      errorText = "ERR_INVALID_VIDEO_BLIT";
+      break;
+    }
+    case -1074396015: {
+      errorText = "ERR_RPC_EXECUTE_IVB";
+      break;
+    }
+    case -1074396016: {
+      errorText = "ERR_NO_VIDEO_DRIVER";
+      break;
+    }
+    case -1074396017: {
+      errorText = "ERR_OPENING_NEWER_AIM_GRADING_DATA";
+      break;
+    }
+    case -1074396018: {
+      errorText = "ERR_INVALID_EDGE_POLARITY_SEARCH_MODE";
+      break;
+    }
+    case -1074396019: {
+      errorText = "ERR_INVALID_THRESHOLD_PERCENTAGE";
+      break;
+    }
+    case -1074396020: {
+      errorText = "ERR_INVALID_GRADING_MODE";
+      break;
+    }
+    case -1074396021: {
+      errorText = "ERR_INVALID_KERNEL_SIZE_FOR_EDGE_DETECTION";
+      break;
+    }
+    case -1074396022: {
+      errorText = "ERR_INVALID_SEARCH_MODE_FOR_STRAIGHT_EDGE";
+      break;
+    }
+    case -1074396023: {
+      errorText = "ERR_INVALID_ANGLE_TOL_FOR_STRAIGHT_EDGE";
+      break;
+    }
+    case -1074396024: {
+      errorText = "ERR_INVALID_MIN_COVERAGE_FOR_STRAIGHT_EDGE";
+      break;
+    }
+    case -1074396025: {
+      errorText = "ERR_INVALID_ANGLE_RANGE_FOR_STRAIGHT_EDGE";
+      break;
+    }
+    case -1074396026: {
+      errorText = "ERR_INVALID_PROCESS_TYPE_FOR_EDGE_DETECTION";
+      break;
+    }
+    case -1074396032: {
+      errorText = "ERR_TEMPLATEDESCRIPTOR_ROTATION_SEARCHSTRATEGY";
+      break;
+    }
+    case -1074396033: {
+      errorText = "ERR_TEMPLATEDESCRIPTOR_LEARNSETUPDATA";
+      break;
+    }
+    case -1074396034: {
+      errorText = "ERR_TEMPLATEIMAGE_EDGEINFO";
+      break;
+    }
+    case -1074396035: {
+      errorText = "ERR_TEMPLATEIMAGE_NOCIRCLE";
+      break;
+    }
+    case -1074396036: {
+      errorText = "ERR_INVALID_SKELETONMODE";
+      break;
+    }
+    case -1074396037: {
+      errorText = "ERR_TIMEOUT";
+      break;
+    }
+    case -1074396038: {
+      errorText = "ERR_FIND_COORDSYS_MORE_THAN_ONE_EDGE";
+      break;
+    }
+    case -1074396039: {
+      errorText = "ERR_IO_ERROR";
+      break;
+    }
+    case -1074396040: {
+      errorText = "ERR_DRIVER";
+      break;
+    }
+    case -1074396041: {
+      errorText = "ERR_INVALID_2D_BARCODE_TYPE";
+      break;
+    }
+    case -1074396042: {
+      errorText = "ERR_INVALID_2D_BARCODE_CONTRAST";
+      break;
+    }
+    case -1074396043: {
+      errorText = "ERR_INVALID_2D_BARCODE_CELL_SHAPE";
+      break;
+    }
+    case -1074396044: {
+      errorText = "ERR_INVALID_2D_BARCODE_SHAPE";
+      break;
+    }
+    case -1074396045: {
+      errorText = "ERR_INVALID_2D_BARCODE_SUBTYPE";
+      break;
+    }
+    case -1074396046: {
+      errorText = "ERR_INVALID_2D_BARCODE_CONTRAST_FOR_ROI";
+      break;
+    }
+    case -1074396047: {
+      errorText = "ERR_INVALID_LINEAR_AVERAGE_MODE";
+      break;
+    }
+    case -1074396048: {
+      errorText = "ERR_INVALID_CELL_SAMPLE_SIZE";
+      break;
+    }
+    case -1074396049: {
+      errorText = "ERR_INVALID_MATRIX_POLARITY";
+      break;
+    }
+    case -1074396050: {
+      errorText = "ERR_INVALID_ECC_TYPE";
+      break;
+    }
+    case -1074396051: {
+      errorText = "ERR_INVALID_CELL_FILTER_MODE";
+      break;
+    }
+    case -1074396052: {
+      errorText = "ERR_INVALID_DEMODULATION_MODE";
+      break;
+    }
+    case -1074396053: {
+      errorText = "ERR_INVALID_BORDER_INTEGRITY";
+      break;
+    }
+    case -1074396054: {
+      errorText = "ERR_INVALID_CELL_FILL_TYPE";
+      break;
+    }
+    case -1074396055: {
+      errorText = "ERR_INVALID_ASPECT_RATIO";
+      break;
+    }
+    case -1074396056: {
+      errorText = "ERR_INVALID_MATRIX_MIRROR_MODE";
+      break;
+    }
+    case -1074396057: {
+      errorText = "ERR_INVALID_SEARCH_VECTOR_WIDTH";
+      break;
+    }
+    case -1074396058: {
+      errorText = "ERR_INVALID_ROTATION_MODE";
+      break;
+    }
+    case -1074396059: {
+      errorText = "ERR_INVALID_MAX_ITERATIONS";
+      break;
+    }
+    case -1074396060: {
+      errorText = "ERR_JPEG2000_LOSSLESS_WITH_FLOATING_POINT";
+      break;
+    }
+    case -1074396061: {
+      errorText = "ERR_INVALID_WINDOW_SIZE";
+      break;
+    }
+    case -1074396062: {
+      errorText = "ERR_INVALID_TOLERANCE";
+      break;
+    }
+    case -1074396063: {
+      errorText = "ERR_EXTERNAL_ALIGNMENT";
+      break;
+    }
+    case -1074396064: {
+      errorText = "ERR_EXTERNAL_NOT_SUPPORTED";
+      break;
+    }
+    case -1074396065: {
+      errorText = "ERR_CANT_RESIZE_EXTERNAL";
+      break;
+    }
+    case -1074396066: {
+      errorText = "ERR_INVALID_POINTSYMBOL";
+      break;
+    }
+    case -1074396067: {
+      errorText = "ERR_IMAGES_NOT_DIFF";
+      break;
+    }
+    case -1074396068: {
+      errorText = "ERR_INVALID_ACTION";
+      break;
+    }
+    case -1074396069: {
+      errorText = "ERR_INVALID_COLOR_MODE";
+      break;
+    }
+    case -1074396070: {
+      errorText = "ERR_INVALID_FUNCTION";
+      break;
+    }
+    case -1074396071: {
+      errorText = "ERR_INVALID_SCAN_DIRECTION";
+      break;
+    }
+    case -1074396072: {
+      errorText = "ERR_INVALID_BORDER";
+      break;
+    }
+    case -1074396073: {
+      errorText = "ERR_MASK_OUTSIDE_IMAGE";
+      break;
+    }
+    case -1074396074: {
+      errorText = "ERR_INCOMP_SIZE";
+      break;
+    }
+    case -1074396075: {
+      errorText = "ERR_COORD_SYS_SECOND_AXIS";
+      break;
+    }
+    case -1074396076: {
+      errorText = "ERR_COORD_SYS_FIRST_AXIS";
+      break;
+    }
+    case -1074396077: {
+      errorText = "ERR_INCOMP_TYPE";
+      break;
+    }
+    case -1074396079: {
+      errorText = "ERR_INVALID_METAFILE_HANDLE";
+      break;
+    }
+    case -1074396080: {
+      errorText = "ERR_INVALID_IMAGE_TYPE";
+      break;
+    }
+    case -1074396081: {
+      errorText = "ERR_BAD_PASSWORD";
+      break;
+    }
+    case -1074396082: {
+      errorText = "ERR_PALETTE_NOT_SUPPORTED";
+      break;
+    }
+    case -1074396083: {
+      errorText = "ERR_ROLLBACK_TIMEOUT";
+      break;
+    }
+    case -1074396084: {
+      errorText = "ERR_ROLLBACK_DELETE_TIMER";
+      break;
+    }
+    case -1074396085: {
+      errorText = "ERR_ROLLBACK_INIT_TIMER";
+      break;
+    }
+    case -1074396086: {
+      errorText = "ERR_ROLLBACK_START_TIMER";
+      break;
+    }
+    case -1074396087: {
+      errorText = "ERR_ROLLBACK_STOP_TIMER";
+      break;
+    }
+    case -1074396088: {
+      errorText = "ERR_ROLLBACK_RESIZE";
+      break;
+    }
+    case -1074396089: {
+      errorText = "ERR_ROLLBACK_RESOURCE_REINITIALIZE";
+      break;
+    }
+    case -1074396090: {
+      errorText = "ERR_ROLLBACK_RESOURCE_ENABLED";
+      break;
+    }
+    case -1074396091: {
+      errorText = "ERR_ROLLBACK_RESOURCE_UNINITIALIZED_ENABLE";
+      break;
+    }
+    case -1074396092: {
+      errorText = "ERR_ROLLBACK_RESOURCE_NON_EMPTY_INITIALIZE";
+      break;
+    }
+    case -1074396093: {
+      errorText = "ERR_ROLLBACK_RESOURCE_LOCKED";
+      break;
+    }
+    case -1074396094: {
+      errorText = "ERR_ROLLBACK_RESOURCE_CANNOT_UNLOCK";
+      break;
+    }
+    case -1074396095: {
+      errorText = "ERR_CALIBRATION_DUPLICATE_REFERENCE_POINT";
+      break;
+    }
+    case -1074396096: {
+      errorText = "ERR_NOT_AN_OBJECT";
+      break;
+    }
+    case -1074396097: {
+      errorText = "ERR_INVALID_PARTICLE_PARAMETER_VALUE";
+      break;
+    }
+    case -1074396098: {
+      errorText = "ERR_RESERVED_MUST_BE_nullptr";
+      break;
+    }
+    case -1074396099: {
+      errorText = "ERR_CALIBRATION_INFO_SIMPLE_TRANSFORM";
+      break;
+    }
+    case -1074396100: {
+      errorText = "ERR_CALIBRATION_INFO_PERSPECTIVE_PROJECTION";
+      break;
+    }
+    case -1074396101: {
+      errorText = "ERR_CALIBRATION_INFO_MICRO_PLANE";
+      break;
+    }
+    case -1074396102: {
+      errorText = "ERR_CALIBRATION_INFO_6";
+      break;
+    }
+    case -1074396103: {
+      errorText = "ERR_CALIBRATION_INFO_5";
+      break;
+    }
+    case -1074396104: {
+      errorText = "ERR_CALIBRATION_INFO_4";
+      break;
+    }
+    case -1074396105: {
+      errorText = "ERR_CALIBRATION_INFO_3";
+      break;
+    }
+    case -1074396106: {
+      errorText = "ERR_CALIBRATION_INFO_2";
+      break;
+    }
+    case -1074396107: {
+      errorText = "ERR_CALIBRATION_INFO_1";
+      break;
+    }
+    case -1074396108: {
+      errorText = "ERR_CALIBRATION_ERRORMAP";
+      break;
+    }
+    case -1074396109: {
+      errorText = "ERR_CALIBRATION_INVALID_SCALING_FACTOR";
+      break;
+    }
+    case -1074396110: {
+      errorText = "ERR_CALIBRATION_INFO_VERSION";
+      break;
+    }
+    case -1074396111: {
+      errorText = "ERR_CALIBRATION_FAILED_TO_FIND_GRID";
+      break;
+    }
+    case -1074396112: {
+      errorText = "ERR_INCOMP_MATRIX_SIZE";
+      break;
+    }
+    case -1074396113: {
+      errorText = "ERR_CALIBRATION_IMAGE_UNCALIBRATED";
+      break;
+    }
+    case -1074396114: {
+      errorText = "ERR_CALIBRATION_INVALID_ROI";
+      break;
+    }
+    case -1074396115: {
+      errorText = "ERR_CALIBRATION_IMAGE_CORRECTED";
+      break;
+    }
+    case -1074396116: {
+      errorText = "ERR_CALIBRATION_INSF_POINTS";
+      break;
+    }
+    case -1074396117: {
+      errorText = "ERR_MATRIX_SIZE";
+      break;
+    }
+    case -1074396118: {
+      errorText = "ERR_INVALID_STEP_SIZE";
+      break;
+    }
+    case -1074396119: {
+      errorText = "ERR_CUSTOMDATA_INVALID_KEY";
+      break;
+    }
+    case -1074396120: {
+      errorText = "ERR_NOT_IMAGE";
+      break;
+    }
+    case -1074396121: {
+      errorText = "ERR_SATURATION_THRESHOLD_OUT_OF_RANGE";
+      break;
+    }
+    case -1074396122: {
+      errorText = "ERR_DRAWTEXT_COLOR_MUST_BE_GRAYSCALE";
+      break;
+    }
+    case -1074396123: {
+      errorText = "ERR_INVALID_CALIBRATION_MODE";
+      break;
+    }
+    case -1074396124: {
+      errorText = "ERR_INVALID_CALIBRATION_ROI_MODE";
+      break;
+    }
+    case -1074396125: {
+      errorText = "ERR_INVALID_CONTRAST_THRESHOLD";
+      break;
+    }
+    case -1074396126: {
+      errorText = "ERR_ROLLBACK_RESOURCE_CONFLICT_1";
+      break;
+    }
+    case -1074396127: {
+      errorText = "ERR_ROLLBACK_RESOURCE_CONFLICT_2";
+      break;
+    }
+    case -1074396128: {
+      errorText = "ERR_ROLLBACK_RESOURCE_CONFLICT_3";
+      break;
+    }
+    case -1074396129: {
+      errorText = "ERR_ROLLBACK_UNBOUNDED_INTERFACE";
+      break;
+    }
+    case -1074396130: {
+      errorText = "ERR_NOT_RECT_OR_ROTATED_RECT";
+      break;
+    }
+    case -1074396132: {
+      errorText = "ERR_MASK_NOT_TEMPLATE_SIZE";
+      break;
+    }
+    case -1074396133: {
+      errorText = "ERR_THREAD_COULD_NOT_INITIALIZE";
+      break;
+    }
+    case -1074396134: {
+      errorText = "ERR_THREAD_INITIALIZING";
+      break;
+    }
+    case -1074396135: {
+      errorText = "ERR_INVALID_BUTTON_LABEL";
+      break;
+    }
+    case -1074396136: {
+      errorText = "ERR_DIRECTX_INVALID_FILTER_QUALITY";
+      break;
+    }
+    case -1074396137: {
+      errorText = "ERR_DIRECTX_DLL_NOT_FOUND";
+      break;
+    }
+    case -1074396138: {
+      errorText = "ERR_ROLLBACK_NOT_SUPPORTED";
+      break;
+    }
+    case -1074396139: {
+      errorText = "ERR_ROLLBACK_RESOURCE_OUT_OF_MEMORY";
+      break;
+    }
+    case -1074396140: {
+      errorText = "ERR_BARCODE_CODE128_SET";
+      break;
+    }
+    case -1074396141: {
+      errorText = "ERR_BARCODE_CODE128_FNC";
+      break;
+    }
+    case -1074396142: {
+      errorText = "ERR_BARCODE_INVALID";
+      break;
+    }
+    case -1074396143: {
+      errorText = "ERR_BARCODE_TYPE";
+      break;
+    }
+    case -1074396144: {
+      errorText = "ERR_BARCODE_CODE93_SHIFT";
+      break;
+    }
+    case -1074396145: {
+      errorText = "ERR_BARCODE_UPCA";
+      break;
+    }
+    case -1074396146: {
+      errorText = "ERR_BARCODE_MSI";
+      break;
+    }
+    case -1074396147: {
+      errorText = "ERR_BARCODE_I25";
+      break;
+    }
+    case -1074396148: {
+      errorText = "ERR_BARCODE_EAN13";
+      break;
+    }
+    case -1074396149: {
+      errorText = "ERR_BARCODE_EAN8";
+      break;
+    }
+    case -1074396150: {
+      errorText = "ERR_BARCODE_CODE128";
+      break;
+    }
+    case -1074396151: {
+      errorText = "ERR_BARCODE_CODE93";
+      break;
+    }
+    case -1074396152: {
+      errorText = "ERR_BARCODE_CODE39";
+      break;
+    }
+    case -1074396153: {
+      errorText = "ERR_BARCODE_CODABAR";
+      break;
+    }
+    case -1074396154: {
+      errorText = "ERR_IMAGE_TOO_SMALL";
+      break;
+    }
+    case -1074396155: {
+      errorText = "ERR_UNINIT";
+      break;
+    }
+    case -1074396156: {
+      errorText = "ERR_NEED_FULL_VERSION";
+      break;
+    }
+    case -1074396157: {
+      errorText = "ERR_UNREGISTERED";
+      break;
+    }
+    case -1074396158: {
+      errorText = "ERR_MEMORY_ERROR";
+      break;
+    }
+    case -1074396159: {
+      errorText = "ERR_OUT_OF_MEMORY";
+      break;
+    }
+    case -1074396160: {
+      errorText = "ERR_SYSTEM_ERROR";
+      break;
+    }
+    case 0: {
+      errorText = "ERR_SUCCESS";
+      break;
+    }
+    // end National Instruments defined errors
+
+    // begin BAE defined errors
+    case ERR_VISION_GENERAL_ERROR: {
+      errorText = "ERR_VISION_GENERAL_ERROR";
+      break;
+    }
+    case ERR_COLOR_NOT_FOUND: {
+      errorText = "ERR_COLOR_NOT_FOUND";
+      break;
+    }
+    case ERR_PARTICLE_TOO_SMALL: {
+      errorText = "ERR_PARTICLE_TOO_SMALL";
+      break;
+    }
+    case ERR_CAMERA_FAILURE: {
+      errorText = "ERR_CAMERA_FAILURE";
+      break;
+    }
+    case ERR_CAMERA_SOCKET_CREATE_FAILED: {
+      errorText = "ERR_CAMERA_SOCKET_CREATE_FAILED";
+      break;
+    }
+    case ERR_CAMERA_CONNECT_FAILED: {
+      errorText = "ERR_CAMERA_CONNECT_FAILED";
+      break;
+    }
+    case ERR_CAMERA_STALE_IMAGE: {
+      errorText = "ERR_CAMERA_STALE_IMAGE";
+      break;
+    }
+    case ERR_CAMERA_NOT_INITIALIZED: {
+      errorText = "ERR_CAMERA_NOT_INITIALIZED";
+      break;
+    }
+    case ERR_CAMERA_NO_BUFFER_AVAILABLE: {
+      errorText = "ERR_CAMERA_NO_BUFFER_AVAILABLE";
+      break;
+    }
+    case ERR_CAMERA_HEADER_ERROR: {
+      errorText = "ERR_CAMERA_HEADER_ERROR";
+      break;
+    }
+    case ERR_CAMERA_BLOCKING_TIMEOUT: {
+      errorText = "ERR_CAMERA_BLOCKING_TIMEOUT";
+      break;
+    }
+    case ERR_CAMERA_AUTHORIZATION_FAILED: {
+      errorText = "ERR_CAMERA_AUTHORIZATION_FAILED";
+      break;
+    }
+    case ERR_CAMERA_TASK_SPAWN_FAILED: {
+      errorText = "ERR_CAMERA_TASK_SPAWN_FAILED";
+      break;
+    }
+    case ERR_CAMERA_TASK_INPUT_OUT_OF_RANGE: {
+      errorText = "ERR_CAMERA_TASK_INPUT_OUT_OF_RANGE";
+      break;
+    }
+    case ERR_CAMERA_COMMAND_FAILURE: {
+      errorText = "ERR_CAMERA_COMMAND_FAILURE";
+      break;
+    }
+  }
+
+  return errorText;
+}
diff --git a/wpilibc/Athena/src/Vision/HSLImage.cpp b/wpilibc/Athena/src/Vision/HSLImage.cpp
new file mode 100644
index 0000000..5b114c4
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/HSLImage.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/HSLImage.h"
+
+/**
+ * Create a new image that uses the Hue, Saturation, and Luminance planes.
+ */
+HSLImage::HSLImage() : ColorImage(IMAQ_IMAGE_HSL) {}
+
+/**
+ * Create a new image by loading a file.
+ * @param fileName The path of the file to load.
+ */
+HSLImage::HSLImage(const char *fileName) : ColorImage(IMAQ_IMAGE_HSL) {
+  int success = imaqReadFile(m_imaqImage, fileName, nullptr, nullptr);
+  wpi_setImaqErrorWithContext(success, "Imaq ReadFile error");
+}
diff --git a/wpilibc/Athena/src/Vision/ImageBase.cpp b/wpilibc/Athena/src/Vision/ImageBase.cpp
new file mode 100644
index 0000000..f35234a
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/ImageBase.cpp
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/ImageBase.h"
+#include "nivision.h"
+
+/**
+ * Create a new instance of an ImageBase.
+ * Imagebase is the base of all the other image classes. The constructor
+ * creates any type of image and stores the pointer to it in the class.
+ * @param type The type of image to create
+ */
+ImageBase::ImageBase(ImageType type) {
+  m_imaqImage = imaqCreateImage(type, DEFAULT_BORDER_SIZE);
+}
+
+/**
+ * Frees memory associated with an ImageBase.
+ * Destructor frees the imaq image allocated with the class.
+ */
+ImageBase::~ImageBase() {
+  if (m_imaqImage) imaqDispose(m_imaqImage);
+}
+
+/**
+ * Writes an image to a file with the given filename.
+ * Write the image to a file in the flash on the cRIO.
+ * @param fileName The name of the file to write
+ */
+void ImageBase::Write(const char *fileName) {
+  int success = imaqWriteFile(m_imaqImage, fileName, nullptr);
+  wpi_setImaqErrorWithContext(success, "Imaq Image writeFile error");
+}
+
+/**
+ * Gets the height of an image.
+ * @return The height of the image in pixels.
+ */
+int ImageBase::GetHeight() {
+  int height;
+  imaqGetImageSize(m_imaqImage, nullptr, &height);
+  return height;
+}
+
+/**
+ * Gets the width of an image.
+ * @return The width of the image in pixels.
+ */
+int ImageBase::GetWidth() {
+  int width;
+  imaqGetImageSize(m_imaqImage, &width, nullptr);
+  return width;
+}
+
+/**
+ * Access the internal IMAQ Image data structure.
+ *
+ * @return A pointer to the internal IMAQ Image data structure.
+ */
+Image *ImageBase::GetImaqImage() { return m_imaqImage; }
diff --git a/wpilibc/Athena/src/Vision/MonoImage.cpp b/wpilibc/Athena/src/Vision/MonoImage.cpp
new file mode 100644
index 0000000..90703c0
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/MonoImage.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/MonoImage.h"
+#include "nivision.h"
+
+using namespace std;
+
+MonoImage::MonoImage() : ImageBase(IMAQ_IMAGE_U8) {}
+
+/**
+ * Look for ellipses in an image.
+ * Given some input parameters, look for any number of ellipses in an image.
+ * @param ellipseDescriptor Ellipse descriptor
+ * @param curveOptions Curve options
+ * @param shapeDetectionOptions Shape detection options
+ * @param roi Region of Interest
+ * @returns a vector of EllipseMatch structures (0 length vector on no match)
+ */
+vector<EllipseMatch> *MonoImage::DetectEllipses(
+    EllipseDescriptor *ellipseDescriptor, CurveOptions *curveOptions,
+    ShapeDetectionOptions *shapeDetectionOptions, ROI *roi) {
+  int numberOfMatches;
+  EllipseMatch *e =
+      imaqDetectEllipses(m_imaqImage, ellipseDescriptor, curveOptions,
+                         shapeDetectionOptions, roi, &numberOfMatches);
+  auto ellipses = new vector<EllipseMatch>;
+  if (e == nullptr) {
+    return ellipses;
+  }
+  for (int i = 0; i < numberOfMatches; i++) {
+    ellipses->push_back(e[i]);
+  }
+  imaqDispose(e);
+  return ellipses;
+}
+
+vector<EllipseMatch> *MonoImage::DetectEllipses(
+    EllipseDescriptor *ellipseDescriptor) {
+  vector<EllipseMatch> *ellipses =
+      DetectEllipses(ellipseDescriptor, nullptr, nullptr, nullptr);
+  return ellipses;
+}
diff --git a/wpilibc/Athena/src/Vision/RGBImage.cpp b/wpilibc/Athena/src/Vision/RGBImage.cpp
new file mode 100644
index 0000000..5469122
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/RGBImage.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/RGBImage.h"
+
+/**
+ * Create a new image that uses Red, Green, and Blue planes.
+ */
+RGBImage::RGBImage() : ColorImage(IMAQ_IMAGE_RGB) {}
+
+/**
+ * Create a new image by loading a file.
+ * @param fileName The path of the file to load.
+ */
+RGBImage::RGBImage(const char *fileName) : ColorImage(IMAQ_IMAGE_RGB) {
+  int success = imaqReadFile(m_imaqImage, fileName, nullptr, nullptr);
+  wpi_setImaqErrorWithContext(success, "Imaq ReadFile error");
+}
diff --git a/wpilibc/Athena/src/Vision/Threshold.cpp b/wpilibc/Athena/src/Vision/Threshold.cpp
new file mode 100644
index 0000000..2e17243
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/Threshold.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "Vision/Threshold.h"
+
+Threshold::Threshold(int new_plane1Low, int new_plane1High, int new_plane2Low,
+                     int new_plane2High, int new_plane3Low,
+                     int new_plane3High) {
+  plane1Low = new_plane1Low;
+  plane1High = new_plane1High;
+  plane2Low = new_plane2Low;
+  plane2High = new_plane2High;
+  plane3Low = new_plane3Low;
+  plane3High = new_plane3High;
+}
diff --git a/wpilibc/Athena/src/Vision/VisionAPI.cpp b/wpilibc/Athena/src/Vision/VisionAPI.cpp
new file mode 100644
index 0000000..163721d
--- /dev/null
+++ b/wpilibc/Athena/src/Vision/VisionAPI.cpp
@@ -0,0 +1,821 @@
+/*----------------------------------------------------------------------------*/
+/* 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.  */
+/*----------------------------------------------------------------------------*/
+
+#include <stdlib.h>
+#include <stdarg.h>
+
+#include "Vision/BaeUtilities.h"
+#include "Vision/FrcError.h"
+#include "Vision/VisionAPI.h"
+
+int VisionAPI_debugFlag = 1;
+#define DPRINTF \
+  if (VisionAPI_debugFlag) dprintf
+
+/** @file
+ *    Image Management functions
+ */
+
+/**
+* @brief Create an image object
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_COMPLEX,
+* IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64
+* The border size is defaulted to 3 so that convolutional algorithms work at the
+* edges.
+* When you are finished with the created image, dispose of it by calling
+* frcDispose().
+* To get extended error information, call GetLastError().
+*
+* @param type Type of image to create
+* @return Image* On success, this function returns the created image. On
+* failure, it returns nullptr.
+*/
+Image* frcCreateImage(ImageType type) {
+  return imaqCreateImage(type, DEFAULT_BORDER_SIZE);
+}
+
+/**
+* @brief Dispose of one object. Supports any object created on the heap.
+*
+* @param object object to dispose of
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcDispose(void* object) { return imaqDispose(object); }
+/**
+* @brief Dispose of a list of objects. Supports any object created on the heap.
+*
+* @param functionName The name of the function
+* @param ... A list of pointers to structures that need to be disposed of.
+* The last pointer in the list should always be set to nullptr.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcDispose(const char* functionName, ...) /* Variable argument list */
+{
+  va_list disposalPtrList; /* Input argument list */
+  void* disposalPtr;       /* For iteration */
+  int success, returnValue = 1;
+
+  va_start(disposalPtrList, functionName); /* start of variable list */
+  disposalPtr = va_arg(disposalPtrList, void*);
+  while (disposalPtr != nullptr) {
+    success = imaqDispose(disposalPtr);
+    if (!success) {
+      returnValue = 0;
+    }
+    disposalPtr = va_arg(disposalPtrList, void*);
+  }
+  va_end(disposalPtrList);
+  return returnValue;
+}
+
+/**
+* @brief Copy an image object.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_RGB,
+* IMAQ_IMAGE_HSL.
+*
+* @param dest Copy of image. On failure, dest is nullptr. Must have already been
+* created using frcCreateImage().
+* When you are finished with the created image, dispose of it by calling
+* frcDispose().
+* @param source Image to copy
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcCopyImage(Image* dest, const Image* source) {
+  return imaqDuplicate(dest, source);
+}
+
+/**
+* @brief Crop image without changing the scale.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_RGB,
+* IMAQ_IMAGE_HSL.
+*
+* @param dest Modified image
+* @param source Image to crop
+* @param rect region to process, or IMAQ_NO_RECT
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcCrop(Image* dest, const Image* source, Rect rect) {
+  return imaqScale(dest, source, 1, 1, IMAQ_SCALE_LARGER, rect);
+}
+
+/**
+* @brief Scales the entire image larger or smaller.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_RGB,
+* IMAQ_IMAGE_HSL.
+*
+* @param dest Modified image
+* @param source Image to scale
+* @param xScale the horizontal reduction ratio
+* @param yScale the vertical reduction ratio
+* @param scaleMode IMAQ_SCALE_LARGER or IMAQ_SCALE_SMALLER
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcScale(Image* dest, const Image* source, int xScale, int yScale,
+             ScalingMode scaleMode) {
+  Rect rect = IMAQ_NO_RECT;
+  return imaqScale(dest, source, xScale, yScale, scaleMode, rect);
+}
+
+/**
+ * @brief Creates image object from the information in a file. The file can be
+ * in one of the following formats:
+ * PNG, JPEG, JPEG2000, TIFF, AIPD, or BMP.
+ * Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_COMPLEX,
+ * IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64.
+ *
+ * @param image Image read in
+ * @param fileName File to read. Cannot be nullptr
+ *
+ * @return On success: 1. On failure: 0. To get extended error information, call
+ * GetLastError().
+ */
+int frcReadImage(Image* image, const char* fileName) {
+  return imaqReadFile(image, fileName, nullptr, nullptr);
+}
+
+/**
+* @brief Write image to a file.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL, IMAQ_IMAGE_COMPLEX,
+* IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64.
+*
+* The file type is determined by the extension, as follows:
+*
+* 		Extension 					File Type
+* 		aipd or .apd 				AIPD
+* 		.bmp 						BMP
+* 		.jpg or .jpeg 				JPEG
+* 		.jp2 						JPEG2000
+* 		.png 						PNG
+* 		.tif or .tiff 				TIFF
+*
+*
+* The following are the supported image types for each file type:
+*
+* 		File Types 					Image Types
+* 		AIPD 						all image types
+* 		BMP, JPEG 					8-bit, RGB
+* 		PNG, TIFF, JPEG2000 		8-bit, 16-bit, RGB, RGBU64
+*
+* @param image Image to write
+* @param fileName File to read. Cannot be nullptr. The extension determines the
+* file format that is written.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcWriteImage(const Image* image, const char* fileName) {
+  RGBValue* colorTable = nullptr;
+  return imaqWriteFile(image, fileName, colorTable);
+}
+
+/*  Measure Intensity functions */
+
+/**
+* @brief Measures the pixel intensities in a rectangle of an image.
+* Outputs intensity based statistics about an image such as Max, Min, Mean and
+* Std Dev of pixel value.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+*
+*  Parameter Discussion	:
+* 		Relevant parameters of the HistogramReport include:
+* 			min, max, mean and stdDev
+*		min/max —Setting both min and max to 0 causes the function to set
+* min to 0
+* 			and the max to 255 for 8-bit images and to the actual
+* minimum value and
+* 			maximum value of the image for all other image types.
+*		max—Setting both min and max to 0 causes the function to set max
+* to 255
+* 			for 8-bit images and to the actual maximum value of the
+* image for
+* 			all other image types.
+*
+* @param image Image whose histogram the function calculates.
+* @param numClasses The number of classes into which the function separates the
+* pixels.
+* Determines the number of elements in the histogram array returned
+* @param min The minimum pixel value to consider for the histogram.
+* The function does not count pixels with values less than min.
+* @param max The maximum pixel value to consider for the histogram.
+* The function does not count pixels with values greater than max.
+* @param rect Region of interest in the image. If not included, the entire image
+* is used.
+* @return On success, this function returns a report describing the pixel value
+* classification.
+* When you are finished with the report, dispose of it by calling frcDispose().
+* On failure, this function returns nullptr. To get extended error information,
+* call GetLastError().
+*
+*/
+HistogramReport* frcHistogram(const Image* image, int numClasses, float min,
+                              float max) {
+  Rect rect = IMAQ_NO_RECT;
+  return frcHistogram(image, numClasses, min, max, rect);
+}
+HistogramReport* frcHistogram(const Image* image, int numClasses, float min,
+                              float max, Rect rect) {
+  int success;
+  int fillValue = 1;
+
+  /* create the region of interest */
+  ROI* pRoi = imaqCreateROI();
+  success = imaqAddRectContour(pRoi, rect);
+  if (!success) {
+    GetLastVisionError();
+    return nullptr;
+  }
+
+  /* make a mask from the ROI */
+  Image* pMask = frcCreateImage(IMAQ_IMAGE_U8);
+  success = imaqROIToMask(pMask, pRoi, fillValue, nullptr, nullptr);
+  if (!success) {
+    GetLastVisionError();
+    frcDispose(__FUNCTION__, pRoi, nullptr);
+    return nullptr;
+  }
+
+  /* get a histogram report */
+  HistogramReport* pHr = nullptr;
+  pHr = imaqHistogram(image, numClasses, min, max, pMask);
+
+  /* clean up */
+  frcDispose(__FUNCTION__, pRoi, pMask, nullptr);
+
+  return pHr;
+}
+
+/**
+* @brief Calculates the histogram, or pixel distribution, of a color image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+*
+* @param image Image whose histogram the function calculates.
+* @param numClasses The number of classes into which the function separates the
+* pixels.
+* Determines the number of elements in the histogram array returned
+* @param mode The color space in which to perform the histogram. Possible values
+* include IMAQ_RGB and IMAQ_HSL.
+* @param mask An optional mask image. This image must be an IMAQ_IMAGE_U8 image.
+* The function calculates the histogram using only those pixels in the image
+* whose
+* corresponding pixels in the mask are non-zero. Set this parameter to nullptr to
+* calculate
+* the histogram of the entire image, or use the simplified call.
+*
+* @return On success, this function returns a report describing the
+* classification
+* of each plane in a HistogramReport.
+* When you are finished with the report, dispose of it by calling frcDispose().
+* On failure, this function returns nullptr.
+* To get extended error information, call imaqGetLastError().
+*/
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses,
+                                        ColorMode mode) {
+  return frcColorHistogram(image, numClasses, mode, nullptr);
+}
+
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses,
+                                        ColorMode mode, Image* mask) {
+  return imaqColorHistogram2((Image*)image, numClasses, mode, nullptr, mask);
+}
+
+/**
+* @brief Measures the pixel intensities in a rectangle of an image.
+* Outputs intensity based statistics about an image such as Max, Min, Mean and
+* Std Dev of pixel value.
+* Supports IMAQ_IMAGE_U8 (grayscale) IMAQ_IMAGE_RGB (color) IMAQ_IMAGE_HSL
+* (color-HSL).
+*
+* @param image The image whose pixel value the function queries
+* @param pixel The coordinates of the pixel that the function queries
+* @param value On return, the value of the specified image pixel. This parameter
+* cannot be nullptr.
+* This data structure contains either grayscale, RGB, HSL, Complex or
+* RGBU64Value depending on the type of image.
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcGetPixelValue(const Image* image, Point pixel, PixelValue* value) {
+  return imaqGetPixel(image, pixel, value);
+}
+
+/*   Particle Analysis functions */
+
+/**
+* @brief Filters particles out of an image based on their measurements.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+*
+* @param dest The destination image. If dest is used, it must be the same size
+* as the Source image. It will contain only the filtered particles.
+* @param source The image containing the particles to filter.
+* @param criteria An array of criteria to apply to the particles in the source
+* image. This array cannot be nullptr.
+* See the NIVisionCVI.chm help file for definitions of criteria.
+* @param criteriaCount The number of elements in the criteria array.
+* @param options Binary filter options, including rejectMatches, rejectBorder,
+* and connectivity8.
+* @param rect Area of image to filter. If omitted, the default is entire image.
+* @param numParticles On return, the number of particles left in the image
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcParticleFilter(Image* dest, Image* source,
+                      const ParticleFilterCriteria2* criteria,
+                      int criteriaCount, const ParticleFilterOptions* options,
+                      int* numParticles) {
+  Rect rect = IMAQ_NO_RECT;
+  return frcParticleFilter(dest, source, criteria, criteriaCount, options, rect,
+                           numParticles);
+}
+
+int frcParticleFilter(Image* dest, Image* source,
+                      const ParticleFilterCriteria2* criteria,
+                      int criteriaCount, const ParticleFilterOptions* options,
+                      Rect rect, int* numParticles) {
+  ROI* roi = imaqCreateROI();
+  imaqAddRectContour(roi, rect);
+  return imaqParticleFilter3(dest, source, criteria, criteriaCount, options,
+                             roi, numParticles);
+}
+
+/**
+* @brief Performs morphological transformations on binary images.
+* Supports IMAQ_IMAGE_U8.
+*
+* @param dest The destination image. The border size of the destination image is
+* not important.
+* @param source The image on which the function performs the morphological
+* operations. The calculation
+* modifies the border of the source image. The border must be at least half as
+* large as the larger
+* dimension  of the structuring element.  The connected source image for a
+* morphological transformation
+* must have been created with a border capable of supporting the size of the
+* structuring element.
+* A 3 by 3 structuring element requires a minimal border of 1, a 5 by 5
+* structuring element requires a minimal border of 2, and so on.
+* @param method The morphological transform to apply.
+* @param structuringElement The structuring element used in the operation. Omit
+* this parameter if you do not want a custom structuring element.
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method) {
+  return imaqMorphology(dest, source, method, nullptr);
+}
+
+int frcMorphology(Image* dest, Image* source, MorphologyMethod method,
+                  const StructuringElement* structuringElement) {
+  return imaqMorphology(dest, source, method, structuringElement);
+}
+
+/**
+* @brief Eliminates particles that touch the border of the image.
+* Supports IMAQ_IMAGE_U8.
+*
+* @param dest The destination image.
+* @param source The source image. If the image has a border, the function sets
+* all border pixel values to 0.
+* @param connectivity8 specifies the type of connectivity used by the algorithm
+* for particle detection.
+* The connectivity mode directly determines whether an adjacent pixel belongs to
+* the same particle or a
+* different particle. Set to TRUE to use connectivity-8 to determine whether
+* particles are touching
+* Set to FALSE to use connectivity-4 to determine whether particles are
+* touching.
+* The default setting for the simplified call is TRUE
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcRejectBorder(Image* dest, Image* source) {
+  return imaqRejectBorder(dest, source, TRUE);
+}
+
+int frcRejectBorder(Image* dest, Image* source, int connectivity8) {
+  return imaqRejectBorder(dest, source, connectivity8);
+}
+
+/**
+* @brief Counts the number of particles in a binary image.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+* @param image binary (thresholded) image
+* @param numParticles On return, the number of particles.
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcCountParticles(Image* image, int* numParticles) {
+  return imaqCountParticles(image, 1, numParticles);
+}
+
+/**
+* @brief Conduct measurements for a single particle in an images.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16, IMAQ_IMAGE_SGL.
+*
+* @param image image with the particle to analyze. This function modifies the
+* source image.
+* If you need the original image, create a copy of the image using frcCopy()
+* before using this function.
+* @param particleNumber The number of the particle to get information on
+* @param par on return, a particle analysis report containing information about
+* the particle. This structure must be created by the caller.
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcParticleAnalysis(Image* image, int particleNumber,
+                        ParticleAnalysisReport* par) {
+  int success = 0;
+
+  /* image information */
+  int height, width;
+  if (!imaqGetImageSize(image, &width, &height)) {
+    return success;
+  }
+  par->imageWidth = width;
+  par->imageHeight = height;
+  par->particleIndex = particleNumber;
+
+  /* center of mass point of the largest particle	*/
+  double returnDouble;
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_CENTER_OF_MASS_X, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->center_mass_x = (int)returnDouble;  // pixel
+
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_CENTER_OF_MASS_Y, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->center_mass_y = (int)returnDouble;  // pixel
+
+  /* particle size statistics */
+  success = imaqMeasureParticle(image, particleNumber, 0, IMAQ_MT_AREA,
+                                &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->particleArea = returnDouble;
+
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_BOUNDING_RECT_TOP, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->boundingRect.top = (int)returnDouble;
+
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_BOUNDING_RECT_LEFT, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->boundingRect.left = (int)returnDouble;
+
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_BOUNDING_RECT_HEIGHT, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->boundingRect.height = (int)returnDouble;
+
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_BOUNDING_RECT_WIDTH, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->boundingRect.width = (int)returnDouble;
+
+  /* particle quality statistics */
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_AREA_BY_IMAGE_AREA, &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->particleToImagePercent = returnDouble;
+
+  success = imaqMeasureParticle(image, particleNumber, 0,
+                                IMAQ_MT_AREA_BY_PARTICLE_AND_HOLES_AREA,
+                                &returnDouble);
+  if (!success) {
+    return success;
+  }
+  par->particleQuality = returnDouble;
+
+  /* normalized position (-1 to 1) */
+  par->center_mass_x_normalized = RangeToNormalized(par->center_mass_x, width);
+  par->center_mass_y_normalized = RangeToNormalized(par->center_mass_y, height);
+
+  return success;
+}
+
+/*   Image Enhancement functions */
+
+/**
+* @brief Improves contrast on a grayscale image.
+* Supports IMAQ_IMAGE_U8, IMAQ_IMAGE_I16.
+* @param dest The destination image.
+* @param source The image to equalize
+* @param min the smallest value used for processing. After processing, all pixel
+* values that are less than or equal to the Minimum in the original image are set
+* to 0 for an 8-bit image. In 16-bit and floating-point images, these pixel
+* values are set to the smallest pixel value found in the original image.
+* @param max the largest value used for processing. After processing, all pixel
+* values that are greater than or equal to the Maximum in the original image are
+* set to 255 for an 8-bit image. In 16-bit and floating-point images, these pixel
+* values are set to the largest pixel value found in the original image.
+* @param mask an 8-bit image that specifies the region of the small image that
+* will be copied. Only those pixels in the Image Src (Small) image that
+* correspond to an equivalent non-zero pixel in the mask image are copied. All
+* other pixels keep their original values. The entire image is processed if Image
+* Mask is nullptr or this parameter is omitted.
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*
+*  option defaults:
+*       searchRect = IMAQ_NO_RECT
+* 		minMatchScore = DEFAULT_MINMAX_SCORE (800)
+*/
+int frcEqualize(Image* dest, const Image* source, float min, float max) {
+  return frcEqualize(dest, source, min, max, nullptr);
+}
+
+int frcEqualize(Image* dest, const Image* source, float min, float max,
+                const Image* mask) {
+  return imaqEqualize(dest, source, min, max, mask);
+}
+
+/**
+* @brief Improves contrast on a color image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL
+*
+* option defaults: colorEqualization = TRUE to equalize all three planes of the
+* image
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+* @param dest The destination image.
+* @param source The image to equalize
+* @param colorEqualization Set this parameter to TRUE to equalize all three
+* planes of the image (the default). Set this parameter to FALSE to equalize only
+* the luminance plane.
+*/
+int frcColorEqualize(Image* dest, const Image* source) {
+  return imaqColorEqualize(dest, source, TRUE);
+}
+
+int frcColorEqualize(Image* dest, const Image* source, int colorEqualization) {
+  return imaqColorEqualize(dest, source, TRUE);
+}
+
+/*   Image Conversion functions */
+
+/**
+* @brief Automatically thresholds a grayscale image into a binary image for
+* Particle Analysis based on a smart threshold.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_I16
+* @param dest The destination image.
+* @param source The image to threshold
+* @param windowWidth The width of the rectangular window around the pixel on
+* which the function
+*  performs the local threshold. This number must be at least 3 and cannot be
+* larger than the width of source
+* @param windowHeight The height of the rectangular window around the pixel on
+* which the function
+* performs the local threshold. This number must be at least 3 and cannot be
+* larger than the height of source
+* @param method Specifies the local thresholding method the function uses. Value
+* can be IMAQ_NIBLACK
+* (which computes thresholds for each pixel based on its local statistics using
+* the Niblack local thresholding
+* algorithm.), or IMAQ_BACKGROUND_CORRECTION (which does background correction
+* first to eliminate non-uniform
+* lighting effects, then performs thresholding using the Otsu thresholding
+* algorithm)
+* @param deviationWeight Specifies the k constant used in the Niblack local
+* thresholding algorithm, which
+* determines the weight applied to the variance calculation. Valid k constants
+* range from 0 to 1. Setting
+* this value to 0 will increase the performance of the function because the
+* function will not calculate the
+* variance for any of the pixels. The function ignores this value if method is
+* not set to IMAQ_NIBLACK
+* @param type Specifies the type of objects for which you want to look. Values
+* can be IMAQ_BRIGHT_OBJECTS
+* or IMAQ_DARK_OBJECTS.
+* @param replaceValue Specifies the replacement value the function uses for the
+* pixels of the kept objects
+* in the destination image.
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcSmartThreshold(Image* dest, const Image* source,
+                      unsigned int windowWidth, unsigned int windowHeight,
+                      LocalThresholdMethod method, double deviationWeight,
+                      ObjectType type) {
+  float replaceValue = 1.0;
+  return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method,
+                            deviationWeight, type, replaceValue);
+}
+
+int frcSmartThreshold(Image* dest, const Image* source,
+                      unsigned int windowWidth, unsigned int windowHeight,
+                      LocalThresholdMethod method, double deviationWeight,
+                      ObjectType type, float replaceValue) {
+  return imaqLocalThreshold(dest, source, windowWidth, windowHeight, method,
+                            deviationWeight, type, replaceValue);
+}
+
+/**
+* @brief Converts a grayscale image to a binary image for Particle Analysis
+* based on a fixed threshold.
+* The function sets pixels values outside of the given range to 0. The function
+* sets pixel values
+* within the range to a given value or leaves the values unchanged.
+* Use the simplified call to leave pixel values unchanged.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_I16.
+*
+* @param dest The destination image.
+* @param source The image to threshold
+* @param rangeMin The lower boundary of the range of pixel values to keep
+* @param rangeMax The upper boundary of the range of pixel values to keep.
+*
+* @return int - error code: 0 = error. To get extended error information, call
+* GetLastError().
+*/
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin,
+                       float rangeMax) {
+  int newValue = 255;
+  return frcSimpleThreshold(dest, source, rangeMin, rangeMax, newValue);
+}
+
+/**
+* @brief Converts a grayscale image to a binary image for Particle Analysis
+* based on a fixed threshold.
+* The function sets pixels values outside of the given range to 0. The function
+* sets
+* pixel values within the range to the given value.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_I16.
+*
+* @param dest The destination image.
+* @param source The image to threshold
+* @param rangeMin The lower boundary of the range of pixel values to keep
+* @param rangeMax The upper boundary of the range of pixel values to keep.
+* @param newValue The replacement value for pixels within the range. Use the
+* simplified call to leave the pixel values unchanged
+*
+* @return int - error code: 0 = error. To get extended error information, call
+* GetLastError().
+*/
+int frcSimpleThreshold(Image* dest, const Image* source, float rangeMin,
+                       float rangeMax, float newValue) {
+  int useNewValue = TRUE;
+  return imaqThreshold(dest, source, rangeMin, rangeMax, useNewValue, newValue);
+}
+
+/**
+* @brief Applies a threshold to the Red, Green, and Blue values of a RGB image
+* or the Hue,
+* Saturation, Luminance values for a HSL image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+* This simpler version filters based on a hue range in the HSL mode.
+*
+* @param dest The destination image. This must be a IMAQ_IMAGE_U8 image.
+* @param source The image to threshold
+* @param mode The color space to perform the threshold in. valid values are:
+* IMAQ_RGB, IMAQ_HSL.
+* @param plane1Range The selection range for the first plane of the image. Set
+* this parameter to nullptr to use a selection range from 0 to 255.
+* @param plane2Range The selection range for the second plane of the image. Set
+* this parameter to nullptr to use a selection range from 0 to 255.
+* @param plane3Range The selection range for the third plane of the image. Set
+* this parameter to nullptr to use a selection range from 0 to 255.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+* */
+int frcColorThreshold(Image* dest, const Image* source, ColorMode mode,
+                      const Range* plane1Range, const Range* plane2Range,
+                      const Range* plane3Range) {
+  int replaceValue = 1;
+  return imaqColorThreshold(dest, source, replaceValue, mode, plane1Range,
+                            plane2Range, plane3Range);
+}
+
+/**
+* @brief Applies a threshold to the Red, Green, and Blue values of a RGB image
+* or the Hue,
+* Saturation, Luminance values for a HSL image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+* The simpler version filters based on a hue range in the HSL mode.
+*
+* @param dest The destination image. This must be a IMAQ_IMAGE_U8 image.
+* @param source The image to threshold
+* @param replaceValue Value to assign to selected pixels. Defaults to 1 if
+* simplified call is used.
+* @param mode The color space to perform the threshold in. valid values are:
+* IMAQ_RGB, IMAQ_HSL.
+* @param plane1Range The selection range for the first plane of the image. Set
+* this parameter to nullptr to use a selection range from 0 to 255.
+* @param plane2Range The selection range for the second plane of the image. Set
+* this parameter to nullptr to use a selection range from 0 to 255.
+* @param plane3Range The selection range for the third plane of the image. Set
+* this parameter to nullptr to use a selection range from 0 to 255.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcColorThreshold(Image* dest, const Image* source, int replaceValue,
+                      ColorMode mode, const Range* plane1Range,
+                      const Range* plane2Range, const Range* plane3Range) {
+  return imaqColorThreshold(dest, source, replaceValue, mode, plane1Range,
+                            plane2Range, plane3Range);
+}
+
+/**
+* @brief A simpler version of ColorThreshold that thresholds hue range in the
+* HSL mode. Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL.
+* @param dest The destination image.
+* @param source The image to threshold
+* @param hueRange The selection range for the hue (color).
+* @param minSaturation The minimum saturation value (1-255).  If not used,
+* DEFAULT_SATURATION_THRESHOLD is the default.
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange) {
+  return frcHueThreshold(dest, source, hueRange, DEFAULT_SATURATION_THRESHOLD);
+}
+
+int frcHueThreshold(Image* dest, const Image* source, const Range* hueRange,
+                    int minSaturation) {
+  // assume HSL mode
+  ColorMode mode = IMAQ_HSL;
+  // Set saturation 100 - 255
+  Range satRange;
+  satRange.minValue = minSaturation;
+  satRange.maxValue = 255;
+  // Set luminance 100 - 255
+  Range lumRange;
+  lumRange.minValue = 100;
+  lumRange.maxValue = 255;
+  // Replace pixels with 1 if pass threshold filter
+  int replaceValue = 1;
+  return imaqColorThreshold(dest, source, replaceValue, mode, hueRange,
+                            &satRange, &lumRange);
+}
+
+/**
+* @brief Extracts the Red, Green, Blue, or Hue, Saturation or Luminance
+* information from a color image.
+* Supports IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64.
+*
+* @param image The source image that the function extracts the planes from.
+* @param mode The color space that the function extracts the planes from. Valid
+* values are IMAQ_RGB, IMAQ_HSL, IMAQ_HSV, IMAQ_HSI.
+* @param plane1 On return, the first extracted plane. Set this parameter to nullptr
+* if you do not need this information. RGB-Red, HSL/HSV/HSI-Hue.
+* @param plane2 On return, the second extracted plane. Set this parameter to
+* nullptr if you do not need this information. RGB-Green, HSL/HSV/HSI-Saturation.
+* @param plane3 On return, the third extracted plane. Set this parameter to nullptr
+* if you do not need this information. RGB-Blue, HSL-Luminance, HSV-Value,
+* HSI-Intensity.
+*
+* @return error code: 0 = error. To get extended error information, call
+* GetLastError().
+*/
+int frcExtractColorPlanes(const Image* image, ColorMode mode, Image* plane1,
+                          Image* plane2, Image* plane3) {
+  return imaqExtractColorPlanes(image, mode, plane1, plane2, plane3);
+}
+
+/**
+* @brief Extracts the Hue information from a color image. Supports
+* IMAQ_IMAGE_RGB, IMAQ_IMAGE_HSL, IMAQ_IMAGE_RGB_U64
+*
+* @param image The source image that the function extracts the plane from.
+* @param huePlane On return, the extracted hue plane.
+* @param minSaturation the minimum saturation level required 0-255 (try 50)
+*
+* @return On success: 1. On failure: 0. To get extended error information, call
+* GetLastError().
+*/
+int frcExtractHuePlane(const Image* image, Image* huePlane) {
+  return frcExtractHuePlane(image, huePlane, DEFAULT_SATURATION_THRESHOLD);
+}
+
+int frcExtractHuePlane(const Image* image, Image* huePlane, int minSaturation) {
+  return frcExtractColorPlanes(image, IMAQ_HSL, huePlane, nullptr, nullptr);
+}