add an initial version of WPILib

This is our commit 24ccb7836abaa36b0e913474c818da4b6ae7bc9a which
corresponds with FPGA image v23.

Change-Id: I25b999bbcef39aaea6132562c80360d87780b8c3
diff --git a/aos/externals/allwpilib/README b/aos/externals/allwpilib/README
new file mode 100644
index 0000000..90595b6
--- /dev/null
+++ b/aos/externals/allwpilib/README
@@ -0,0 +1,3 @@
+This is our version of WPILib. We copy the wpilibc/ and hal/ folders from
+our customized version periodically. The commit messages all include the commit
+which is being copied in and the corresponding FPGA image version.
diff --git a/aos/externals/allwpilib/hal/CMakeLists.txt b/aos/externals/allwpilib/hal/CMakeLists.txt
new file mode 100644
index 0000000..5ad2e64
--- /dev/null
+++ b/aos/externals/allwpilib/hal/CMakeLists.txt
@@ -0,0 +1,17 @@
+cmake_minimum_required(VERSION 2.8)
+project(HAL)
+
+file(GLOB_RECURSE SRC_FILES lib/Athena/*.cpp)
+include_directories(lib/Athena lib/Athena/FRC_FPGA_ChipObject include)
+add_library(HALAthena STATIC ${SRC_FILES})
+target_link_libraries(HALAthena ${NI_LIBS})
+INSTALL(TARGETS HALAthena ARCHIVE DESTINATION lib COMPONENT lib)
+INSTALL(FILES ${NI_LIBS} ${WPI_LD_LIBS} DESTINATION lib COMPONENT ni_lib)
+INSTALL(DIRECTORY include DESTINATION ${CMAKE_INSTALL_PREFIX} COMPONENT headers)
+
+add_library(HALAthena_shared SHARED ${SRC_FILES})
+target_link_libraries(HALAthena_shared ${NI_LIBS})
+INSTALL(TARGETS HALAthena_shared LIBRARY DESTINATION lib COMPONENT lib)
+# lib/ c m gcc_s ld-linux
+# usr/lib 
+# FRC_NetworkCommunication FRC_FPGA_ChipObject RoboRIO_FRC_ChipObject
diff --git a/aos/externals/allwpilib/hal/README.org b/aos/externals/allwpilib/hal/README.org
new file mode 100644
index 0000000..9eb132a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/README.org
@@ -0,0 +1,94 @@
+
+* Purpose
+The HAL is a hardware abstraction layer that provides a uniform
+interface that can be used to access a number of primarily I/O
+features in the underlying platform. The features include:
+- Analog input, accumulation and triggers
+- PWM, Relay and Solenoid output
+- Digital input and output
+- I2C and SPI communication
+- Encoders and counters
+- Interrupts and Notifiers
+
+The initial goal is to allow a higher level like WPILib to support
+both the CRIO and the upcoming Athena platform only by changing which
+version of the HAL it's running on.
+
+* Editing
+You can always use any text editor and then build with Maven. There
+are also eclipse project files so that it can be edited in the same
+eclipse environment that teams develop with. For the AthenaXX, this
+can be found in the =root= directory of this project. It imports as an
+FRC Robot C++ Eclipse project. The Windriver project can be imported
+from the =src= directory.
+
+* Building with Maven
+There are multiple build targets that the HAL supports. Instructions
+for setting up the environment and building each of these is described
+below. Current targets are listed below:
+- All: All of the following targets.
+- include: The header files for the HAL.
+- Azalea: CRIO C++ build.
+- AthenaXX: Athena Dos Equis C++ build.
+- AthenaXXJava: Athena Dos Equis Java build with auto-generated JNA
+  wrappers.
+
+Output from each build target is placed in the directory
+=target/<target-name>=. So, the Azalea output is placed in
+=target/Azalea=.
+
+** All
+Note: Windows only due to the Windriver requirement.
+1. Ensure that =C:\WindRiver\gnu\3.4.4-vxworks-6.3\x86-win32\bin= is
+   on the system path so that =ccppc= and =arppc= can be accessed.
+2. Set the environment variable =WIND_BASE= to =C:\WindRiver\vxworks-6.3=.
+3. Ensure that
+   =$HOME/wpilib/toolchains/arm-none-linux-gnueabi-4.4.1/bin/= is on
+   the system path so that =arm-none-linux-gnueabi-g++= and
+   =arm-none-linux-gnueabi-ar= can be accessed.
+4. Checkout and install the NI-Libraries from Github:
+   [[https://github.com/first/NI-Libraries]].
+5. Run the following maven command:
+   =mvn clean install=
+6. Success
+
+** include
+1. =cd= into the include directory: =cd include=
+2. Run the following maven command:
+   =mvn clean install=
+3. Success
+
+** Azalea
+Note: Windows only.
+1. Ensure that =C:\WindRiver\gnu\3.4.4-vxworks-6.3\x86-win32\bin= is
+   on the system path so that =ccppc= and =arppc= can be accessed.
+2. Set the environment variable =WIND_BASE= to =C:\WindRiver\vxworks-6.3=.
+3. =cd= into the AthenaXX directory: =cd AthenaXX=
+4. =cd= into the Azalea directory:  =cd Azalea=
+5. Run the following maven command:
+   =mvn clean install=
+6. Success
+
+** AthenaXX
+1. Ensure that
+   =$HOME/wpilib/toolchains/arm-none-linux-gnueabi-4.4.1/bin/= is on
+   the system path so that =arm-none-linux-gnueabi-g++= and
+   =arm-none-linux-gnueabi-ar= can be accessed.
+2. Install the include target.
+3. =cd= into the AthenaXX directory: =cd AthenaXX=
+4. Run the following maven command:
+   =mvn clean install=
+5. Success
+
+** AthenaXXJava
+1. Ensure that
+   =$HOME/wpilib/toolchains/arm-none-linux-gnueabi-4.4.1/bin/= is on
+   the system path so that =arm-none-linux-gnueabi-g++= and
+   =arm-none-linux-gnueabi-ar= can be accessed.
+2. Checkout and install the NI-Libraries from Github:
+   [[https://github.com/first/NI-Libraries]].
+3. Install the include target.
+4. =cd= into the AthenaXXJava directory: =cd AthenaXXJava=
+5. Run the following maven command:
+   =mvn clean install=
+6. Success
diff --git a/aos/externals/allwpilib/hal/include/HAL/Accelerometer.hpp b/aos/externals/allwpilib/hal/include/HAL/Accelerometer.hpp
new file mode 100644
index 0000000..103fb2a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Accelerometer.hpp
@@ -0,0 +1,15 @@
+#pragma once
+
+enum AccelerometerRange {
+	kRange_2G = 0,
+	kRange_4G = 1,
+	kRange_8G = 2,
+};
+
+extern "C" {
+	void setAccelerometerActive(bool);
+	void setAccelerometerRange(AccelerometerRange);
+	double getAccelerometerX();
+	double getAccelerometerY();
+	double getAccelerometerZ();
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Analog.hpp b/aos/externals/allwpilib/hal/include/HAL/Analog.hpp
new file mode 100644
index 0000000..981aa9e
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Analog.hpp
@@ -0,0 +1,80 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+enum AnalogTriggerType
+{
+	kInWindow = 0,
+	kState = 1,
+	kRisingPulse = 2,
+	kFallingPulse = 3
+};
+
+extern "C"
+{
+	// Analog output functions
+	void* initializeAnalogOutputPort(void* port_pointer, int32_t *status);
+	void setAnalogOutput(void* analog_port_pointer, double voltage, int32_t *status);
+	double getAnalogOutput(void* analog_port_pointer, int32_t *status);
+	bool checkAnalogOutputChannel(uint32_t pin);
+
+	// Analog input functions
+	void* initializeAnalogInputPort(void* port_pointer, int32_t *status);
+	bool checkAnalogModule(uint8_t module);
+	bool checkAnalogInputChannel(uint32_t pin);
+
+	void setAnalogSampleRate(double samplesPerSecond, int32_t *status);
+	float getAnalogSampleRate(int32_t *status);
+	void setAnalogAverageBits(void* analog_port_pointer, uint32_t bits, int32_t *status);
+	uint32_t getAnalogAverageBits(void* analog_port_pointer, int32_t *status);
+	void setAnalogOversampleBits(void* analog_port_pointer, uint32_t bits, int32_t *status);
+	uint32_t getAnalogOversampleBits(void* analog_port_pointer, int32_t *status);
+	int16_t getAnalogValue(void* analog_port_pointer, int32_t *status);
+	int32_t getAnalogAverageValue(void* analog_port_pointer, int32_t *status);
+	int32_t getAnalogVoltsToValue(void* analog_port_pointer, double voltage, int32_t *status);
+	float getAnalogVoltage(void* analog_port_pointer, int32_t *status);
+	float getAnalogAverageVoltage(void* analog_port_pointer, int32_t *status);
+	uint32_t getAnalogLSBWeight(void* analog_port_pointer, int32_t *status);
+	int32_t getAnalogOffset(void* analog_port_pointer, int32_t *status);
+
+	bool isAccumulatorChannel(void* analog_port_pointer, int32_t *status);
+	void initAccumulator(void* analog_port_pointer, int32_t *status);
+	void resetAccumulator(void* analog_port_pointer, int32_t *status);
+	void setAccumulatorCenter(void* analog_port_pointer, int32_t center, int32_t *status);
+	void setAccumulatorDeadband(void* analog_port_pointer, int32_t deadband, int32_t *status);
+	int64_t getAccumulatorValue(void* analog_port_pointer, int32_t *status);
+	uint32_t getAccumulatorCount(void* analog_port_pointer, int32_t *status);
+	void getAccumulatorOutput(void* analog_port_pointer, int64_t *value, uint32_t *count,
+			int32_t *status);
+
+	void* initializeAnalogTrigger(void* port_pointer, uint32_t *index, int32_t *status);
+	void cleanAnalogTrigger(void* analog_trigger_pointer, int32_t *status);
+	void setAnalogTriggerLimitsRaw(void* analog_trigger_pointer, int32_t lower, int32_t upper,
+			int32_t *status);
+	void setAnalogTriggerLimitsVoltage(void* analog_trigger_pointer, double lower, double upper,
+			int32_t *status);
+	void setAnalogTriggerAveraged(void* analog_trigger_pointer, bool useAveragedValue,
+			int32_t *status);
+	void setAnalogTriggerFiltered(void* analog_trigger_pointer, bool useFilteredValue,
+			int32_t *status);
+	bool getAnalogTriggerInWindow(void* analog_trigger_pointer, int32_t *status);
+	bool getAnalogTriggerTriggerState(void* analog_trigger_pointer, int32_t *status);
+	bool getAnalogTriggerOutput(void* analog_trigger_pointer, AnalogTriggerType type,
+			int32_t *status);
+
+	//// Float JNA Hack
+	// Float
+	int getAnalogSampleRateIntHack(int32_t *status);
+	int getAnalogVoltageIntHack(void* analog_port_pointer, int32_t *status);
+	int getAnalogAverageVoltageIntHack(void* analog_port_pointer, int32_t *status);
+
+	// Doubles
+	void setAnalogSampleRateIntHack(int samplesPerSecond, int32_t *status);
+	int32_t getAnalogVoltsToValueIntHack(void* analog_port_pointer, int voltage, int32_t *status);
+	void setAnalogTriggerLimitsVoltageIntHack(void* analog_trigger_pointer, int lower, int upper,
+			int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/CAN.hpp b/aos/externals/allwpilib/hal/include/HAL/CAN.hpp
new file mode 100644
index 0000000..80b589c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/CAN.hpp
@@ -0,0 +1,26 @@
+#pragma once
+
+#include <stdint.h>
+#include "NetworkCommunication/CANSessionMux.h"
+
+void canTxSend(uint32_t arbID, uint8_t length, int32_t period = CAN_SEND_PERIOD_NO_REPEAT);
+
+void canTxPackInt8 (uint32_t arbID, uint8_t offset, uint8_t  value);
+void canTxPackInt16(uint32_t arbID, uint8_t offset, uint16_t value);
+void canTxPackInt32(uint32_t arbID, uint8_t offset, uint32_t value);
+void canTxPackFXP16(uint32_t arbID, uint8_t offset, double   value);
+void canTxPackFXP32(uint32_t arbID, uint8_t offset, double   value);
+
+uint8_t  canTxUnpackInt8 (uint32_t arbID, uint8_t offset);
+uint32_t canTxUnpackInt32(uint32_t arbID, uint8_t offset);
+uint16_t canTxUnpackInt16(uint32_t arbID, uint8_t offset);
+double   canTxUnpackFXP16(uint32_t arbID, uint8_t offset);
+double   canTxUnpackFXP32(uint32_t arbID, uint8_t offset);
+
+bool canRxReceive(uint32_t arbID);
+
+uint8_t  canRxUnpackInt8 (uint32_t arbID, uint8_t offset);
+uint16_t canRxUnpackInt16(uint32_t arbID, uint8_t offset);
+uint32_t canRxUnpackInt32(uint32_t arbID, uint8_t offset);
+double   canRxUnpackFXP16(uint32_t arbID, uint8_t offset);
+double   canRxUnpackFXP32(uint32_t arbID, uint8_t offset);
diff --git a/aos/externals/allwpilib/hal/include/HAL/Compressor.hpp b/aos/externals/allwpilib/hal/include/HAL/Compressor.hpp
new file mode 100644
index 0000000..5c222eb
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Compressor.hpp
@@ -0,0 +1,37 @@
+/**
+ * Compressor.h
+ * Methods for interacting with a compressor with the CAN PCM device
+ */
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+#ifndef __HAL_COMPRESSOR_H__
+#define __HAL_COMPRESSOR_H__
+
+extern "C" {
+	void *initializeCompressor(uint8_t module);
+	bool checkCompressorModule(uint8_t module);
+	
+	bool getCompressor(void *pcm_pointer, int32_t *status);
+	
+	void setClosedLoopControl(void *pcm_pointer, bool value, int32_t *status);
+	bool getClosedLoopControl(void *pcm_pointer, int32_t *status);
+	
+	bool getPressureSwitch(void *pcm_pointer, int32_t *status);
+	float getCompressorCurrent(void *pcm_pointer, int32_t *status);
+
+	bool getCompressorCurrentTooHighFault(void *pcm_pointer, int32_t *status);
+	bool getCompressorCurrentTooHighStickyFault(void *pcm_pointer, int32_t *status);
+	bool getCompressorShortedStickyFault(void *pcm_pointer, int32_t *status);
+	bool getCompressorShortedFault(void *pcm_pointer, int32_t *status);
+	bool getCompressorNotConnectedStickyFault(void *pcm_pointer, int32_t *status);
+	bool getCompressorNotConnectedFault(void *pcm_pointer, int32_t *status);
+	void clearAllPCMStickyFaults(void *pcm_pointer, int32_t *status);
+}
+
+#endif
+
diff --git a/aos/externals/allwpilib/hal/include/HAL/Digital.hpp b/aos/externals/allwpilib/hal/include/HAL/Digital.hpp
new file mode 100644
index 0000000..a860381
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Digital.hpp
@@ -0,0 +1,122 @@
+#pragma once
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+#include "HAL/cpp/Synchronized.hpp"
+
+enum Mode
+{
+	kTwoPulse = 0,
+	kSemiperiod = 1,
+	kPulseLength = 2,
+	kExternalDirection = 3
+};
+
+extern "C"
+{
+	void* initializeDigitalPort(void* port_pointer, int32_t *status);
+	bool checkPWMChannel(void* digital_port_pointer);
+	bool checkRelayChannel(void* digital_port_pointer);
+
+	void setPWM(void* digital_port_pointer, unsigned short value, int32_t *status);
+	bool allocatePWMChannel(void* digital_port_pointer, int32_t *status);
+	void freePWMChannel(void* digital_port_pointer, int32_t *status);
+	unsigned short getPWM(void* digital_port_pointer, int32_t *status);
+	void latchPWMZero(void* digital_port_pointer, int32_t *status);
+	void setPWMPeriodScale(void* digital_port_pointer, uint32_t squelchMask, int32_t *status);
+	void* allocatePWM(int32_t *status);
+	void freePWM(void* pwmGenerator, int32_t *status);
+	void setPWMRate(double rate, int32_t *status);
+	void setPWMDutyCycle(void* pwmGenerator, double dutyCycle, int32_t *status);
+	void setPWMOutputChannel(void* pwmGenerator, uint32_t pin, int32_t *status);
+
+	void setRelayForward(void* digital_port_pointer, bool on, int32_t *status);
+	void setRelayReverse(void* digital_port_pointer, bool on, int32_t *status);
+	bool getRelayForward(void* digital_port_pointer, int32_t *status);
+	bool getRelayReverse(void* digital_port_pointer, int32_t *status);
+
+	bool allocateDIO(void* digital_port_pointer, bool input, int32_t *status);
+	void freeDIO(void* digital_port_pointer, int32_t *status);
+	void setDIO(void* digital_port_pointer, short value, int32_t *status);
+	bool getDIO(void* digital_port_pointer, int32_t *status);
+	bool getDIODirection(void* digital_port_pointer, int32_t *status);
+	void pulse(void* digital_port_pointer, double pulseLength, int32_t *status);
+	bool isPulsing(void* digital_port_pointer, int32_t *status);
+	bool isAnyPulsing(int32_t *status);
+
+	void setFilterSelect(void* digital_port_pointer, int filter_index,
+	                   int32_t* status);
+	int getFilterSelect(void* digital_port_pointer, int32_t* status);
+
+	void setFilterPeriod(int filter_index, uint32_t value, int32_t *status);
+	uint32_t getFilterPeriod(int filter_index, int32_t *status);
+
+	void* initializeCounter(Mode mode, uint32_t *index, int32_t *status);
+	void freeCounter(void* counter_pointer, int32_t *status);
+	void setCounterAverageSize(void* counter_pointer, int32_t size, int32_t *status);
+	void setCounterUpSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status);
+	void setCounterUpSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge,
+			int32_t *status);
+	void clearCounterUpSource(void* counter_pointer, int32_t *status);
+	void setCounterDownSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status);
+	void setCounterDownSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge,
+			int32_t *status);
+	void clearCounterDownSource(void* counter_pointer, int32_t *status);
+	void setCounterUpDownMode(void* counter_pointer, int32_t *status);
+	void setCounterExternalDirectionMode(void* counter_pointer, int32_t *status);
+	void setCounterSemiPeriodMode(void* counter_pointer, bool highSemiPeriod, int32_t *status);
+	void setCounterPulseLengthMode(void* counter_pointer, double threshold, int32_t *status);
+	int32_t getCounterSamplesToAverage(void* counter_pointer, int32_t *status);
+	void setCounterSamplesToAverage(void* counter_pointer, int samplesToAverage, int32_t *status);
+	void resetCounter(void* counter_pointer, int32_t *status);
+	int32_t getCounter(void* counter_pointer, int32_t *status);
+	double getCounterPeriod(void* counter_pointer, int32_t *status);
+	void setCounterMaxPeriod(void* counter_pointer, double maxPeriod, int32_t *status);
+	void setCounterUpdateWhenEmpty(void* counter_pointer, bool enabled, int32_t *status);
+	bool getCounterStopped(void* counter_pointer, int32_t *status);
+	bool getCounterDirection(void* counter_pointer, int32_t *status);
+	void setCounterReverseDirection(void* counter_pointer, bool reverseDirection, int32_t *status);
+
+	void* initializeEncoder(uint8_t port_a_module, uint32_t port_a_pin, bool port_a_analog_trigger,
+			uint8_t port_b_module, uint32_t port_b_pin, bool port_b_analog_trigger,
+			bool reverseDirection, int32_t *index, int32_t *status); // TODO: fix routing
+	void freeEncoder(void* encoder_pointer, int32_t *status);
+	void resetEncoder(void* encoder_pointer, int32_t *status);
+	int32_t getEncoder(void* encoder_pointer, int32_t *status); // Raw value
+	double getEncoderPeriod(void* encoder_pointer, int32_t *status);
+	void setEncoderMaxPeriod(void* encoder_pointer, double maxPeriod, int32_t *status);
+	bool getEncoderStopped(void* encoder_pointer, int32_t *status);
+	bool getEncoderDirection(void* encoder_pointer, int32_t *status);
+	void setEncoderReverseDirection(void* encoder_pointer, bool reverseDirection, int32_t *status);
+	void setEncoderSamplesToAverage(void* encoder_pointer, uint32_t samplesToAverage,
+			int32_t *status);
+	uint32_t getEncoderSamplesToAverage(void* encoder_pointer, int32_t *status);
+
+	uint16_t getLoopTiming(int32_t *status);
+
+	void spiInitialize(uint8_t port, int32_t *status);
+	int32_t spiTransaction(uint8_t port, uint8_t *dataToSend, uint8_t *dataReceived, uint8_t size);
+	int32_t spiWrite(uint8_t port, uint8_t* dataToSend, uint8_t sendSize);
+	int32_t spiRead(uint8_t port, uint8_t *buffer, uint8_t count);
+	void spiClose(uint8_t port);
+	void spiSetSpeed(uint8_t port, uint32_t speed);
+	void spiSetBitsPerWord(uint8_t port, uint8_t bpw);
+	void spiSetOpts(uint8_t port, int msb_first, int sample_on_trailing, int clk_idle_high);
+	void spiSetChipSelectActiveHigh(uint8_t port, int32_t *status);
+	void spiSetChipSelectActiveLow(uint8_t port, int32_t *status);
+	int32_t spiGetHandle(uint8_t port);
+	void spiSetHandle(uint8_t port, int32_t handle);
+
+	void i2CInitialize(uint8_t port, int32_t *status);
+	int32_t i2CTransaction(uint8_t port, uint8_t deviceAddress, uint8_t *dataToSend, uint8_t sendSize, uint8_t *dataReceived, uint8_t receiveSize);
+	int32_t i2CWrite(uint8_t port, uint8_t deviceAddress, uint8_t *dataToSend, uint8_t sendSize);
+	int32_t i2CRead(uint8_t port, uint8_t deviceAddress, uint8_t *buffer, uint8_t count);
+	void i2CClose(uint8_t port);
+
+	//// Float JNA Hack
+	// double
+	void setPWMRateIntHack(int rate, int32_t *status);
+	void setPWMDutyCycleIntHack(void* pwmGenerator, int32_t dutyCycle, int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Errors.hpp b/aos/externals/allwpilib/hal/include/HAL/Errors.hpp
new file mode 100644
index 0000000..35ed961
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Errors.hpp
@@ -0,0 +1,64 @@
+#pragma once
+
+#define CTR_RxTimeout_MESSAGE "CTRE CAN Recieve Timeout"
+#define CTR_TxTimeout_MESSAGE "CTRE CAN Transmit Timeout"
+#define CTR_InvalidParamValue_MESSAGE "CTRE CAN Invalid Parameter"
+#define CTR_UnexpectedArbId_MESSAGE "CTRE Unexpected Arbitration ID (CAN Node ID)"
+#define CTR_TxFailed_MESSAGE "CTRE CAN Transmit Error"
+#define CTR_SigNotUpdated_MESSAGE "CTRE CAN Signal Not Updated"
+
+#define NiFpga_Status_FifoTimeout_MESSAGE "NIFPGA: FIFO timeout error"
+#define NiFpga_Status_TransferAborted_MESSAGE "NIFPGA: Transfer aborted error"
+#define NiFpga_Status_MemoryFull_MESSAGE "NIFPGA: Memory Allocation failed, memory full"
+#define NiFpga_Status_SoftwareFault_MESSAGE "NIFPGA: Unexepected software error"
+#define NiFpga_Status_InvalidParameter_MESSAGE "NIFPGA: Invalid Parameter"
+#define NiFpga_Status_ResourceNotFound_MESSAGE "NIFPGA: Resource not found"
+#define NiFpga_Status_ResourceNotInitialized_MESSAGE "NIFPGA: Resource not initialized"
+#define NiFpga_Status_HardwareFault_MESSAGE "NIFPGA: Hardware Fault"
+#define NiFpga_Status_IrqTimeout_MESSAGE "NIFPGA: Interrupt timeout"
+
+#define ERR_CANSessionMux_InvalidBuffer_MESSAGE "CAN: Invalid Buffer"
+#define ERR_CANSessionMux_MessageNotFound_MESSAGE "CAN: Message not found"
+#define WARN_CANSessionMux_NoToken_MESSAGE "CAN: No token"
+#define ERR_CANSessionMux_NotAllowed_MESSAGE "CAN: Not allowed"
+#define ERR_CANSessionMux_NotInitialized_MESSAGE "CAN: Not initialized" 
+
+#define SAMPLE_RATE_TOO_HIGH 1001
+#define SAMPLE_RATE_TOO_HIGH_MESSAGE "HAL: Analog module sample rate is too high"
+#define VOLTAGE_OUT_OF_RANGE 1002
+#define VOLTAGE_OUT_OF_RANGE_MESSAGE "HAL: Voltage to convert to raw value is out of range [0; 5]"
+#define LOOP_TIMING_ERROR 1004
+#define LOOP_TIMING_ERROR_MESSAGE "HAL: Digital module loop timing is not the expected value"
+#define SPI_WRITE_NO_MOSI 1012
+#define SPI_WRITE_NO_MOSI_MESSAGE "HAL: Cannot write to SPI port with no MOSI output"
+#define SPI_READ_NO_MISO 1013
+#define SPI_READ_NO_MISO_MESSAGE "HAL: Cannot read from SPI port with no MISO input"
+#define SPI_READ_NO_DATA 1014
+#define SPI_READ_NO_DATA_MESSAGE "HAL: No data available to read from SPI"
+#define INCOMPATIBLE_STATE 1015
+#define INCOMPATIBLE_STATE_MESSAGE "HAL: Incompatible State: The operation cannot be completed"
+#define NO_AVAILABLE_RESOURCES -1004
+#define NO_AVAILABLE_RESOURCES_MESSAGE "HAL: No available resources to allocate"
+#define NULL_PARAMETER -1005
+#define NULL_PARAMETER_MESSAGE "HAL: A pointer parameter to a method is NULL"
+#define ANALOG_TRIGGER_LIMIT_ORDER_ERROR -1010
+#define ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE "HAL: AnalogTrigger limits error.  Lower limit > Upper Limit"
+#define ANALOG_TRIGGER_PULSE_OUTPUT_ERROR -1011
+#define ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE "HAL: Attempted to read AnalogTrigger pulse output."
+#define PARAMETER_OUT_OF_RANGE -1028
+#define PARAMETER_OUT_OF_RANGE_MESSAGE "HAL: A parameter is out of range."
+#define RESOURCE_IS_ALLOCATED -1029
+#define RESOURCE_IS_ALLOCATED_MESSAGE "HAL: Resource already allocated"
+
+#define VI_ERROR_SYSTEM_ERROR_MESSAGE "HAL - VISA: System Error";
+#define VI_ERROR_INV_OBJECT_MESSAGE "HAL - VISA: Invalid Object"
+#define VI_ERROR_RSRC_LOCKED_MESSAGE "HAL - VISA: Resource Locked"
+#define VI_ERROR_RSRC_NFOUND_MESSAGE "HAL - VISA: Resource Not Found"
+#define VI_ERROR_INV_RSRC_NAME_MESSAGE "HAL - VISA: Invalid Resource Name"  
+#define VI_ERROR_QUEUE_OVERFLOW_MESSAGE "HAL - VISA: Queue Overflow" 
+#define VI_ERROR_IO_MESSAGE "HAL - VISA: General IO Error"
+#define VI_ERROR_ASRL_PARITY_MESSAGE "HAL - VISA: Parity Error"
+#define VI_ERROR_ASRL_FRAMING_MESSAGE "HAL - VISA: Framing Error"
+#define VI_ERROR_ASRL_OVERRUN_MESSAGE "HAL - VISA: Buffer Overrun Error" 
+#define VI_ERROR_RSRC_BUSY_MESSAGE "HAL - VISA: Resource Busy"
+#define VI_ERROR_INV_PARAMETER_MESSAGE "HAL - VISA: Invalid Parameter" 
diff --git a/aos/externals/allwpilib/hal/include/HAL/HAL.hpp b/aos/externals/allwpilib/hal/include/HAL/HAL.hpp
new file mode 100644
index 0000000..9c6acb7
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/HAL.hpp
@@ -0,0 +1,257 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2013. 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
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+#include <cmath>
+
+#include "Accelerometer.hpp"
+#include "Analog.hpp"
+#include "Compressor.hpp"
+#include "Digital.hpp"
+#include "Solenoid.hpp"
+#include "Notifier.hpp"
+#include "Interrupts.hpp"
+#include "Errors.hpp"
+#include "PDP.hpp"
+#include "Power.hpp"
+
+#include "Utilities.hpp"
+#include "Semaphore.hpp"
+#include "Task.hpp"
+
+#define HAL_IO_CONFIG_DATA_SIZE 32
+#define HAL_SYS_STATUS_DATA_SIZE 44
+#define HAL_USER_STATUS_DATA_SIZE (984 - HAL_IO_CONFIG_DATA_SIZE - HAL_SYS_STATUS_DATA_SIZE)
+
+#define HALFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Input 17
+#define HALFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Output 18
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Header 19
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Extra1 20
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Vertices1 21
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Extra2 22
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Vertices2 23
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Joystick 24
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Custom 25
+
+namespace HALUsageReporting
+{
+	enum tResourceType
+	{
+		kResourceType_Controller,
+		kResourceType_Module,
+		kResourceType_Language,
+		kResourceType_CANPlugin,
+		kResourceType_Accelerometer,
+		kResourceType_ADXL345,
+		kResourceType_AnalogChannel,
+		kResourceType_AnalogTrigger,
+		kResourceType_AnalogTriggerOutput,
+		kResourceType_CANJaguar,
+		kResourceType_Compressor,
+		kResourceType_Counter,
+		kResourceType_Dashboard,
+		kResourceType_DigitalInput,
+		kResourceType_DigitalOutput,
+		kResourceType_DriverStationCIO,
+		kResourceType_DriverStationEIO,
+		kResourceType_DriverStationLCD,
+		kResourceType_Encoder,
+		kResourceType_GearTooth,
+		kResourceType_Gyro,
+		kResourceType_I2C,
+		kResourceType_Framework,
+		kResourceType_Jaguar,
+		kResourceType_Joystick,
+		kResourceType_Kinect,
+		kResourceType_KinectStick,
+		kResourceType_PIDController,
+		kResourceType_Preferences,
+		kResourceType_PWM,
+		kResourceType_Relay,
+		kResourceType_RobotDrive,
+		kResourceType_SerialPort,
+		kResourceType_Servo,
+		kResourceType_Solenoid,
+		kResourceType_SPI,
+		kResourceType_Task,
+		kResourceType_Ultrasonic,
+		kResourceType_Victor,
+		kResourceType_Button,
+		kResourceType_Command,
+		kResourceType_AxisCamera,
+		kResourceType_PCVideoServer,
+		kResourceType_SmartDashboard,
+		kResourceType_Talon,
+		kResourceType_HiTechnicColorSensor,
+		kResourceType_HiTechnicAccel,
+		kResourceType_HiTechnicCompass,
+		kResourceType_SRF08,
+		kResourceType_DigitalGlitchFilter,
+	};
+
+	enum tInstances
+	{
+		kLanguage_LabVIEW = 1,
+		kLanguage_CPlusPlus = 2,
+		kLanguage_Java = 3,
+		kLanguage_Python = 4,
+
+		kCANPlugin_BlackJagBridge = 1,
+		kCANPlugin_2CAN = 2,
+
+		kFramework_Iterative = 1,
+		kFramework_Simple = 2,
+
+		kRobotDrive_ArcadeStandard = 1,
+		kRobotDrive_ArcadeButtonSpin = 2,
+		kRobotDrive_ArcadeRatioCurve = 3,
+		kRobotDrive_Tank = 4,
+		kRobotDrive_MecanumPolar = 5,
+		kRobotDrive_MecanumCartesian = 6,
+
+		kDriverStationCIO_Analog = 1,
+		kDriverStationCIO_DigitalIn = 2,
+		kDriverStationCIO_DigitalOut = 3,
+
+		kDriverStationEIO_Acceleration = 1,
+		kDriverStationEIO_AnalogIn = 2,
+		kDriverStationEIO_AnalogOut = 3,
+		kDriverStationEIO_Button = 4,
+		kDriverStationEIO_LED = 5,
+		kDriverStationEIO_DigitalIn = 6,
+		kDriverStationEIO_DigitalOut = 7,
+		kDriverStationEIO_FixedDigitalOut = 8,
+		kDriverStationEIO_PWM = 9,
+		kDriverStationEIO_Encoder = 10,
+		kDriverStationEIO_TouchSlider = 11,
+
+		kADXL345_SPI = 1,
+		kADXL345_I2C = 2,
+
+		kCommand_Scheduler = 1,
+
+		kSmartDashboard_Instance = 1,
+	};
+}
+
+struct HALControlWord {
+	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;
+};
+
+enum HALAllianceStationID {
+	kHALAllianceStationID_red1,
+	kHALAllianceStationID_red2,
+	kHALAllianceStationID_red3,
+	kHALAllianceStationID_blue1,
+	kHALAllianceStationID_blue2,
+	kHALAllianceStationID_blue3,
+};
+
+/* The maximum number of axes that will be stored in a single HALJoystickAxes
+	struct. This is used for allocating buffers, not bounds checking, since
+	there are usually less axes in practice. */
+static constexpr size_t kMaxJoystickAxes = 12;
+static constexpr size_t kMaxJoystickPOVs = 12;
+
+struct HALJoystickAxes {
+	uint16_t count;
+	int16_t axes[kMaxJoystickAxes];
+};
+
+struct HALJoystickPOVs {
+	uint16_t count;
+	int16_t povs[kMaxJoystickPOVs];
+};
+
+struct HALJoystickButtons {
+	uint32_t buttons;
+	uint8_t count;
+};
+
+struct HALJoystickDescriptor {
+	uint8_t isXbox;
+	uint8_t type;
+	char name[256];
+	uint8_t axisCount;
+	uint8_t axisTypes;
+	uint8_t buttonCount;
+	uint8_t povCount;
+};
+
+inline float intToFloat(int value)
+{
+	return (float)value;
+}
+
+inline int floatToInt(float value)
+{
+	return round(value);
+}
+
+extern "C"
+{
+	extern const uint32_t dio_kNumSystems;
+	extern const uint32_t solenoid_kNumDO7_0Elements;
+	extern const uint32_t interrupt_kNumSystems;
+	extern const uint32_t kSystemClockTicksPerMicrosecond;
+
+	void* getPort(uint8_t pin);
+	void* getPortWithModule(uint8_t module, uint8_t pin);
+	const char* getHALErrorMessage(int32_t code);
+
+	uint16_t getFPGAVersion(int32_t *status);
+	uint32_t getFPGARevision(int32_t *status);
+	uint32_t getFPGATime(int32_t *status);
+
+	bool getFPGAButton(int32_t *status);
+
+	int HALSetErrorData(const char *errors, int errorsLength, int wait_ms);
+
+	int HALGetControlWord(HALControlWord *data);
+	int HALGetAllianceStation(enum HALAllianceStationID *allianceStation);
+	int HALGetJoystickAxes(uint8_t joystickNum, HALJoystickAxes *axes);
+	int HALGetJoystickPOVs(uint8_t joystickNum, HALJoystickPOVs *povs);
+	int HALGetJoystickButtons(uint8_t joystickNum, HALJoystickButtons *buttons);
+	int HALGetJoystickDescriptor(uint8_t joystickNum, HALJoystickDescriptor *desc);
+	int HALSetJoystickOutputs(uint8_t joystickNum, uint32_t outputs, uint16_t leftRumble, uint16_t rightRumble);
+	int HALGetMatchTime(float *matchTime);
+
+	void HALSetNewDataSem(MULTIWAIT_ID sem);
+	
+	bool HALGetSystemActive(int32_t *status);
+	bool HALGetBrownedOut(int32_t *status);
+
+	int HALInitialize(int mode = 0);
+	void HALNetworkCommunicationObserveUserProgramStarting();
+	void HALNetworkCommunicationObserveUserProgramDisabled();
+	void HALNetworkCommunicationObserveUserProgramAutonomous();
+	void HALNetworkCommunicationObserveUserProgramTeleop();
+	void HALNetworkCommunicationObserveUserProgramTest();
+
+	uint32_t HALReport(uint8_t resource, uint8_t instanceNumber, uint8_t context = 0,
+			const char *feature = NULL);
+}
+
+// TODO: HACKS for now...
+extern "C"
+{
+
+	void NumericArrayResize();
+	void RTSetCleanupProc();
+	void EDVR_CreateReference();
+	void Occur();
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Interrupts.hpp b/aos/externals/allwpilib/hal/include/HAL/Interrupts.hpp
new file mode 100644
index 0000000..636e809
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Interrupts.hpp
@@ -0,0 +1,30 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+#include <iostream>
+#include "errno.h"
+
+extern "C"
+{
+	typedef void (*InterruptHandlerFunction)(uint32_t interruptAssertedMask, void *param);
+
+	void* initializeInterrupts(uint32_t interruptIndex, bool watcher, int32_t *status);
+	void cleanInterrupts(void* interrupt_pointer, int32_t *status);
+
+	uint32_t waitForInterrupt(void* interrupt_pointer, double timeout, bool ignorePrevious, int32_t *status);
+	void enableInterrupts(void* interrupt_pointer, int32_t *status);
+	void disableInterrupts(void* interrupt_pointer, int32_t *status);
+	double readRisingTimestamp(void* interrupt_pointer, int32_t *status);
+	double readFallingTimestamp(void* interrupt_pointer, int32_t *status);
+	void requestInterrupts(void* interrupt_pointer, uint8_t routing_module, uint32_t routing_pin,
+			bool routing_analog_trigger, int32_t *status);
+	void attachInterruptHandler(void* interrupt_pointer, InterruptHandlerFunction handler,
+			void* param, int32_t *status);
+	void setInterruptUpSourceEdge(void* interrupt_pointer, bool risingEdge, bool fallingEdge,
+			int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Notifier.hpp b/aos/externals/allwpilib/hal/include/HAL/Notifier.hpp
new file mode 100644
index 0000000..987686c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Notifier.hpp
@@ -0,0 +1,15 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+extern "C"
+{
+	void* initializeNotifier(void (*ProcessQueue)(uint32_t, void*), int32_t *status);
+	void cleanNotifier(void* notifier_pointer, int32_t *status);
+
+	void updateNotifierAlarm(void* notifier_pointer, uint32_t triggerTime, int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/PDP.hpp b/aos/externals/allwpilib/hal/include/HAL/PDP.hpp
new file mode 100644
index 0000000..3dde22b
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/PDP.hpp
@@ -0,0 +1,19 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+extern "C"
+{
+	double getPDPTemperature(int32_t *status);
+	double getPDPVoltage(int32_t *status);
+	double getPDPChannelCurrent(uint8_t channel, int32_t *status);
+	double getPDPTotalCurrent(int32_t *status);
+	double getPDPTotalPower(int32_t *status);
+	double getPDPTotalEnergy(int32_t *status);
+	void resetPDPTotalEnergy(int32_t *status);
+	void clearPDPStickyFaults(int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Power.hpp b/aos/externals/allwpilib/hal/include/HAL/Power.hpp
new file mode 100644
index 0000000..b430c1e
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Power.hpp
@@ -0,0 +1,21 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+	float getVinVoltage(int32_t *status);
+	float getVinCurrent(int32_t *status);
+	float getUserVoltage6V(int32_t *status);
+	float getUserCurrent6V(int32_t *status);
+	bool getUserActive6V(int32_t *status);
+	int getUserCurrentFaults6V(int32_t *status);
+	float getUserVoltage5V(int32_t *status);
+	float getUserCurrent5V(int32_t *status);
+	bool getUserActive5V(int32_t *status);
+	int getUserCurrentFaults5V(int32_t *status);
+	float getUserVoltage3V3(int32_t *status);
+	float getUserCurrent3V3(int32_t *status);
+	bool getUserActive3V3(int32_t *status);
+	int getUserCurrentFaults3V3(int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Semaphore.hpp b/aos/externals/allwpilib/hal/include/HAL/Semaphore.hpp
new file mode 100644
index 0000000..e02011f
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Semaphore.hpp
@@ -0,0 +1,53 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#include <pthread.h>
+#include <semaphore.h>
+#endif
+
+#ifdef __vxworks
+typedef SEM_ID MUTEX_ID;
+typedef SEM_ID SEMAPHORE_ID;
+typedef SEM_ID MULTIWAIT_ID;
+#else
+class MutexInterface;
+typedef MutexInterface* MUTEX_ID;
+typedef sem_t* SEMAPHORE_ID;
+typedef pthread_cond_t* MULTIWAIT_ID;
+#endif
+
+extern "C"
+{
+	extern const uint32_t SEMAPHORE_Q_FIFO;
+	extern const uint32_t SEMAPHORE_Q_PRIORITY;
+	extern const uint32_t SEMAPHORE_DELETE_SAFE;
+	extern const uint32_t SEMAPHORE_INVERSION_SAFE;
+
+	extern const int32_t SEMAPHORE_NO_WAIT;
+	extern const int32_t SEMAPHORE_WAIT_FOREVER;
+
+	extern const uint32_t SEMAPHORE_EMPTY;
+	extern const uint32_t SEMAPHORE_FULL;
+
+	MUTEX_ID initializeMutexRecursive();
+	MUTEX_ID initializeMutexNormal();
+	void deleteMutex(MUTEX_ID sem);
+	int8_t lockMutex(MUTEX_ID sem);
+	int8_t tryLockMutex(MUTEX_ID sem);
+	int8_t unlockMutex(MUTEX_ID sem);
+
+	SEMAPHORE_ID initializeSemaphore(uint32_t initial_value);
+	void deleteSemaphore(SEMAPHORE_ID sem);
+	int8_t takeSemaphore(SEMAPHORE_ID sem);
+	int8_t tryTakeSemaphore(SEMAPHORE_ID sem);
+	int8_t giveSemaphore(SEMAPHORE_ID sem);
+
+	MULTIWAIT_ID initializeMultiWait();
+	void deleteMultiWait(MULTIWAIT_ID sem);
+	int8_t takeMultiWait(MULTIWAIT_ID sem, MUTEX_ID m, int32_t timeout);
+	int8_t giveMultiWait(MULTIWAIT_ID sem);
+}
+
diff --git a/aos/externals/allwpilib/hal/include/HAL/Solenoid.hpp b/aos/externals/allwpilib/hal/include/HAL/Solenoid.hpp
new file mode 100644
index 0000000..1654dc2
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Solenoid.hpp
@@ -0,0 +1,22 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+extern "C"
+{
+	void* initializeSolenoidPort(void* port_pointer, int32_t *status);
+	bool checkSolenoidModule(uint8_t module);
+
+	bool getSolenoid(void* solenoid_port_pointer, int32_t *status);
+	void setSolenoid(void* solenoid_port_pointer, bool value, int32_t *status);
+	void setSolenoids(void* solenoid_port_pointer, uint8_t value, uint8_t mask, int32_t *status);
+
+	int getPCMSolenoidBlackList(void* solenoid_port_pointer, int32_t *status);
+	bool getPCMSolenoidVoltageStickyFault(void* solenoid_port_pointer, int32_t *status);
+	bool getPCMSolenoidVoltageFault(void* solenoid_port_pointer, int32_t *status);
+	void clearAllPCMStickyFaults_sol(void *solenoid_port_pointer, int32_t *status);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/Task.hpp b/aos/externals/allwpilib/hal/include/HAL/Task.hpp
new file mode 100644
index 0000000..ec3ed9b
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Task.hpp
@@ -0,0 +1,55 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#include <pthread.h>
+#endif
+
+#ifndef _FUNCPTR_DEFINED
+#define _FUNCPTR_DEFINED
+#ifdef __cplusplus
+typedef int (*FUNCPTR)(...);
+/* ptr to function returning int */
+#else
+typedef int (*FUNCPTR) (); /* ptr to function returning int */
+#endif /* __cplusplus */
+#endif /* _FUNCPTR_DEFINED */
+
+#ifndef _STATUS_DEFINED
+#define _STATUS_DEFINED
+typedef int STATUS;
+#endif /* _STATUS_DEFINED */
+
+#ifdef __vxworks
+#define NULL_TASK -1
+typedef int32_t TASK;
+#else
+#define NULL_TASK NULL
+typedef pthread_t* TASK;
+#endif
+
+extern "C"
+{
+	extern const uint32_t VXWORKS_FP_TASK;
+	extern const int32_t HAL_objLib_OBJ_ID_ERROR;
+	extern const int32_t HAL_objLib_OBJ_DELETED;
+	extern const int32_t HAL_taskLib_ILLEGAL_OPTIONS;
+	extern const int32_t HAL_memLib_NOT_ENOUGH_MEMORY;
+	extern const int32_t HAL_taskLib_ILLEGAL_PRIORITY;
+
+	TASK spawnTask(char * name, int priority, int options, int stackSize, FUNCPTR entryPt,
+			uint32_t arg0, uint32_t arg1, uint32_t arg2, uint32_t arg3, uint32_t arg4,
+			uint32_t arg5, uint32_t arg6, uint32_t arg7, uint32_t arg8, uint32_t arg9);
+	STATUS restartTask(TASK task);
+	STATUS deleteTask(TASK task);
+	STATUS isTaskReady(TASK task);
+	STATUS isTaskSuspended(TASK task);
+	STATUS suspendTask(TASK task);
+	STATUS resumeTask(TASK task);
+	STATUS verifyTaskID(TASK task);
+	STATUS setTaskPriority(TASK task, int priority);
+	STATUS getTaskPriority(TASK task, int* priority);
+}
+
diff --git a/aos/externals/allwpilib/hal/include/HAL/Utilities.hpp b/aos/externals/allwpilib/hal/include/HAL/Utilities.hpp
new file mode 100644
index 0000000..b24cd29
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/Utilities.hpp
@@ -0,0 +1,17 @@
+#pragma once
+
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+extern "C"
+{
+	extern const int32_t HAL_NO_WAIT;
+	extern const int32_t HAL_WAIT_FOREVER;
+
+	void delayTicks(int32_t ticks);
+	void delayMillis(double ms);
+	void delaySeconds(double s);
+}
diff --git a/aos/externals/allwpilib/hal/include/HAL/cpp/Resource.hpp b/aos/externals/allwpilib/hal/include/HAL/cpp/Resource.hpp
new file mode 100644
index 0000000..931407f
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/cpp/Resource.hpp
@@ -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 "../Errors.hpp"
+#include "Synchronized.hpp"
+#ifdef __vxworks
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+/**
+ * The Resource class is a convenient way to track allocated resources.
+ * It tracks them as indicies in the range [0 .. elements - 1].
+ * E.g. the library uses this to track hardware channel allocation.
+ *
+ * The Resource class does not allocate the hardware channels or other
+ * resources; it just tracks which indices were marked in use by
+ * Allocate and not yet freed by Free.
+ */
+class Resource
+{
+public:
+	virtual ~Resource();
+	static void CreateResourceObject(Resource **r, uint32_t elements);
+	uint32_t Allocate(const char *resourceDesc);
+	uint32_t Allocate(uint32_t index, const char *resourceDesc);
+	void Free(uint32_t index);
+
+private:
+	explicit Resource(uint32_t size);
+
+	bool *m_isAllocated;
+	ReentrantMutex m_allocateLock;
+	uint32_t m_size;
+
+	static ReentrantMutex m_createLock;
+
+	DISALLOW_COPY_AND_ASSIGN(Resource);
+};
+
diff --git a/aos/externals/allwpilib/hal/include/HAL/cpp/Synchronized.hpp b/aos/externals/allwpilib/hal/include/HAL/cpp/Synchronized.hpp
new file mode 100644
index 0000000..af8b149
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/HAL/cpp/Synchronized.hpp
@@ -0,0 +1,144 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <mutex>
+#include "HAL/Semaphore.hpp"
+
+// A macro to disallow the copy constructor and operator= functions
+// This should be used in the private: declarations for a class
+#define DISALLOW_COPY_AND_ASSIGN(TypeName) \
+  TypeName(const TypeName&) = delete;      \
+  void operator=(const TypeName&) = delete
+
+class Synchronized;
+
+/**
+ * Wrap a pthead mutex for easier use in C++. For a static
+ * instance, the constructor runs at program load time before main() can spawn
+ * any tasks. Use that to fix race conditions in setup code.
+ *
+ * This uses a pthread mutex which has PTHREAD_MUTEX_RECURSIVE set, making it
+ * "reentrant" in the sense that the owning task can lock it more than once. The
+ * task will need to unlock the mutex the same number of times to make it
+ * available for other threads to acquire.
+ *
+ * This class is safe to use in static variables because it does not depend on
+ * any other C++ static constructors or destructors.
+ */
+class ReentrantMutex {
+ public:
+  typedef pthread_mutex_t *native_handle_type;
+
+  constexpr ReentrantMutex() noexcept = default;
+  ReentrantMutex(const ReentrantMutex &) = delete;
+  ReentrantMutex &operator=(const ReentrantMutex &) = delete;
+
+  /**
+   * Lock the mutex, blocking until it's available.
+   */
+  void lock() { pthread_mutex_lock(&mutex_); }
+
+  /**
+   * Unlock the mutex.
+   */
+  void unlock() { pthread_mutex_unlock(&mutex_); }
+
+  /**
+   * Tries to lock the mutex.
+   */
+  bool try_lock() noexcept { return !pthread_mutex_trylock(&mutex_); }
+
+  pthread_mutex_t *native_handle() { return &mutex_; }
+
+ private:
+  // Do the equivalent of setting PTHREAD_PRIO_INHERIT and
+  // PTHREAD_MUTEX_RECURSIVE_NP.
+#if __WORDSIZE == 64
+  #error "Should work, but need to run test case to verify"
+  pthread_mutex_t mutex_ = {
+      {0, 0, 0, 0, 0x20 | PTHREAD_MUTEX_RECURSIVE_NP, 0, {0, 0}}};
+#else
+  pthread_mutex_t mutex_ = {
+      {0, 0, 0, 0x20 | PTHREAD_MUTEX_RECURSIVE_NP, 0, {0}}};
+#endif
+};
+
+/**
+ * Wrap a pthead mutex for easier use in C++. For a static
+ * instance, the constructor runs at program load time before main() can spawn
+ * any tasks. Use that to fix race conditions in setup code.
+ *
+ * This class is safe to use in static variables because it does not depend on
+ * any other C++ static constructors or destructors.
+ */
+class Mutex {
+ public:
+  typedef pthread_mutex_t *native_handle_type;
+
+  constexpr Mutex() noexcept = default;
+  Mutex(const Mutex &) = delete;
+  Mutex &operator=(const Mutex &) = delete;
+
+  /**
+   * Lock the mutex, blocking until it's available.
+   */
+  void lock() { pthread_mutex_lock(&mutex_); }
+
+  /**
+   * Unlock the mutex.
+   */
+  void unlock() { pthread_mutex_unlock(&mutex_); }
+
+  /**
+   * Tries to lock the mutex.
+   */
+  bool try_lock() noexcept { return !pthread_mutex_trylock(&mutex_); }
+
+  native_handle_type native_handle() { return &mutex_; }
+
+ private:
+  // Do the equivalent of setting PTHREAD_PRIO_INHERIT.
+#if __WORDSIZE == 64
+  #error "Should work, but need to run test case to verify"
+  pthread_mutex_t mutex_ = { { 0, 0, 0, 0, 0x20, 0, { 0, 0 } } };
+#else
+  pthread_mutex_t mutex_ = { { 0, 0, 0, 0x20, 0, { 0 } } };
+#endif
+};
+
+
+/**
+ * Provide easy support for critical regions.
+ *
+ * A critical region is an area of code that is always executed under mutual exclusion. Only
+ * one task can be executing this code at any time. The idea is that code that manipulates data
+ * that is shared between two or more tasks has to be prevented from executing at the same time
+ * otherwise a race condition is possible when both tasks try to update the data. Typically
+ * semaphores are used to ensure only single task access to the data.
+ *
+ * Synchronized objects are a simple wrapper around semaphores to help ensure
+ * that semaphores are always unlocked (semGive) after locking (semTake).
+ *
+ * You allocate a Synchronized as a local variable, *not* on the heap. That
+ * makes it a "stack object" whose destructor runs automatically when it goes
+ * out of scope. E.g.
+ *
+ *   { Synchronized _sync(aReentrantSemaphore); ... critical region ... }
+ */
+class Synchronized
+{
+public:
+#ifndef __vxworks
+	explicit Synchronized(SEMAPHORE_ID);
+#endif
+	virtual ~Synchronized();
+private:
+	SEMAPHORE_ID m_semaphore;
+
+	DISALLOW_COPY_AND_ASSIGN(Synchronized);
+};
+
diff --git a/aos/externals/allwpilib/hal/include/Log.hpp b/aos/externals/allwpilib/hal/include/Log.hpp
new file mode 100644
index 0000000..eb221e7
--- /dev/null
+++ b/aos/externals/allwpilib/hal/include/Log.hpp
@@ -0,0 +1,103 @@
+#pragma once
+
+#include <sstream>
+#include <iomanip>
+#include <string>
+#include <stdio.h>
+#include <sys/time.h>
+
+inline std::string NowTime();
+
+enum TLogLevel {logNONE, logERROR, logWARNING, logINFO, logDEBUG, logDEBUG1, logDEBUG2, logDEBUG3, logDEBUG4};
+
+class Log
+{
+public:
+    Log();
+    virtual ~Log();
+    std::ostringstream& Get(TLogLevel level = logINFO);
+public:
+    static TLogLevel& ReportingLevel();
+    static std::string ToString(TLogLevel level);
+    static TLogLevel FromString(const std::string& level);
+protected:
+    std::ostringstream os;
+private:
+    Log(const Log&);
+    Log& operator =(const Log&);
+};
+
+inline Log::Log()
+{
+}
+
+inline std::ostringstream& Log::Get(TLogLevel level)
+{
+    os << "- " << NowTime();
+    os << " " << ToString(level) << ": ";
+    os << std::string(level > logDEBUG ? level - logDEBUG : 0, '\t');
+    return os;
+}
+
+inline Log::~Log()
+{
+    os << std::endl;
+    fprintf(stderr, "%s", os.str().c_str());
+    fflush(stderr);
+}
+
+inline TLogLevel& Log::ReportingLevel()
+{
+    static TLogLevel reportingLevel = logDEBUG4;
+    return reportingLevel;
+}
+
+inline std::string Log::ToString(TLogLevel level)
+{
+	static const char* const buffer[] = {"NONE", "ERROR", "WARNING", "INFO", "DEBUG", "DEBUG1", "DEBUG2", "DEBUG3", "DEBUG4"};
+    return buffer[level];
+}
+
+inline TLogLevel Log::FromString(const std::string& level)
+{
+    if (level == "DEBUG4")
+        return logDEBUG4;
+    if (level == "DEBUG3")
+        return logDEBUG3;
+    if (level == "DEBUG2")
+        return logDEBUG2;
+    if (level == "DEBUG1")
+        return logDEBUG1;
+    if (level == "DEBUG")
+        return logDEBUG;
+    if (level == "INFO")
+        return logINFO;
+    if (level == "WARNING")
+        return logWARNING;
+    if (level == "ERROR")
+        return logERROR;
+    if (level == "NONE")
+    	return logNONE;
+    Log().Get(logWARNING) << "Unknown logging level '" << level << "'. Using INFO level as default.";
+    return logINFO;
+}
+
+typedef Log FILELog;
+
+#define FILE_LOG(level) \
+    if (level > FILELog::ReportingLevel()) ; \
+    else Log().Get(level)
+
+inline std::string NowTime()
+{
+    char buffer[11];
+    time_t t;
+    time(&t);
+    tm * r = gmtime(&t);
+    strftime(buffer, sizeof(buffer), "%H:%M:%S", r);
+    struct timeval tv;
+    gettimeofday(&tv, 0);
+    char result[100] = {0};
+    sprintf(result, "%s.%03ld", buffer, (long)tv.tv_usec / 1000);
+    return result;
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Accelerometer.cpp b/aos/externals/allwpilib/hal/lib/Athena/Accelerometer.cpp
new file mode 100644
index 0000000..0895c9c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Accelerometer.cpp
@@ -0,0 +1,234 @@
+#include "HAL/Accelerometer.hpp"
+
+#include "ChipObject.h"
+#include <stdint.h>
+#include <stdio.h>
+#include <assert.h>
+
+// The 7-bit I2C address with a 0 "send" bit
+static const uint8_t kSendAddress = (0x1c << 1) | 0;
+
+// The 7-bit I2C address with a 1 "receive" bit
+static const uint8_t kReceiveAddress = (0x1c << 1) | 1;
+
+static const uint8_t kControlTxRx = 1;
+static const uint8_t kControlStart = 2;
+static const uint8_t kControlStop = 4;
+
+static tAccel *accel = 0;
+static AccelerometerRange accelerometerRange;
+
+// Register addresses
+enum Register {
+	kReg_Status = 0x00,
+	kReg_OutXMSB = 0x01,
+	kReg_OutXLSB = 0x02,
+	kReg_OutYMSB = 0x03,
+	kReg_OutYLSB = 0x04,
+	kReg_OutZMSB = 0x05,
+	kReg_OutZLSB = 0x06,
+	kReg_Sysmod = 0x0B,
+	kReg_IntSource = 0x0C,
+	kReg_WhoAmI = 0x0D,
+	kReg_XYZDataCfg = 0x0E,
+	kReg_HPFilterCutoff = 0x0F,
+	kReg_PLStatus = 0x10,
+	kReg_PLCfg = 0x11,
+	kReg_PLCount = 0x12,
+	kReg_PLBfZcomp = 0x13,
+	kReg_PLThsReg = 0x14,
+	kReg_FFMtCfg = 0x15,
+	kReg_FFMtSrc = 0x16,
+	kReg_FFMtThs = 0x17,
+	kReg_FFMtCount = 0x18,
+	kReg_TransientCfg = 0x1D,
+	kReg_TransientSrc = 0x1E,
+	kReg_TransientThs = 0x1F,
+	kReg_TransientCount = 0x20,
+	kReg_PulseCfg = 0x21,
+	kReg_PulseSrc = 0x22,
+	kReg_PulseThsx = 0x23,
+	kReg_PulseThsy = 0x24,
+	kReg_PulseThsz = 0x25,
+	kReg_PulseTmlt = 0x26,
+	kReg_PulseLtcy = 0x27,
+	kReg_PulseWind = 0x28,
+	kReg_ASlpCount = 0x29,
+	kReg_CtrlReg1 = 0x2A,
+	kReg_CtrlReg2 = 0x2B,
+	kReg_CtrlReg3 = 0x2C,
+	kReg_CtrlReg4 = 0x2D,
+	kReg_CtrlReg5 = 0x2E,
+	kReg_OffX = 0x2F,
+	kReg_OffY = 0x30,
+	kReg_OffZ = 0x31
+};
+
+extern "C" uint32_t getFPGATime(int32_t *status);
+
+static void writeRegister(Register reg, uint8_t data);
+static uint8_t readRegister(Register reg);
+
+/**
+ * Initialize the accelerometer.
+ */
+static void initializeAccelerometer() {
+	int32_t status;
+
+	if(!accel) {
+		accel = tAccel::create(&status);
+
+		// Enable I2C
+		accel->writeCNFG(1, &status);
+
+		// Set the counter to 100 kbps
+		accel->writeCNTR(213, &status);
+
+		// The device identification number should be 0x2a
+		assert(readRegister(kReg_WhoAmI) == 0x2a);
+	}
+}
+
+static void writeRegister(Register reg, uint8_t data) {
+	int32_t status = 0;
+	uint32_t initialTime;
+
+	accel->writeADDR(kSendAddress, &status);
+
+	// Send a start transmit/receive message with the register address
+	accel->writeCNTL(kControlStart | kControlTxRx, &status);
+	accel->writeDATO(reg, &status);
+	accel->strobeGO(&status);
+
+	// Execute and wait until it's done (up to a millisecond)
+	initialTime = getFPGATime(&status);
+	while(accel->readSTAT(&status) & 1) {
+		if(getFPGATime(&status) > initialTime + 1000) break;
+	}
+
+	// Send a stop transmit/receive message with the data
+	accel->writeCNTL(kControlStop | kControlTxRx, &status);
+	accel->writeDATO(data, &status);
+	accel->strobeGO(&status);
+
+	// Execute and wait until it's done (up to a millisecond)
+	initialTime = getFPGATime(&status);
+	while(accel->readSTAT(&status) & 1) {
+		if(getFPGATime(&status) > initialTime + 1000) break;
+	}
+
+	fflush(stdout);
+}
+
+static uint8_t readRegister(Register reg) {
+	int32_t status = 0;
+	uint32_t initialTime;
+
+	// Send a start transmit/receive message with the register address
+	accel->writeADDR(kSendAddress, &status);
+	accel->writeCNTL(kControlStart | kControlTxRx, &status);
+	accel->writeDATO(reg, &status);
+	accel->strobeGO(&status);
+
+	// Execute and wait until it's done (up to a millisecond)
+	initialTime = getFPGATime(&status);
+	while(accel->readSTAT(&status) & 1) {
+		if(getFPGATime(&status) > initialTime + 1000) break;
+	}
+
+	// Receive a message with the data and stop
+	accel->writeADDR(kReceiveAddress, &status);
+	accel->writeCNTL(kControlStart | kControlStop | kControlTxRx, &status);
+	accel->strobeGO(&status);
+
+	// Execute and wait until it's done (up to a millisecond)
+	initialTime = getFPGATime(&status);
+	while(accel->readSTAT(&status) & 1) {
+		if(getFPGATime(&status) > initialTime + 1000) break;
+	}
+
+	fflush(stdout);
+
+	return accel->readDATI(&status);
+}
+
+/**
+ * Convert a 12-bit raw acceleration value into a scaled double in units of
+ * 1 g-force, taking into account the accelerometer range.
+ */
+static double unpackAxis(int16_t raw) {
+	// The raw value is actually 12 bits, not 16, so we need to propogate the
+	// 2's complement sign bit to the unused 4 bits for this to work with
+	// negative numbers.
+	raw <<= 4;
+	raw >>= 4;
+
+	switch(accelerometerRange) {
+	case kRange_2G: return raw / 1024.0;
+	case kRange_4G: return raw / 512.0;
+	case kRange_8G: return raw / 256.0;
+	default: return 0.0;
+	}
+}
+
+/**
+ * Set the accelerometer to active or standby mode.  It must be in standby
+ * mode to change any configuration.
+ */
+void setAccelerometerActive(bool active) {
+	initializeAccelerometer();
+
+	uint8_t ctrlReg1 = readRegister(kReg_CtrlReg1);
+	ctrlReg1 &= ~1; // Clear the existing active bit
+	writeRegister(kReg_CtrlReg1, ctrlReg1 | (active? 1 : 0));
+}
+
+/**
+ * Set the range of values that can be measured (either 2, 4, or 8 g-forces).
+ * The accelerometer should be in standby mode when this is called.
+ */
+void setAccelerometerRange(AccelerometerRange range) {
+	initializeAccelerometer();
+
+	accelerometerRange = range;
+
+	uint8_t xyzDataCfg = readRegister(kReg_XYZDataCfg);
+	xyzDataCfg &= ~3; // Clear the existing two range bits
+	writeRegister(kReg_XYZDataCfg, xyzDataCfg | range);
+}
+
+/**
+ * Get the x-axis acceleration
+ *
+ * This is a floating point value in units of 1 g-force
+ */
+double getAccelerometerX() {
+	initializeAccelerometer();
+
+	int raw = (readRegister(kReg_OutXMSB) << 4) | (readRegister(kReg_OutXLSB) >> 4);
+	return unpackAxis(raw);
+}
+
+/**
+ * Get the y-axis acceleration
+ *
+ * This is a floating point value in units of 1 g-force
+ */
+double getAccelerometerY() {
+	initializeAccelerometer();
+
+	int raw = (readRegister(kReg_OutYMSB) << 4) | (readRegister(kReg_OutYLSB) >> 4);
+	return unpackAxis(raw);
+}
+
+/**
+ * Get the z-axis acceleration
+ *
+ * This is a floating point value in units of 1 g-force
+ */
+double getAccelerometerZ() {
+	initializeAccelerometer();
+
+	int raw = (readRegister(kReg_OutZMSB) << 4) | (readRegister(kReg_OutZLSB) >> 4);
+	return unpackAxis(raw);
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Analog.cpp b/aos/externals/allwpilib/hal/lib/Athena/Analog.cpp
new file mode 100644
index 0000000..bba7043
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Analog.cpp
@@ -0,0 +1,725 @@
+
+#include "HAL/Analog.hpp"
+
+#include "Port.h"
+#include "HAL/HAL.hpp"
+#include "ChipObject.h"
+#include "HAL/cpp/Synchronized.hpp"
+#include "HAL/cpp/Resource.hpp"
+#include "NetworkCommunication/AICalibration.h"
+#include "NetworkCommunication/LoadOut.h"
+
+static const long kTimebase = 40000000; ///< 40 MHz clock
+static const long kDefaultOversampleBits = 0;
+static const long kDefaultAverageBits = 7;
+static const float kDefaultSampleRate = 50000.0;
+static const uint32_t kAnalogInputPins = 8;
+static const uint32_t kAnalogOutputPins = 2;
+
+static const uint32_t kAccumulatorNumChannels = 2;
+static const uint32_t kAccumulatorChannels[] = {0, 1};
+
+struct AnalogPort {
+  Port port;
+  tAccumulator *accumulator;
+};
+
+bool analogSampleRateSet = false;
+ReentrantMutex analogRegisterWindowMutex;
+tAI* analogInputSystem = NULL;
+tAO* analogOutputSystem = NULL;
+uint32_t analogNumChannelsToActivate = 0;
+
+// Utility methods defined below.
+uint32_t getAnalogNumActiveChannels(int32_t *status);
+uint32_t getAnalogNumChannelsToActivate(int32_t *status);
+void setAnalogNumChannelsToActivate(uint32_t channels);
+
+bool analogSystemInitialized = false;
+
+/**
+ * Initialize the analog System.
+ */
+void initializeAnalog(int32_t *status) {
+  ::std::unique_lock<ReentrantMutex> sync(analogRegisterWindowMutex);
+  if (analogSystemInitialized) return;
+  analogInputSystem = tAI::create(status);
+  analogOutputSystem = tAO::create(status);
+  setAnalogNumChannelsToActivate(kAnalogInputPins);
+  setAnalogSampleRate(kDefaultSampleRate, status);
+  analogSystemInitialized = true;
+}
+
+/**
+ * Initialize the analog input port using the given port object.
+ */
+void* initializeAnalogInputPort(void* port_pointer, int32_t *status) {
+  initializeAnalog(status);
+  Port* port = (Port*) port_pointer;
+
+  // Initialize port structure
+  AnalogPort* analog_port = new AnalogPort();
+  analog_port->port = *port;
+  if (isAccumulatorChannel(analog_port, status)) {
+    analog_port->accumulator = tAccumulator::create(port->pin, status);
+  } else analog_port->accumulator = NULL;
+
+  // Set default configuration
+  analogInputSystem->writeScanList(port->pin, port->pin, status);
+  setAnalogAverageBits(analog_port, kDefaultAverageBits, status);
+  setAnalogOversampleBits(analog_port, kDefaultOversampleBits, status);
+  return analog_port;
+}
+
+/**
+ * Initialize the analog output port using the given port object.
+ */
+void* initializeAnalogOutputPort(void* port_pointer, int32_t *status) {
+  initializeAnalog(status);
+  Port* port = (Port*) port_pointer;
+
+  // Initialize port structure
+  AnalogPort* analog_port = new AnalogPort();
+  analog_port->port = *port;
+  return analog_port;
+}
+
+
+/**
+ * Check that the analog module number is valid.
+ *
+ * @return Analog module is valid and present
+ */
+bool checkAnalogModule(uint8_t module) {
+  return module == 1;
+}
+
+/**
+ * Check that the analog output channel number is value.
+ * Verify that the analog channel number is one of the legal channel numbers. Channel numbers
+ * are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool checkAnalogInputChannel(uint32_t pin) {
+  if (pin < kAnalogInputPins)
+    return true;
+  return false;
+}
+
+/**
+ * Check that the analog output channel number is value.
+ * Verify that the analog channel number is one of the legal channel numbers. Channel numbers
+ * are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool checkAnalogOutputChannel(uint32_t pin) {
+  if (pin < kAnalogOutputPins)
+    return true;
+  return false;
+}
+
+void setAnalogOutput(void* analog_port_pointer, double voltage, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+
+  uint16_t rawValue = (uint16_t)(voltage / 5.0 * 0x1000);
+
+  if(voltage < 0.0) rawValue = 0;
+  else if(voltage > 5.0) rawValue = 0x1000;
+
+  analogOutputSystem->writeMXP(port->port.pin, rawValue, status);
+}
+
+double getAnalogOutput(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+
+  uint16_t rawValue = analogOutputSystem->readMXP(port->port.pin, status);
+
+  return rawValue * 5.0 / 0x1000;
+}
+
+/**
+ * Set the sample rate.
+ *
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @param samplesPerSecond The number of samples per channel per second.
+ */
+void setAnalogSampleRate(double samplesPerSecond, int32_t *status) {
+  // TODO: This will change when variable size scan lists are implemented.
+  // TODO: Need float comparison with epsilon.
+  //wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond);
+  analogSampleRateSet = true;
+
+  // Compute the convert rate
+  uint32_t ticksPerSample = (uint32_t)((float)kTimebase / samplesPerSecond);
+  uint32_t ticksPerConversion = ticksPerSample / getAnalogNumChannelsToActivate(status);
+  // ticksPerConversion must be at least 80
+  if (ticksPerConversion < 80) {
+    if ((*status) >= 0) *status = SAMPLE_RATE_TOO_HIGH;
+    ticksPerConversion = 80;
+  }
+
+  // Atomically set the scan size and the convert rate so that the sample rate is constant
+  tAI::tConfig config;
+  config.ScanSize = getAnalogNumChannelsToActivate(status);
+  config.ConvertRate = ticksPerConversion;
+  analogInputSystem->writeConfig(config, status);
+
+  // Indicate that the scan size has been commited to hardware.
+  setAnalogNumChannelsToActivate(0);
+}
+
+/**
+ * Get the current sample rate.
+ *
+ * This assumes one entry in the scan list.
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @return Sample rate.
+ */
+float getAnalogSampleRate(int32_t *status) {
+  uint32_t ticksPerConversion = analogInputSystem->readLoopTiming(status);
+  uint32_t ticksPerSample = ticksPerConversion * getAnalogNumActiveChannels(status);
+  return (float)kTimebase / (float)ticksPerSample;
+}
+
+/**
+ * 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 analog_port_pointer Pointer to the analog port to configure.
+ * @param bits Number of bits to average.
+ */
+void setAnalogAverageBits(void* analog_port_pointer, uint32_t bits, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  analogInputSystem->writeAverageBits(port->port.pin, bits, status);
+}
+
+/**
+ * Get the number of averaging bits.
+ *
+ * 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.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Bits to average.
+ */
+uint32_t getAnalogAverageBits(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  uint32_t result = analogInputSystem->readAverageBits(port->port.pin, status);
+  return result;
+}
+
+/**
+ * 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 analog_port_pointer Pointer to the analog port to use.
+ * @param bits Number of bits to oversample.
+ */
+void setAnalogOversampleBits(void* analog_port_pointer, uint32_t bits, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  analogInputSystem->writeOversampleBits(port->port.pin, bits, status);
+}
+
+
+/**
+ * Get the number of oversample bits.
+ *
+ * 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.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Bits to oversample.
+ */
+uint32_t getAnalogOversampleBits(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  uint32_t result = analogInputSystem->readOversampleBits(port->port.pin, status);
+  return result;
+}
+
+/**
+ * Get a sample straight from the channel on this module.
+ *
+ * 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.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A sample straight from the channel on this module.
+ */
+int16_t getAnalogValue(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  int16_t value;
+  checkAnalogInputChannel(port->port.pin);
+
+  tAI::tReadSelect readSelect;
+  readSelect.Channel = port->port.pin;
+  readSelect.Averaged = false;
+
+  {
+    ::std::unique_lock<ReentrantMutex> sync(analogRegisterWindowMutex);
+    analogInputSystem->writeReadSelect(readSelect, status);
+    analogInputSystem->strobeLatchOutput(status);
+    value = (int16_t) analogInputSystem->readOutput(status);
+  }
+
+  return value;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for the channel.
+ *
+ * The sample is 12-bit + the value 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**(OversamplBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A sample from the oversample and average engine for the channel.
+ */
+int32_t getAnalogAverageValue(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  int32_t value;
+  checkAnalogInputChannel(port->port.pin);
+
+  tAI::tReadSelect readSelect;
+  readSelect.Channel = port->port.pin;
+  readSelect.Averaged = true;
+
+  {
+    ::std::unique_lock<ReentrantMutex> sync(analogRegisterWindowMutex);
+    analogInputSystem->writeReadSelect(readSelect, status);
+    analogInputSystem->strobeLatchOutput(status);
+    value = (int32_t) analogInputSystem->readOutput(status);
+  }
+
+  return value;
+}
+
+/**
+ * Get a scaled sample straight from the channel on this module.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A scaled sample straight from the channel on this module.
+ */
+float getAnalogVoltage(void* analog_port_pointer, int32_t *status) {
+  int16_t value = getAnalogValue(analog_port_pointer, status);
+  uint32_t LSBWeight = getAnalogLSBWeight(analog_port_pointer, status);
+  int32_t offset = getAnalogOffset(analog_port_pointer, status);
+  float voltage = LSBWeight * 1.0e-9 * value - offset * 1.0e-9;
+  return voltage;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for the 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.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A scaled sample from the output of the oversample and average engine for the channel.
+ */
+float getAnalogAverageVoltage(void* analog_port_pointer, int32_t *status) {
+  int32_t value = getAnalogAverageValue(analog_port_pointer, status);
+  uint32_t LSBWeight = getAnalogLSBWeight(analog_port_pointer, status);
+  int32_t offset = getAnalogOffset(analog_port_pointer, status);
+  uint32_t oversampleBits = getAnalogOversampleBits(analog_port_pointer, status);
+  float voltage = ((LSBWeight * 1.0e-9 * value) / (float)(1 << oversampleBits)) - offset * 1.0e-9;
+  return voltage;
+}
+
+/**
+ * Convert a voltage to a raw value for a specified channel.
+ *
+ * This process depends on the calibration of each channel, so the channel
+ * must be specified.
+ *
+ * @todo This assumes raw values.  Oversampling not supported as is.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @param voltage The voltage to convert.
+ * @return The raw value for the channel.
+ */
+int32_t getAnalogVoltsToValue(void* analog_port_pointer, double voltage, int32_t *status) {
+  if (voltage > 5.0) {
+    voltage = 5.0;
+    *status = VOLTAGE_OUT_OF_RANGE;
+  }
+  if (voltage < 0.0) {
+    voltage = 0.0;
+    *status = VOLTAGE_OUT_OF_RANGE;
+  }
+  uint32_t LSBWeight = getAnalogLSBWeight(analog_port_pointer, status);
+  int32_t offset = getAnalogOffset(analog_port_pointer, status);
+  int32_t value = (int32_t) ((voltage + offset * 1.0e-9) / (LSBWeight * 1.0e-9));
+  return value;
+}
+
+/**
+ * Get the factory scaling least significant bit weight constant.
+ * The least significant bit weight constant for the channel that was calibrated in
+ * manufacturing and stored in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Least significant bit weight.
+ */
+uint32_t getAnalogLSBWeight(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  uint32_t lsbWeight = FRC_NetworkCommunication_nAICalibration_getLSBWeight(0, port->port.pin, status); // XXX: aiSystemIndex == 0?
+  return lsbWeight;
+}
+
+/**
+ * Get the factory scaling offset constant.
+ * The offset constant for the channel that was calibrated in manufacturing and stored
+ * in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Offset constant.
+ */
+int32_t getAnalogOffset(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  int32_t offset = FRC_NetworkCommunication_nAICalibration_getOffset(0, port->port.pin, status); // XXX: aiSystemIndex == 0?
+  return offset;
+}
+
+
+/**
+ * Return the number of channels on the module in use.
+ *
+ * @return Active channels.
+ */
+uint32_t getAnalogNumActiveChannels(int32_t *status) {
+  uint32_t scanSize = analogInputSystem->readConfig_ScanSize(status);
+  if (scanSize == 0)
+    return 8;
+  return scanSize;
+}
+
+/**
+ * Get the number of active channels.
+ *
+ * This is an internal function to allow the atomic update of both the
+ * number of active channels and the sample rate.
+ *
+ * When the number of channels changes, use the new value.  Otherwise,
+ * return the curent value.
+ *
+ * @return Value to write to the active channels field.
+ */
+uint32_t getAnalogNumChannelsToActivate(int32_t *status) {
+  if(analogNumChannelsToActivate == 0) return getAnalogNumActiveChannels(status);
+  return analogNumChannelsToActivate;
+}
+
+/**
+ * Set the number of active channels.
+ *
+ * Store the number of active channels to set.  Don't actually commit to hardware
+ * until SetSampleRate().
+ *
+ * @param channels Number of active channels.
+ */
+void setAnalogNumChannelsToActivate(uint32_t channels) {
+  analogNumChannelsToActivate = channels;
+}
+
+//// Accumulator Stuff
+
+/**
+ * Is the channel attached to an accumulator.
+ *
+ * @return The analog channel is attached to an accumulator.
+ */
+bool isAccumulatorChannel(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  for (uint32_t i=0; i < kAccumulatorNumChannels; i++) {
+    if (port->port.pin == kAccumulatorChannels[i]) return true;
+  }
+  return false;
+}
+
+/**
+ * Initialize the accumulator.
+ */
+void initAccumulator(void* analog_port_pointer, int32_t *status) {
+  setAccumulatorCenter(analog_port_pointer, 0, status);
+  resetAccumulator(analog_port_pointer, status);
+}
+
+/**
+ * Resets the accumulator to the initial value.
+ */
+void resetAccumulator(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  if (port->accumulator == NULL) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  port->accumulator->strobeReset(status);
+}
+
+/**
+ * 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 make integration work
+ * and to take the device offset into account when integrating.
+ *
+ * This center value is based on the output of the oversampled and averaged source from channel 1.
+ * Because of this, any non-zero oversample bits will affect the size of the value for this field.
+ */
+void setAccumulatorCenter(void* analog_port_pointer, int32_t center, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  if (port->accumulator == NULL) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  port->accumulator->writeCenter(center, status);
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void setAccumulatorDeadband(void* analog_port_pointer, int32_t deadband, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  if (port->accumulator == NULL) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  port->accumulator->writeDeadband(deadband, status);
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * Read the value that has been accumulating on channel 1.
+ * The accumulator is attached after the oversample and average engine.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t getAccumulatorValue(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  if (port->accumulator == NULL) {
+    *status = NULL_PARAMETER;
+    return 0;
+  }
+  int64_t value = port->accumulator->readOutput_Value(status);
+  return value;
+}
+
+/**
+ * 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 getAccumulatorCount(void* analog_port_pointer, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  if (port->accumulator == NULL) {
+    *status = NULL_PARAMETER;
+    return 0;
+  }
+  return port->accumulator->readOutput_Count(status);
+}
+
+/**
+ * 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 Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void getAccumulatorOutput(void* analog_port_pointer, int64_t *value, uint32_t *count, int32_t *status) {
+  AnalogPort* port = (AnalogPort*) analog_port_pointer;
+  if (port->accumulator == NULL) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  if (value == NULL || count == NULL) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+
+  tAccumulator::tOutput output = port->accumulator->readOutput(status);
+
+  *value = output.Value;
+  *count = output.Count;
+}
+
+
+struct trigger_t {
+  tAnalogTrigger* trigger;
+  AnalogPort* port;
+  uint32_t index;
+};
+typedef struct trigger_t AnalogTrigger;
+
+static Resource *triggers = NULL;
+
+void* initializeAnalogTrigger(void* port_pointer, uint32_t *index, int32_t *status) {
+  Port* port = (Port*) port_pointer;
+  Resource::CreateResourceObject(&triggers, tAnalogTrigger::kNumSystems);
+
+  AnalogTrigger* trigger = new AnalogTrigger();
+  trigger->port = (AnalogPort*) initializeAnalogInputPort(port, status);
+  trigger->index = triggers->Allocate("Analog Trigger");
+  *index = trigger->index;
+  // TODO: if (index == ~0ul) { CloneError(triggers); return; }
+
+  trigger->trigger = tAnalogTrigger::create(trigger->index, status);
+  trigger->trigger->writeSourceSelect_Channel(port->pin, status);
+
+  return trigger;
+}
+
+void cleanAnalogTrigger(void* analog_trigger_pointer, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  triggers->Free(trigger->index);
+  delete trigger->trigger;
+  delete trigger;
+}
+
+void setAnalogTriggerLimitsRaw(void* analog_trigger_pointer, int32_t lower, int32_t upper, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  if (lower > upper) {
+	*status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+  }
+  trigger->trigger->writeLowerLimit(lower, status);
+  trigger->trigger->writeUpperLimit(upper, status);
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ * The limits are given as floating point voltage values.
+ */
+void setAnalogTriggerLimitsVoltage(void* analog_trigger_pointer, double lower, double upper, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  if (lower > upper) {
+	*status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+  }
+  // TODO: This depends on the averaged setting.  Only raw values will work as is.
+  trigger->trigger->writeLowerLimit(getAnalogVoltsToValue(trigger->port, lower, status), status);
+  trigger->trigger->writeUpperLimit(getAnalogVoltsToValue(trigger->port, upper, status), 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.
+ */
+void setAnalogTriggerAveraged(void* analog_trigger_pointer, bool useAveragedValue, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  if (trigger->trigger->readSourceSelect_Filter(status) != 0) {
+	*status = INCOMPATIBLE_STATE;
+	// TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not support average and filtering at the same time.");
+  }
+  trigger->trigger->writeSourceSelect_Averaged(useAveragedValue, 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.
+ */
+void setAnalogTriggerFiltered(void* analog_trigger_pointer, bool useFilteredValue, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  if (trigger->trigger->readSourceSelect_Averaged(status) != 0) {
+	*status = INCOMPATIBLE_STATE;
+	// TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not support average and filtering at the same time.");
+  }
+  trigger->trigger->writeSourceSelect_Filter(useFilteredValue, status);
+}
+
+/**
+ * Return the InWindow output of the analog trigger.
+ * True if the analog input is between the upper and lower limits.
+ * @return The InWindow output of the analog trigger.
+ */
+bool getAnalogTriggerInWindow(void* analog_trigger_pointer, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  return trigger->trigger->readOutput_InHysteresis(trigger->index, status) != 0;
+}
+
+/**
+ * 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 The TriggerState output of the analog trigger.
+ */
+bool getAnalogTriggerTriggerState(void* analog_trigger_pointer, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  return trigger->trigger->readOutput_OverLimit(trigger->index, status) != 0;
+}
+
+/**
+ * Get the state of the analog trigger output.
+ * @return The state of the analog trigger output.
+ */
+bool getAnalogTriggerOutput(void* analog_trigger_pointer, AnalogTriggerType type, int32_t *status) {
+  AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+  bool result = false;
+  switch(type) {
+  case kInWindow:
+	result = trigger->trigger->readOutput_InHysteresis(trigger->index, status);
+	break; // XXX: Backport
+  case kState:
+	result = trigger->trigger->readOutput_OverLimit(trigger->index, status);
+	break; // XXX: Backport
+  case kRisingPulse:
+  case kFallingPulse:
+	*status = ANALOG_TRIGGER_PULSE_OUTPUT_ERROR;
+	return false;
+  }
+  return result;
+}
+
+
+
+//// Float JNA Hack
+// Float
+int getAnalogSampleRateIntHack(int32_t *status) {
+  return floatToInt(getAnalogSampleRate(status));
+}
+
+int getAnalogVoltageIntHack(void* analog_port_pointer, int32_t *status) {
+  return floatToInt(getAnalogVoltage(analog_port_pointer, status));
+}
+
+int getAnalogAverageVoltageIntHack(void* analog_port_pointer, int32_t *status) {
+  return floatToInt(getAnalogAverageVoltage(analog_port_pointer, status));
+}
+
+
+// Doubles
+void setAnalogSampleRateIntHack(int samplesPerSecond, int32_t *status) {
+  setAnalogSampleRate(intToFloat(samplesPerSecond), status);
+}
+
+int32_t getAnalogVoltsToValueIntHack(void* analog_port_pointer, int voltage, int32_t *status) {
+  return getAnalogVoltsToValue(analog_port_pointer, intToFloat(voltage), status);
+}
+
+void setAnalogTriggerLimitsVoltageIntHack(void* analog_trigger_pointer, int lower, int upper, int32_t *status) {
+  setAnalogTriggerLimitsVoltage(analog_trigger_pointer, intToFloat(lower), intToFloat(upper), status);
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/ChipObject.h b/aos/externals/allwpilib/hal/lib/Athena/ChipObject.h
new file mode 100644
index 0000000..630c34d
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ChipObject.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wpedantic"
+#pragma GCC diagnostic ignored "-Wignored-qualifiers"
+
+#include <stdint.h>
+
+#include "FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h"
+#include "FRC_FPGA_ChipObject/tDMAChannelDescriptor.h"
+#include "FRC_FPGA_ChipObject/tDMAManager.h"
+#include "FRC_FPGA_ChipObject/tInterruptManager.h"
+#include "FRC_FPGA_ChipObject/tSystem.h"
+#include "FRC_FPGA_ChipObject/tSystemInterface.h"
+
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h"
+
+// FIXME: these should not be here!
+using namespace nFPGA;
+using namespace nRoboRIO_FPGANamespace;
+#pragma GCC diagnostic pop
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Compressor.cpp b/aos/externals/allwpilib/hal/lib/Athena/Compressor.cpp
new file mode 100644
index 0000000..9305097
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Compressor.cpp
@@ -0,0 +1,116 @@
+#include "HAL/Compressor.hpp"
+#include "ctre/PCM.h"
+#include <iostream>
+
+static const int NUM_MODULE_NUMBERS = 63;
+extern PCM *modules[NUM_MODULE_NUMBERS];
+extern void initializePCM(int module);
+
+void *initializeCompressor(uint8_t module) {
+	initializePCM(module);
+	
+	return modules[module];
+}
+
+bool checkCompressorModule(uint8_t module) {
+	return module < NUM_MODULE_NUMBERS;
+}
+
+bool getCompressor(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressor(value);
+	
+	return value;
+}
+
+
+void setClosedLoopControl(void *pcm_pointer, bool value, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	
+	*status = module->SetClosedLoopControl(value);
+}
+
+
+bool getClosedLoopControl(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetClosedLoopControl(value);
+	
+	return value;
+}
+
+
+bool getPressureSwitch(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetPressure(value);
+	
+	return value;
+}
+
+
+float getCompressorCurrent(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	float value;
+	
+	*status = module->GetCompressorCurrent(value);
+	
+	return value;
+}
+bool getCompressorCurrentTooHighFault(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressorCurrentTooHighFault(value);
+	
+	return value;
+}
+bool getCompressorCurrentTooHighStickyFault(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressorCurrentTooHighStickyFault(value);
+	
+	return value;
+}
+bool getCompressorShortedStickyFault(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressorShortedStickyFault(value);
+	
+	return value;
+}
+bool getCompressorShortedFault(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressorShortedFault(value);
+	
+	return value;
+}
+bool getCompressorNotConnectedStickyFault(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressorNotConnectedStickyFault(value);
+	
+	return value;
+}
+bool getCompressorNotConnectedFault(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	bool value;
+	
+	*status = module->GetCompressorNotConnectedFault(value);
+	
+	return value;
+}
+void clearAllPCMStickyFaults(void *pcm_pointer, int32_t *status) {
+	PCM *module = (PCM *)pcm_pointer;
+	
+	*status = module->ClearStickyFaults();
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Digital.cpp b/aos/externals/allwpilib/hal/lib/Athena/Digital.cpp
new file mode 100644
index 0000000..006983f
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Digital.cpp
@@ -0,0 +1,1553 @@
+
+#include "HAL/Digital.hpp"
+
+#include "Port.h"
+#include "HAL/HAL.hpp"
+#include "ChipObject.h"
+#include "HAL/cpp/Synchronized.hpp"
+#include "HAL/cpp/Resource.hpp"
+#include "NetworkCommunication/LoadOut.h"
+#include <stdio.h>
+#include <math.h>
+#include "i2clib/i2c-lib.h"
+#include "spilib/spi-lib.h"
+
+static const uint32_t kExpectedLoopTiming = 40;
+static const uint32_t kDigitalPins = 26;
+static const uint32_t kPwmPins = 20;
+static const uint32_t kRelayPins = 8;
+static const uint32_t kNumHeaders = 10; // Number of non-MXP pins
+
+ReentrantMutex& spiGetSemaphore(uint8_t port);
+
+/**
+ * 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 const float kDefaultPwmPeriod = 5.05;
+/**
+ * kDefaultPwmCenter is the PWM range center in ms
+ */
+static const 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;
+
+struct DigitalPort {
+  Port port;
+  uint32_t PWMGeneratorID;
+};
+
+// XXX: Set these back to static once we figure out the memory clobbering issue
+// Create a semaphore to protect changes to the digital output values
+ReentrantMutex digitalDIOSemaphore;
+// Create a semaphore to protect changes to the relay values
+ReentrantMutex digitalRelaySemaphore;
+// Create a semaphore to protect changes to the DO PWM config
+ReentrantMutex digitalPwmSemaphore;
+ReentrantMutex digitalI2COnBoardSemaphore;
+ReentrantMutex digitalI2CMXPSemaphore;
+
+tDIO* digitalSystem = NULL;
+tRelay* relaySystem = NULL;
+tPWM* pwmSystem = NULL;
+Resource *DIOChannels = NULL;
+Resource *DO_PWMGenerators = NULL;
+Resource *PWMChannels = NULL;
+
+bool digitalSystemsInitialized = false;
+
+uint8_t i2COnboardObjCount = 0;
+uint8_t i2CMXPObjCount = 0;
+uint8_t i2COnBoardHandle = 0;
+uint8_t i2CMXPHandle = 0;
+
+int32_t m_spiCS0Handle = 0;
+int32_t m_spiCS1Handle = 0;
+int32_t m_spiCS2Handle = 0;
+int32_t m_spiCS3Handle = 0;
+int32_t m_spiMXPHandle = 0;
+ReentrantMutex spiOnboardSemaphore;
+ReentrantMutex spiMXPSemaphore;
+tSPI *spiSystem;
+
+/**
+ * Initialize the digital system.
+ */
+void initializeDigital(int32_t *status) {
+  if (digitalSystemsInitialized) return;
+
+  Resource::CreateResourceObject(&DIOChannels, tDIO::kNumSystems * kDigitalPins);
+  Resource::CreateResourceObject(&DO_PWMGenerators, tDIO::kNumPWMDutyCycleAElements + tDIO::kNumPWMDutyCycleBElements);
+  Resource::CreateResourceObject(&PWMChannels, tPWM::kNumSystems * kPwmPins);
+  digitalSystem = tDIO::create(status);
+
+  // Relay Setup
+  relaySystem = tRelay::create(status);
+
+  // Turn off all relay outputs.
+  relaySystem->writeValue_Forward(0, status);
+  relaySystem->writeValue_Reverse(0, status);
+
+  // PWM Setup
+  pwmSystem = tPWM::create(status);
+
+  // Make sure that the 9403 IONode has had a chance to initialize before continuing.
+  while(pwmSystem->readLoopTiming(status) == 0) delayTicks(1);
+
+  if (pwmSystem->readLoopTiming(status) != kExpectedLoopTiming) {
+	// TODO: char err[128];
+	// TODO: sprintf(err, "DIO LoopTiming: %d, expecting: %lu\n", digitalModules[port->module-1]->readLoopTiming(status), kExpectedLoopTiming);
+	*status = LOOP_TIMING_ERROR; // NOTE: Doesn't display the error
+  }
+
+  //Calculate the length, in ms, of one DIO loop
+  double loopTime = pwmSystem->readLoopTiming(status)/(kSystemClockTicksPerMicrosecond*1e3);
+
+  pwmSystem->writeConfig_Period((uint16_t) (kDefaultPwmPeriod/loopTime + .5), status);
+  uint16_t minHigh = (uint16_t) ((kDefaultPwmCenter-kDefaultPwmStepsDown*loopTime)/loopTime + .5);
+  pwmSystem->writeConfig_MinHigh(minHigh, status);
+//  printf("MinHigh: %d\n", minHigh);
+  // Ensure that PWM output values are set to OFF
+  for (uint32_t pwm_index = 0; pwm_index < kPwmPins; pwm_index++) {
+    // Initialize port structure
+    DigitalPort* digital_port = new DigitalPort();
+    digital_port->port.pin = pwm_index;
+
+    setPWM(digital_port, kPwmDisabled, status);
+    setPWMPeriodScale(digital_port, 3, status); // Set all to 4x by default.
+  }
+
+  digitalSystemsInitialized = true;
+}
+
+/**
+ * Create a new instance of a digital port.
+ */
+void* initializeDigitalPort(void* port_pointer, int32_t *status) {
+  initializeDigital(status);
+  Port* port = (Port*) port_pointer;
+
+  // Initialize port structure
+  DigitalPort* digital_port = new DigitalPort();
+  digital_port->port = *port;
+
+  return digital_port;
+}
+
+bool checkPWMChannel(void* digital_port_pointer) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  return port->port.pin < kPwmPins;
+}
+
+bool checkRelayChannel(void* digital_port_pointer) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  return port->port.pin < kRelayPins;
+}
+
+/**
+ * Map DIO pin numbers from their physical number (10 to 26) to their position
+ * in the bit field.
+ */
+uint32_t remapMXPChannel(uint32_t pin) {
+    return pin - 10;
+}
+
+uint32_t remapMXPPWMChannel(uint32_t pin) {
+	if(pin < 14) {
+		return pin - 10;	//first block of 4 pwms (MXP 0-3)
+	} else {
+		return pin - 6;	//block of PWMs after SPI
+	}
+}
+
+/**
+ * Set a PWM channel to the desired value. The values range from 0 to 255 and the period is controlled
+ * by the PWM Period and MinHigh registers.
+ *
+ * @param channel The PWM channel to set.
+ * @param value The PWM value to set.
+ */
+void setPWM(void* digital_port_pointer, unsigned short value, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  checkPWMChannel(port);
+
+  if(port->port.pin < tPWM::kNumHdrRegisters) {
+    pwmSystem->writeHdr(port->port.pin, value, status);
+  } else {
+    pwmSystem->writeMXP(port->port.pin - tPWM::kNumHdrRegisters, value, status);
+  }
+}
+
+/**
+ * Get a value from a PWM channel. The values range from 0 to 255.
+ *
+ * @param channel The PWM channel to read from.
+ * @return The raw PWM value.
+ */
+unsigned short getPWM(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  checkPWMChannel(port);
+
+  if(port->port.pin < tPWM::kNumHdrRegisters) {
+    return pwmSystem->readHdr(port->port.pin, status);
+  } else {
+    return pwmSystem->readMXP(port->port.pin - tPWM::kNumHdrRegisters, status);
+  }
+}
+
+void latchPWMZero(void* digital_port_pointer, int32_t *status) {
+	DigitalPort* port = (DigitalPort*) digital_port_pointer;
+	pwmSystem->writeZeroLatch(port->port.pin, true, status);
+	pwmSystem->writeZeroLatch(port->port.pin, false, status);
+}
+
+/**
+ * Set how how often the PWM signal is squelched, thus scaling the period.
+ *
+ * @param channel The PWM channel to configure.
+ * @param squelchMask The 2-bit mask of outputs to squelch.
+ */
+void setPWMPeriodScale(void* digital_port_pointer, uint32_t squelchMask, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  checkPWMChannel(port);
+
+  if(port->port.pin < tPWM::kNumPeriodScaleHdrElements) {
+    pwmSystem->writePeriodScaleHdr(port->port.pin, squelchMask, status);
+  } else {
+    pwmSystem->writePeriodScaleMXP(port->port.pin - tPWM::kNumPeriodScaleHdrElements, squelchMask, status);
+  }
+}
+
+/**
+ * Allocate a DO PWM Generator.
+ * Allocate PWM generators so that they are not accidentally reused.
+ *
+ * @return PWM Generator refnum
+ */
+void* allocatePWM(int32_t *status) {
+  return (void*)DO_PWMGenerators->Allocate("DO_PWM");
+}
+
+/**
+ * Free the resource associated with a DO PWM generator.
+ *
+ * @param pwmGenerator The pwmGen to free that was allocated with AllocateDO_PWM()
+ */
+void freePWM(void* pwmGenerator, int32_t *status) {
+  uint32_t id = (uint32_t) pwmGenerator;
+  if (id == ~0ul) return;
+  DO_PWMGenerators->Free(id);
+}
+
+/**
+ * Change the frequency of the DO PWM generator.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz.  The frequency resolution is logarithmic.
+ *
+ * @param rate The frequency to output all digital output PWM signals.
+ */
+void setPWMRate(double rate, int32_t *status) {
+  // Currently rounding in the log rate domain... heavy weight toward picking a higher freq.
+  // TODO: Round in the linear rate domain.
+  uint8_t pwmPeriodPower = (uint8_t)(log(1.0 / (pwmSystem->readLoopTiming(status) * 0.25E-6 * rate))/log(2.0) + 0.5);
+  digitalSystem->writePWMPeriodPower(pwmPeriodPower, status);
+}
+
+
+/**
+ * Configure the duty-cycle of the PWM generator
+ *
+ * @param pwmGenerator The generator index reserved by AllocateDO_PWM()
+ * @param dutyCycle The percent duty cycle to output [0..1].
+ */
+void setPWMDutyCycle(void* pwmGenerator, double dutyCycle, int32_t *status) {
+  uint32_t id = (uint32_t) pwmGenerator;
+  if (id == ~0ul) return;
+  if (dutyCycle > 1.0) dutyCycle = 1.0;
+  if (dutyCycle < 0.0) dutyCycle = 0.0;
+  float rawDutyCycle = 256.0 * dutyCycle;
+  if (rawDutyCycle > 255.5) rawDutyCycle = 255.5;
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalPwmSemaphore);
+    uint8_t pwmPeriodPower = digitalSystem->readPWMPeriodPower(status);
+    if (pwmPeriodPower < 4) {
+	  // The resolution of the duty cycle drops close to the highest frequencies.
+	  rawDutyCycle = rawDutyCycle / pow(2.0, 4 - pwmPeriodPower);
+	}
+	if(id < 4)
+		digitalSystem->writePWMDutyCycleA(id, (uint8_t)rawDutyCycle, status);
+	else 
+		digitalSystem->writePWMDutyCycleB(id - 4, (uint8_t)rawDutyCycle, status);
+  }
+}
+
+/**
+ * Configure which DO channel the PWM signal is output on
+ *
+ * @param pwmGenerator The generator index reserved by AllocateDO_PWM()
+ * @param channel The Digital Output channel to output on
+ */
+void setPWMOutputChannel(void* pwmGenerator, uint32_t pin, int32_t *status) {
+  uint32_t id = (uint32_t) pwmGenerator;
+  if (id > 5) return;
+  digitalSystem->writePWMOutputSelect(id, pin, status);
+}
+
+/**
+ * Set the state of a relay.
+ * Set the state of a relay output to be forward. Relays have two outputs and each is
+ * independently set to 0v or 12v.
+ */
+void setRelayForward(void* digital_port_pointer, bool on, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  checkRelayChannel(port);
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalRelaySemaphore);
+    uint8_t forwardRelays = relaySystem->readValue_Forward(status);
+    if (on)
+      forwardRelays |= 1 << port->port.pin;
+    else
+      forwardRelays &= ~(1 << port->port.pin);
+    relaySystem->writeValue_Forward(forwardRelays, status);
+  }
+}
+
+/**
+ * Set the state of a relay.
+ * Set the state of a relay output to be reverse. Relays have two outputs and each is
+ * independently set to 0v or 12v.
+ */
+void setRelayReverse(void* digital_port_pointer, bool on, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  checkRelayChannel(port);
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalRelaySemaphore);
+    uint8_t reverseRelays = relaySystem->readValue_Reverse(status);
+    if (on)
+      reverseRelays |= 1 << port->port.pin;
+    else
+      reverseRelays &= ~(1 << port->port.pin);
+    relaySystem->writeValue_Reverse(reverseRelays, status);
+  }
+}
+
+/**
+ * Get the current state of the forward relay channel
+ */
+bool getRelayForward(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  uint8_t forwardRelays = relaySystem->readValue_Forward(status);
+  return (forwardRelays & (1 << port->port.pin)) != 0;
+}
+
+/**
+ * Get the current state of the reverse relay channel
+ */
+bool getRelayReverse(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  uint8_t reverseRelays = relaySystem->readValue_Reverse(status);
+  return (reverseRelays & (1 << port->port.pin)) != 0;
+}
+
+/**
+ * Allocate Digital I/O channels.
+ * Allocate channels so that they are not accidently reused. Also the direction is set at the
+ * time of the allocation.
+ *
+ * @param channel The Digital I/O channel
+ * @param input If true open as input; if false open as output
+ * @return Was successfully allocated
+ */
+bool allocateDIO(void* digital_port_pointer, bool input, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  char buf[64];
+  snprintf(buf, 64, "DIO %d", port->port.pin);
+  if (DIOChannels->Allocate(port->port.pin, buf) == ~0ul) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return false;
+  }
+
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalDIOSemaphore);
+
+    tDIO::tOutputEnable outputEnable = digitalSystem->readOutputEnable(status);
+
+    if(port->port.pin < kNumHeaders) {
+      uint32_t bitToSet = 1 << port->port.pin;
+      if (input) {
+        outputEnable.Headers = outputEnable.Headers & (~bitToSet); // clear the bit for read
+      } else {
+        outputEnable.Headers = outputEnable.Headers | bitToSet; // set the bit for write
+      }
+    } else {
+      uint32_t bitToSet = 1 << remapMXPChannel(port->port.pin);
+
+      // Disable special functions on this pin
+      short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+      digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status);
+
+      if (input) {
+        outputEnable.MXP = outputEnable.MXP & (~bitToSet); // clear the bit for read
+      } else {
+        outputEnable.MXP = outputEnable.MXP | bitToSet; // set the bit for write
+      }
+    }
+
+    digitalSystem->writeOutputEnable(outputEnable, status);
+  }
+  return true;
+}
+
+bool allocatePWMChannel(void* digital_port_pointer, int32_t *status) {
+		DigitalPort* port = (DigitalPort*) digital_port_pointer;
+		char buf[64];
+		snprintf(buf, 64, "PWM %d", port->port.pin);
+		if (PWMChannels->Allocate(port->port.pin, buf) == ~0ul) {
+      *status = RESOURCE_IS_ALLOCATED;
+      return false;
+    }
+
+		if (port->port.pin > tPWM::kNumHdrRegisters-1) {
+			snprintf(buf, 64, "PWM %d and DIO %d", port->port.pin, remapMXPPWMChannel(port->port.pin) + 10);
+			if (DIOChannels->Allocate(remapMXPPWMChannel(port->port.pin) + 10, buf) == ~0ul) return false;
+		    uint32_t bitToSet = 1 << remapMXPPWMChannel(port->port.pin);
+		    short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+		    digitalSystem->writeEnableMXPSpecialFunction(specialFunctions | bitToSet, status);
+		}
+		return true;
+}
+
+void freePWMChannel(void* digital_port_pointer, int32_t *status) {
+    DigitalPort* port = (DigitalPort*) digital_port_pointer;
+    PWMChannels->Free(port->port.pin);
+    if(port->port.pin > tPWM::kNumHdrRegisters-1) {
+        DIOChannels->Free(remapMXPPWMChannel(port->port.pin) + 10);
+        uint32_t bitToUnset = 1 << remapMXPPWMChannel(port->port.pin);
+        short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+        digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToUnset, status);
+    }
+}
+
+/**
+ * Free the resource associated with a digital I/O channel.
+ *
+ * @param channel The Digital I/O channel to free
+ */
+void freeDIO(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  DIOChannels->Free(port->port.pin);
+}
+
+/**
+ * Write a digital I/O bit to the FPGA.
+ * Set a single value on a digital I/O channel.
+ *
+ * @param channel The Digital I/O channel
+ * @param value The state to set the digital channel (if it is configured as an output)
+ */
+void setDIO(void* digital_port_pointer, short value, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  if (value != 0 && value != 1) {
+    if (value != 0)
+      value = 1;
+  }
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalDIOSemaphore);
+    tDIO::tDO currentDIO = digitalSystem->readDO(status);
+
+    if(port->port.pin < kNumHeaders) {
+      if(value == 0) {
+        currentDIO.Headers = currentDIO.Headers & ~(1 << port->port.pin);
+      } else if (value == 1) {
+        currentDIO.Headers = currentDIO.Headers | (1 << port->port.pin);
+      }
+    } else {
+      if(value == 0) {
+        currentDIO.MXP = currentDIO.MXP & ~(1 << remapMXPChannel(port->port.pin));
+      } else if (value == 1) {
+        currentDIO.MXP = currentDIO.MXP | (1 << remapMXPChannel(port->port.pin));
+      }
+
+      uint32_t bitToSet = 1 << remapMXPChannel(port->port.pin);
+      short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+      digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status);
+    }
+    digitalSystem->writeDO(currentDIO, status);
+  }
+}
+
+/**
+ * Write the filter index from the FPGA.
+ * Set the filter index used to filter out short pulses.
+ *
+ * @param digital_port_pointer The digital I/O channel
+ * @param filter_index The filter index.  Must be between 0 and 3.
+ */
+void setFilterSelect(void* digital_port_pointer, int filter_index,
+                     int32_t* status) {
+  DigitalPort* port = (DigitalPort*)digital_port_pointer;
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalDIOSemaphore);
+    if (port->port.pin < kNumHeaders) {
+      digitalSystem->writeFilterSelectHdr(port->port.pin, filter_index, status);
+    } else {
+      digitalSystem->writeFilterSelectMXP(remapMXPChannel(port->port.pin),
+                                          filter_index, status);
+    }
+  }
+}
+
+/**
+ * Read the filter index from the FPGA.
+ * Get the filter index used to filter out short pulses.
+ *
+ * @param digital_port_pointer The digital I/O channel
+ * @return filter_index The filter index.  Must be between 0 and 3.
+ */
+int getFilterSelect(void* digital_port_pointer, int32_t* status) {
+  DigitalPort* port = (DigitalPort*)digital_port_pointer;
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalDIOSemaphore);
+    if (port->port.pin < kNumHeaders) {
+      return digitalSystem->readFilterSelectHdr(port->port.pin, status);
+    } else {
+      return digitalSystem->readFilterSelectMXP(remapMXPChannel(port->port.pin),
+                                                status);
+    }
+  }
+}
+
+/**
+ * Set the filter period for the specified filter index.
+ *
+ * Set the filter period in FPGA cycles.  Even though there are 2 different
+ * filter index domains (MXP vs HDR), ignore that distinction for now since it
+ * compilicates the interface.  That can be changed later.
+ *
+ * @param filter_index The filter index, 0 - 2.
+ * @param value The number of cycles that the signal must not transition to be
+ * counted as a transition.
+ */
+void setFilterPeriod(int filter_index, uint32_t value, int32_t* status) {
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalDIOSemaphore);
+    digitalSystem->writeFilterPeriodHdr(filter_index, value, status);
+    if (*status == 0) {
+      printf("My error %d index %d period %d\n", *status, filter_index, value);
+      digitalSystem->writeFilterPeriodMXP(filter_index, value, status);
+      printf("My error %d index %d period %d\n", *status, filter_index, value);
+    }
+  }
+}
+
+/**
+ * Get the filter period for the specified filter index.
+ *
+ * Get the filter period in FPGA cycles.  Even though there are 2 different
+ * filter index domains (MXP vs HDR), ignore that distinction for now since it
+ * compilicates the interface.  Set status to NiFpga_Status_SoftwareFault if the
+ * filter values miss-match.
+ *
+ * @param filter_index The filter index, 0 - 2.
+ * @param value The number of cycles that the signal must not transition to be
+ * counted as a transition.
+ */
+uint32_t getFilterPeriod(int filter_index, int32_t* status) {
+  uint32_t hdr_period = 0;
+  uint32_t mxp_period = 0;
+  {
+    ::std::unique_lock<ReentrantMutex> sync(digitalDIOSemaphore);
+    hdr_period = digitalSystem->readFilterPeriodHdr(filter_index, status);
+    printf("My error get %d index %d %d\n", *status, filter_index, hdr_period);
+    if (*status == 0) {
+      mxp_period = digitalSystem->readFilterPeriodMXP(filter_index, status);
+      printf("My error get %d index %d %d\n", *status, filter_index, mxp_period);
+    }
+  }
+  if (hdr_period != mxp_period) {
+    printf("Periods %d %d\n", hdr_period, mxp_period);
+    *status = NiFpga_Status_SoftwareFault;
+    return -1;
+  }
+  return hdr_period;
+}
+
+/**
+ * Read a digital I/O bit from the FPGA.
+ * Get a single value from a digital I/O channel.
+ *
+ * @param channel The digital I/O channel
+ * @return The state of the specified channel
+ */
+bool getDIO(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  tDIO::tDI currentDIO = digitalSystem->readDI(status);
+  //Shift 00000001 over channel-1 places.
+  //AND it against the currentDIO
+  //if it == 0, then return false
+  //else return true
+
+  if(port->port.pin < kNumHeaders) {
+    return ((currentDIO.Headers >> port->port.pin) & 1) != 0;
+  } else {
+    // Disable special functions
+    uint32_t bitToSet = 1 << remapMXPChannel(port->port.pin);
+    short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+    digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status);
+
+    return ((currentDIO.MXP >> remapMXPChannel(port->port.pin)) & 1) != 0;
+  }
+}
+
+/**
+ * Read the direction of a the Digital I/O lines
+ * A 1 bit means output and a 0 bit means input.
+ *
+ * @param channel The digital I/O channel
+ * @return The direction of the specified channel
+ */
+bool getDIODirection(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  tDIO::tOutputEnable currentOutputEnable = digitalSystem->readOutputEnable(status);
+	//Shift 00000001 over port->port.pin-1 places.
+  //AND it against the currentOutputEnable
+  //if it == 0, then return false
+  //else return true
+
+  if(port->port.pin < kNumHeaders) {
+    return ((currentOutputEnable.Headers >> port->port.pin) & 1) != 0;
+  } else {
+    return ((currentOutputEnable.MXP >> remapMXPChannel(port->port.pin)) & 1) != 0;
+  }
+}
+
+/**
+ * Generate a single pulse.
+ * Write a pulse to the specified digital output channel. There can only be a single pulse going at any time.
+ *
+ * @param channel The Digital Output channel that the pulse should be output on
+ * @param pulseLength The active length of the pulse (in seconds)
+ */
+void pulse(void* digital_port_pointer, double pulseLength, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  tDIO::tPulse pulse;
+
+  if(port->port.pin < kNumHeaders) {
+    pulse.Headers = 1 << port->port.pin;
+  } else {
+    pulse.MXP = 1 << remapMXPChannel(port->port.pin);
+  }
+
+  digitalSystem->writePulseLength((uint8_t)(1.0e9 * pulseLength / (pwmSystem->readLoopTiming(status) * 25)), status);
+  digitalSystem->writePulse(pulse, status);
+}
+
+/**
+ * Check a DIO line to see if it is currently generating a pulse.
+ *
+ * @return A pulse is in progress
+ */
+bool isPulsing(void* digital_port_pointer, int32_t *status) {
+  DigitalPort* port = (DigitalPort*) digital_port_pointer;
+  tDIO::tPulse pulseRegister = digitalSystem->readPulse(status);
+
+  if(port->port.pin < kNumHeaders) {
+    return (pulseRegister.Headers & (1 << port->port.pin)) != 0;
+  } else {
+    return (pulseRegister.MXP & (1 << remapMXPChannel(port->port.pin))) != 0;
+  }
+}
+
+/**
+ * Check if any DIO line is currently generating a pulse.
+ *
+ * @return A pulse on some line is in progress
+ */
+bool isAnyPulsing(int32_t *status) {
+  tDIO::tPulse pulseRegister = digitalSystem->readPulse(status);
+  return pulseRegister.Headers != 0 && pulseRegister.MXP != 0;
+}
+
+struct counter_t {
+  tCounter* counter;
+  uint32_t index;
+};
+typedef struct counter_t Counter;
+
+static Resource *counters = NULL;
+
+void* initializeCounter(Mode mode, uint32_t *index, int32_t *status) {
+	Resource::CreateResourceObject(&counters, tCounter::kNumSystems);
+	*index = counters->Allocate("Counter");
+	if (*index == ~0ul) {
+		*status = NO_AVAILABLE_RESOURCES;
+		return NULL;
+	}
+	Counter* counter = new Counter();
+	counter->counter = tCounter::create(*index, status);
+	counter->counter->writeConfig_Mode(mode, status);
+	counter->counter->writeTimerConfig_AverageSize(1, status);
+	counter->index = *index;
+	return counter;
+}
+
+void freeCounter(void* counter_pointer, int32_t *status) {
+  if (counter_pointer != NULL) {
+	  Counter* counter = (Counter*) counter_pointer;
+	  delete counter->counter;
+	  counters->Free(counter->index);
+  } else {
+	  *status = NULL_PARAMETER;
+  }
+}
+
+void setCounterAverageSize(void* counter_pointer, int32_t size, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeTimerConfig_AverageSize(size, status);
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ * Set the up counting DigitalSource.
+ */
+void setCounterUpSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+
+  uint8_t module;
+
+  if(pin >= kNumHeaders) {
+    pin = remapMXPChannel(pin);
+    module = 1;
+  } else {
+    module = 0;
+  }
+
+  counter->counter->writeConfig_UpSource_Module(module, status);
+  counter->counter->writeConfig_UpSource_Channel(pin, status);
+  counter->counter->writeConfig_UpSource_AnalogTrigger(analogTrigger, status);
+
+  if(counter->counter->readConfig_Mode(status) == kTwoPulse ||
+	 counter->counter->readConfig_Mode(status) == kExternalDirection) {
+	setCounterUpSourceEdge(counter_pointer, true, false, status);
+  }
+  counter->counter->strobeReset(status);
+}
+
+/**
+ * Set the edge sensitivity on an up counting source.
+ * Set the up source to either detect rising edges or falling edges.
+ */
+void setCounterUpSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_UpRisingEdge(risingEdge, status);
+  counter->counter->writeConfig_UpFallingEdge(fallingEdge, status);
+}
+
+/**
+ * Disable the up counting source to the counter.
+ */
+void clearCounterUpSource(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_UpFallingEdge(false, status);
+  counter->counter->writeConfig_UpRisingEdge(false, status);
+  // Index 0 of digital is always 0.
+  counter->counter->writeConfig_UpSource_Channel(0, status);
+  counter->counter->writeConfig_UpSource_AnalogTrigger(false, status);
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ * Set the down counting DigitalSource.
+ */
+void setCounterDownSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  unsigned char mode = counter->counter->readConfig_Mode(status);
+  if (mode != kTwoPulse && mode != kExternalDirection) {
+	// TODO: wpi_setWPIErrorWithContext(ParameterOutOfRange, "Counter only supports DownSource in TwoPulse and ExternalDirection modes.");
+	*status = PARAMETER_OUT_OF_RANGE;
+	return;
+  }
+
+  uint8_t module;
+
+  if(pin >= kNumHeaders) {
+    pin = remapMXPChannel(pin);
+    module = 1;
+  } else {
+    module = 0;
+  }
+
+  counter->counter->writeConfig_DownSource_Module(module, status);
+  counter->counter->writeConfig_DownSource_Channel(pin, status);
+  counter->counter->writeConfig_DownSource_AnalogTrigger(analogTrigger, status);
+
+  setCounterDownSourceEdge(counter_pointer, true, false, status);
+  counter->counter->strobeReset(status);
+}
+
+/**
+ * Set the edge sensitivity on a down counting source.
+ * Set the down source to either detect rising edges or falling edges.
+ */
+void setCounterDownSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_DownRisingEdge(risingEdge, status);
+  counter->counter->writeConfig_DownFallingEdge(fallingEdge, status);
+}
+
+/**
+ * Disable the down counting source to the counter.
+ */
+void clearCounterDownSource(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_DownFallingEdge(false, status);
+  counter->counter->writeConfig_DownRisingEdge(false, status);
+  // Index 0 of digital is always 0.
+  counter->counter->writeConfig_DownSource_Channel(0, status);
+  counter->counter->writeConfig_DownSource_AnalogTrigger(false, status);
+}
+
+/**
+ * Set standard up / down counting mode on this counter.
+ * Up and down counts are sourced independently from two inputs.
+ */
+void setCounterUpDownMode(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_Mode(kTwoPulse, 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 setCounterExternalDirectionMode(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_Mode(kExternalDirection, status);
+}
+
+/**
+ * Set Semi-period mode on this counter.
+ * Counts up on both rising and falling edges.
+ */
+void setCounterSemiPeriodMode(void* counter_pointer, bool highSemiPeriod, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_Mode(kSemiperiod, status);
+  counter->counter->writeConfig_UpRisingEdge(highSemiPeriod, status);
+  setCounterUpdateWhenEmpty(counter_pointer, false, 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 setCounterPulseLengthMode(void* counter_pointer, double threshold, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeConfig_Mode(kPulseLength, status);
+  counter->counter->writeConfig_PulseLengthThreshold((uint32_t)(threshold * 1.0e6) * kSystemClockTicksPerMicrosecond, 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)
+ */
+int32_t getCounterSamplesToAverage(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  return counter->counter->readTimerConfig_AverageSize(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 setCounterSamplesToAverage(void* counter_pointer, int samplesToAverage, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+	*status = PARAMETER_OUT_OF_RANGE;
+  }
+  counter->counter->writeTimerConfig_AverageSize(samplesToAverage, status);
+}
+
+/**
+ * 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 resetCounter(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->strobeReset(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 getCounter(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  int32_t value = counter->counter->readOutput_Value(status);
+  return value;
+}
+
+/*
+ * 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 of the last two pulses in units of seconds.
+ */
+double getCounterPeriod(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  tCounter::tTimerOutput output = counter->counter->readTimerOutput(status);
+  double period;
+  if (output.Stalled)	{
+	// Return infinity
+	double zero = 0.0;
+	period = 1.0 / zero;
+  } else {
+	// output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits)
+	period = (double)(output.Period << 1) / (double)output.Count;
+  }
+  return period * 2.5e-8;  // result * timebase (currently 40ns)
+}
+
+/**
+ * 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 setCounterMaxPeriod(void* counter_pointer, double maxPeriod, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeTimerConfig_StallPeriod((uint32_t)(maxPeriod * 4.0e8), 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).
+ */
+void setCounterUpdateWhenEmpty(void* counter_pointer, bool enabled, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  counter->counter->writeTimerConfig_UpdateWhenEmpty(enabled, 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 getCounterStopped(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  return counter->counter->readTimerOutput_Stalled(status);
+}
+
+/**
+ * The last direction the counter value changed.
+ * @return The last direction the counter value changed.
+ */
+bool getCounterDirection(void* counter_pointer, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  bool value = counter->counter->readOutput_Direction(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 setCounterReverseDirection(void* counter_pointer, bool reverseDirection, int32_t *status) {
+  Counter* counter = (Counter*) counter_pointer;
+  if (counter->counter->readConfig_Mode(status) == kExternalDirection) {
+	if (reverseDirection)
+	  setCounterDownSourceEdge(counter_pointer, true, true, status);
+	else
+	  setCounterDownSourceEdge(counter_pointer, false, true, status);
+  }
+}
+
+struct encoder_t {
+  tEncoder* encoder;
+  uint32_t index;
+};
+typedef struct encoder_t Encoder;
+
+static const double DECODING_SCALING_FACTOR = 0.25;
+static Resource *quadEncoders = NULL;
+
+void* initializeEncoder(uint8_t port_a_module, uint32_t port_a_pin, bool port_a_analog_trigger,
+						uint8_t port_b_module, uint32_t port_b_pin, bool port_b_analog_trigger,
+						bool reverseDirection, int32_t *index, int32_t *status) {
+
+  // Initialize encoder structure
+  Encoder* encoder = new Encoder();
+
+  if(port_a_pin >= kNumHeaders) {
+    port_a_pin = remapMXPChannel(port_a_pin);
+    port_a_module = 1;
+  }
+
+  if(port_b_pin >= kNumHeaders) {
+    port_b_pin = remapMXPChannel(port_b_pin);
+    port_b_module = 1;
+  }
+
+  Resource::CreateResourceObject(&quadEncoders, tEncoder::kNumSystems);
+  encoder->index = quadEncoders->Allocate("4X Encoder");
+  *index = encoder->index;
+  // TODO: if (index == ~0ul) { CloneError(quadEncoders); return; }
+  encoder->encoder = tEncoder::create(encoder->index, status);
+  encoder->encoder->writeConfig_ASource_Module(port_a_module, status);
+  encoder->encoder->writeConfig_ASource_Channel(port_a_pin, status);
+  encoder->encoder->writeConfig_ASource_AnalogTrigger(port_a_analog_trigger, status);
+  encoder->encoder->writeConfig_BSource_Module(port_b_module, status);
+  encoder->encoder->writeConfig_BSource_Channel(port_b_pin, status);
+  encoder->encoder->writeConfig_BSource_AnalogTrigger(port_b_analog_trigger, status);
+  encoder->encoder->strobeReset(status);
+  encoder->encoder->writeConfig_Reverse(reverseDirection, status);
+  encoder->encoder->writeTimerConfig_AverageSize(4, status);
+
+  return encoder;
+}
+
+void freeEncoder(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  quadEncoders->Free(encoder->index);
+  delete encoder->encoder;
+}
+
+/**
+ * Reset the Encoder distance to zero.
+ * Resets the current count to zero on the encoder.
+ */
+void resetEncoder(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  encoder->encoder->strobeReset(status);
+}
+
+/**
+ * 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 getEncoder(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  return encoder->encoder->readOutput_Value(status);
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compenstates 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 getEncoderPeriod(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  tEncoder::tTimerOutput output = encoder->encoder->readTimerOutput(status);
+  double value;
+  if (output.Stalled) {
+	// Return infinity
+	double zero = 0.0;
+	value = 1.0 / zero;
+  } else {
+	// output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits)
+	value = (double)(output.Period << 1) / (double)output.Count;
+  }
+  double measuredPeriod = value * 2.5e-8;
+  return measuredPeriod / DECODING_SCALING_FACTOR;
+}
+
+/**
+ * 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 setEncoderMaxPeriod(void* encoder_pointer, double maxPeriod, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  encoder->encoder->writeTimerConfig_StallPeriod((uint32_t)(maxPeriod * 4.0e8 * DECODING_SCALING_FACTOR), 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 getEncoderStopped(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  return encoder->encoder->readTimerOutput_Stalled(status) != 0;
+}
+
+/**
+ * The last direction the encoder value changed.
+ * @return The last direction the encoder value changed.
+ */
+bool getEncoderDirection(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  return encoder->encoder->readOutput_Direction(status);
+}
+
+/**
+ * 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 setEncoderReverseDirection(void* encoder_pointer, bool reverseDirection, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  encoder->encoder->writeConfig_Reverse(reverseDirection, 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 setEncoderSamplesToAverage(void* encoder_pointer, uint32_t samplesToAverage, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+	*status = PARAMETER_OUT_OF_RANGE;
+  }
+  encoder->encoder->writeTimerConfig_AverageSize(samplesToAverage, 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)
+ */
+uint32_t getEncoderSamplesToAverage(void* encoder_pointer, int32_t *status) {
+  Encoder* encoder = (Encoder*) encoder_pointer;
+  return encoder->encoder->readTimerConfig_AverageSize(status);
+}
+
+/**
+ * Get the loop timing of the PWM system
+ *
+ * @return The loop time
+ */
+uint16_t getLoopTiming(int32_t *status) {
+  return pwmSystem->readLoopTiming(status);
+}
+
+/*
+ * Initialize the spi port. Opens the port if necessary and saves the handle.
+ * If opening the MXP port, also sets up the pin functions appropriately
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiInitialize(uint8_t port, int32_t *status) {
+	if(spiSystem == NULL)
+		spiSystem = tSPI::create(status);
+	if(spiGetHandle(port) !=0 ) return;
+	switch(port){
+	case 0:
+		spiSetHandle(0, spilib_open("/dev/spidev0.0"));
+		break;
+	case 1:
+		spiSetHandle(1, spilib_open("/dev/spidev0.1"));
+		break;
+	case 2:
+		spiSetHandle(2, spilib_open("/dev/spidev0.2"));
+		break;
+	case 3:
+		spiSetHandle(3, spilib_open("/dev/spidev0.3"));
+		break;
+	case 4:
+		initializeDigital(status);
+		if(!allocateDIO(getPort(14), false, status)){printf("Failed to allocate DIO 14\n"); return;}
+		if(!allocateDIO(getPort(15), false, status)) {printf("Failed to allocate DIO 15\n"); return;}
+		if(!allocateDIO(getPort(16), true, status)) {printf("Failed to allocate DIO 16\n"); return;}
+		if(!allocateDIO(getPort(17), false, status)) {printf("Failed to allocate DIO 17\n"); return;}
+		digitalSystem->writeEnableMXPSpecialFunction(digitalSystem->readEnableMXPSpecialFunction(status)|0x00F0, status);
+		spiSetHandle(4, spilib_open("/dev/spidev1.0"));
+		break;
+	default:
+		break;
+	}
+	return;
+}
+
+/**
+ * Generic transaction.
+ *
+ * This is a lower-level interface to the spi hardware giving you more control over each transaction.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param dataToSend Buffer of data to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param size Number of bytes to transfer. [0..7]
+ * @return Number of bytes transferred, -1 for error
+ */
+int32_t spiTransaction(uint8_t port, uint8_t *dataToSend, uint8_t *dataReceived, uint8_t size)
+{
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	return spilib_writeread(spiGetHandle(port), (const char*) dataToSend, (char*) dataReceived, (int32_t) size);
+}
+
+/**
+ * Execute a write transaction with the device.
+ *
+ * Write to a device and wait until the transaction is complete.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param datToSend The data to write to the register on the device.
+ * @param sendSize The number of bytes to be written
+ * @return The number of bytes written. -1 for an error
+ */
+int32_t spiWrite(uint8_t port, uint8_t* dataToSend, uint8_t sendSize)
+{
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	return spilib_write(spiGetHandle(port), (const char*) dataToSend, (int32_t) sendSize);
+}
+
+/**
+ * Execute a read from the device.
+ *
+ *   This methdod does not write any data out to the device
+ *   Most spi devices will require a register address to be written before
+ *   they begin returning data
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @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. [1..7]
+ * @return Number of bytes read. -1 for error.
+ */
+int32_t spiRead(uint8_t port, uint8_t *buffer, uint8_t count)
+{
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	return spilib_read(spiGetHandle(port), (char*) buffer, (int32_t) count);
+}
+
+/**
+ * Close the SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiClose(uint8_t port) {
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	spilib_close(spiGetHandle(port));
+	spiSetHandle(port, 0);
+	return;
+}
+
+/**
+ * Set the clock speed for the SPI bus.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param speed The speed in Hz (0-1MHz)
+ */
+void spiSetSpeed(uint8_t port, uint32_t speed) {
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	spilib_setspeed(spiGetHandle(port), speed);
+}
+
+/**
+ * Set the SPI options
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param msb_first True to write the MSB first, False for LSB first
+ * @param sample_on_trailing True to sample on the trailing edge, False to sample on the leading edge
+ * @param clk_idle_high True to set the clock to active low, False to set the clock active high
+ */
+void spiSetOpts(uint8_t port, int msb_first, int sample_on_trailing, int clk_idle_high) {
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	spilib_setopts(spiGetHandle(port), msb_first, sample_on_trailing, clk_idle_high);
+}
+
+/**
+ * Set the CS Active high for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiSetChipSelectActiveHigh(uint8_t port, int32_t *status){
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	if(port < 4)
+	{
+		spiSystem->writeChipSelectActiveHigh_Hdr(spiSystem->readChipSelectActiveHigh_Hdr(status) | (1<<port), status);
+	}
+	else
+	{
+		spiSystem->writeChipSelectActiveHigh_MXP(1, status);
+	}
+}
+
+/**
+ * Set the CS Active low for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiSetChipSelectActiveLow(uint8_t port, int32_t *status){
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	if(port < 4)
+	{
+		spiSystem->writeChipSelectActiveHigh_Hdr(spiSystem->readChipSelectActiveHigh_Hdr(status) & ~(1<<port), status);
+	}
+	else
+	{
+		spiSystem->writeChipSelectActiveHigh_MXP(0, status);
+	}
+}
+
+/**
+ * Get the stored handle for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @return The stored handle for the SPI port. 0 represents no stored handle.
+ */
+int32_t spiGetHandle(uint8_t port){
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	switch(port){
+	case 0:
+		return m_spiCS0Handle;
+	case 1:
+		return m_spiCS1Handle;
+	case 2:
+		return m_spiCS2Handle;
+	case 3:
+		return m_spiCS3Handle;
+	case 4:
+		return m_spiMXPHandle;
+	default:
+		return 0;
+	}
+}
+
+/**
+ * Set the stored handle for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP.
+ * @param handle The value of the handle for the port.
+ */
+void spiSetHandle(uint8_t port, int32_t handle){
+	::std::unique_lock<ReentrantMutex> sync(spiGetSemaphore(port));
+	switch(port){
+	case 0:
+		m_spiCS0Handle = handle;
+		break;
+	case 1:
+		m_spiCS1Handle = handle;
+		break;
+	case 2:
+		m_spiCS2Handle = handle;
+		break;
+	case 3:
+		m_spiCS3Handle = handle;
+		break;
+	case 4:
+		m_spiMXPHandle = handle;
+		break;
+	default:
+		break;
+	}
+}
+
+/**
+ * Get the semaphore for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @return The semaphore for the SPI port.
+ */
+ReentrantMutex& spiGetSemaphore(uint8_t port) {
+	if(port < 4)
+		return spiOnboardSemaphore;
+	else
+		return spiMXPSemaphore;
+}
+
+/*
+ * Initialize the I2C port. Opens the port if necessary and saves the handle.
+ * If opening the MXP port, also sets up the pin functions appropriately
+ * @param port The port to open, 0 for the on-board, 1 for the MXP.
+ */
+void i2CInitialize(uint8_t port, int32_t *status) {
+	initializeDigital(status);
+
+	if(port > 1)
+	{
+		//Set port out of range error here
+		return;
+	}
+
+	ReentrantMutex &lock = port == 0 ? digitalI2COnBoardSemaphore : digitalI2CMXPSemaphore;
+	{
+    ::std::unique_lock<ReentrantMutex> sync(lock);
+		if(port == 0) {
+			i2COnboardObjCount++;
+			if (i2COnBoardHandle > 0) return;
+			i2COnBoardHandle = i2clib_open("/dev/i2c-2");
+		} else if(port == 1) {
+			i2CMXPObjCount++;
+			if (i2CMXPHandle > 0) return;
+			if(!allocateDIO(getPort(24), false, status)) return;
+			if(!allocateDIO(getPort(25), false, status)) return;
+			digitalSystem->writeEnableMXPSpecialFunction(digitalSystem->readEnableMXPSpecialFunction(status)|0xC000, status);
+			i2CMXPHandle = i2clib_open("/dev/i2c-1");
+		}
+	return;
+	}
+}
+
+/**
+ * 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. [0..6]
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize Number of bytes to read from the device. [0..7]
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+int32_t i2CTransaction(uint8_t port, uint8_t deviceAddress, uint8_t *dataToSend, uint8_t sendSize, uint8_t *dataReceived, uint8_t receiveSize)
+{
+	if(port > 1) {
+		//Set port out of range error here
+		return -1;
+	}
+	/*if (sendSize > 6) // Optional, provides better error message.	TODO: Are these limits still right? Implement error. Check for null buffer
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "sendSize");
+		return true;
+	}
+	if (receiveSize > 7) // Optional, provides better error message.
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "receiveSize");
+		return true;
+	}*/
+	int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+	ReentrantMutex &lock = port == 0 ? digitalI2COnBoardSemaphore : digitalI2CMXPSemaphore;
+
+	{
+    ::std::unique_lock<ReentrantMutex> sync(lock);
+		return i2clib_writeread(handle, deviceAddress, (const char*) dataToSend, (int32_t) sendSize, (char*) dataReceived, (int32_t) receiveSize);
+	}
+}
+
+/**
+ * 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.
+ */
+int32_t i2CWrite(uint8_t port, uint8_t deviceAddress, uint8_t* dataToSend, uint8_t sendSize)
+{
+	if(port > 1) {
+		//Set port out of range error here
+		return -1;
+	}
+	/*if (sendSize > 6) // Optional, provides better error message.	TODO: Are these limits still right? Implement error. Check for null buffer
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "sendSize");
+		return true;
+	}*/
+	int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+	ReentrantMutex &lock = port == 0 ? digitalI2COnBoardSemaphore : digitalI2CMXPSemaphore;
+	{
+    ::std::unique_lock<ReentrantMutex> sync(lock);
+		return i2clib_write(handle, deviceAddress, (const char*) dataToSend, (int32_t) sendSize);
+	}
+}
+
+/**
+ * Execute a read transaction with the device.
+ *
+ * Read 1 to 7 bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally
+ *   allowing you to read up to 7 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. [1..7]
+ * @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.
+ */
+int32_t i2CRead(uint8_t port, uint8_t deviceAddress, uint8_t *buffer, uint8_t count)
+{
+	if(port > 1) {
+		//Set port out of range error here
+		return -1;
+	}
+	/*	if (count < 1 || count > 7) Todo: Are these limits still right? Implement error
+		{
+			wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+			return true;
+		}
+		if (buffer == NULL)
+		{
+			wpi_setWPIErrorWithContext(NullParameter, "buffer");
+			return true;
+		}*/
+	int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+	ReentrantMutex &lock = port == 0 ? digitalI2COnBoardSemaphore : digitalI2CMXPSemaphore;
+	{
+    ::std::unique_lock<ReentrantMutex> sync(lock);
+		return i2clib_read(handle, deviceAddress, (char*) buffer, (int32_t) count);
+	}
+
+}
+
+void i2CClose(uint8_t port) {
+	if(port > 1) {
+		//Set port out of range error here
+		return;
+	}
+	ReentrantMutex &lock = port == 0 ? digitalI2COnBoardSemaphore : digitalI2CMXPSemaphore;
+	{
+    ::std::unique_lock<ReentrantMutex> sync(lock);
+		if((port == 0 ? i2COnboardObjCount--:i2CMXPObjCount--) == 0) {
+			int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+			i2clib_close(handle);
+		}
+	}
+	return;
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/FRC_FPGA_ChipObject_Aliases.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/FRC_FPGA_ChipObject_Aliases.h
new file mode 100644
index 0000000..d9fba25
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/FRC_FPGA_ChipObject_Aliases.h
@@ -0,0 +1,10 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __FRC_FPGA_ChipObject_Aliases_h__

+#define __FRC_FPGA_ChipObject_Aliases_h__

+

+#define nRuntimeFPGANamespace nFRC_2012_1_6_4

+#define nInvariantFPGANamespace nFRC_C0EF_1_1_0

+

+#endif // __FRC_FPGA_ChipObject_Aliases_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h
new file mode 100644
index 0000000..7bae082
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h
@@ -0,0 +1,9 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __RoboRIO_FRC_ChipObject_Aliases_h__

+#define __RoboRIO_FRC_ChipObject_Aliases_h__

+

+#define nRoboRIO_FPGANamespace nFRC_2015_1_0_A

+

+#endif // __RoboRIO_FRC_ChipObject_Aliases_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h
new file mode 100644
index 0000000..27b0665
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h
@@ -0,0 +1,2450 @@
+/*

+ * FPGA Interface C API 14.0 header file.

+ *

+ * Copyright (c) 2014,

+ * National Instruments Corporation.

+ * All rights reserved.

+ */

+

+#ifndef __NiFpga_h__

+#define __NiFpga_h__

+

+/*

+ * Determine platform details.

+ */

+#if defined(_M_IX86) \

+ || defined(_M_X64) \

+ || defined(_M_AMD64) \

+ || defined(i386) \

+ || defined(__i386) \

+ || defined(__i386__) \

+ || defined(__i486__) \

+ || defined(__i586__) \

+ || defined(__i686__) \

+ || defined(__amd64__) \

+ || defined(__amd64) \

+ || defined(__x86_64__) \

+ || defined(__x86_64) \

+ || defined(__IA32__) \

+ || defined(_X86_) \

+ || defined(__THW_INTEL__) \

+ || defined(__I86__) \

+ || defined(__INTEL__) \

+ || defined(__X86__) \

+ || defined(__386__) \

+ || defined(__I86__) \

+ || defined(M_I386) \

+ || defined(M_I86) \

+ || defined(_M_I386) \

+ || defined(_M_I86)

+   #if defined(_WIN32) \

+    || defined(_WIN64) \

+    || defined(__WIN32__) \

+    || defined(__TOS_WIN__) \

+    || defined(__WINDOWS__) \

+    || defined(_WINDOWS) \

+    || defined(__WINDOWS_386__) \

+    || defined(__CYGWIN__)

+      /* Either Windows or Phar Lap ETS. */

+      #define NiFpga_Windows 1

+   #elif defined(__linux__) \

+      || defined(__linux) \

+      || defined(linux) \

+      || defined(__gnu_linux__)

+      #define NiFpga_Linux 1

+   #elif defined(__APPLE__) && defined(__MACH__)

+      #define NiFpga_MacOsX 1

+   #else

+      #error Unsupported OS.

+   #endif

+#elif defined(__powerpc) \

+   || defined(__powerpc__) \

+   || defined(__POWERPC__) \

+   || defined(__ppc__) \

+   || defined(__PPC) \

+   || defined(_M_PPC) \

+   || defined(_ARCH_PPC) \

+   || defined(__PPC__) \

+   || defined(__ppc)

+   #if defined(__vxworks)

+      #define NiFpga_VxWorks 1

+   #else

+      #error Unsupported OS.

+   #endif

+#elif defined(__arm__) \

+   || defined(__thumb__) \

+   || defined(__TARGET_ARCH_ARM) \

+   || defined(__TARGET_ARCH_THUMB) \

+   || defined(_ARM) \

+   || defined(_M_ARM) \

+   || defined(_M_ARMT)

+#if defined(__linux__) \

+ || defined(__linux) \

+ || defined(linux) \

+ || defined(__gnu_linux__)

+   #define NiFpga_Linux 1

+#else

+      #error Unsupported OS.

+   #endif

+#else

+   #error Unsupported architecture.

+#endif

+

+/*

+ * Determine compiler.

+ */

+#if defined(_MSC_VER)

+   #define NiFpga_Msvc 1

+#elif defined(__GNUC__)

+   #define NiFpga_Gcc 1

+#elif defined(_CVI_) && !defined(_TPC_)

+   #define NiFpga_Cvi 1

+   /* Enables CVI Library Protection Errors. */

+   #pragma EnableLibraryRuntimeChecking

+#else

+   /* Unknown compiler. */

+#endif

+

+/*

+ * Determine compliance with different C/C++ language standards.

+ */

+#if defined(__cplusplus)

+   #define NiFpga_Cpp 1

+   #if __cplusplus >= 199707L

+      #define NiFpga_Cpp98 1

+      #if __cplusplus >= 201103L

+         #define NiFpga_Cpp11 1

+      #endif

+   #endif

+#endif

+#if defined(__STDC__)

+   #define NiFpga_C89 1

+   #if defined(__STDC_VERSION__)

+      #define NiFpga_C90 1

+      #if __STDC_VERSION__ >= 199409L

+         #define NiFpga_C94 1

+         #if __STDC_VERSION__ >= 199901L

+            #define NiFpga_C99 1

+            #if __STDC_VERSION__ >= 201112L

+               #define NiFpga_C11 1

+            #endif

+         #endif

+      #endif

+   #endif

+#endif

+

+/*

+ * Determine ability to inline functions.

+ */

+#if NiFpga_Cpp || NiFpga_C99

+   /* The inline keyword exists in C++ and C99. */

+#define NiFpga_Inline inline

+#elif NiFpga_Msvc

+   /* Visual C++ (at least since 6.0) also supports an alternate keyword. */

+   #define NiFpga_Inline __inline

+#elif NiFpga_Gcc

+   /* GCC (at least since 2.95.2) also supports an alternate keyword. */

+   #define NiFpga_Inline __inline__

+#elif !defined(NiFpga_Inline)

+   /*

+    * Disable inlining if inline support is unknown. To manually enable

+    * inlining, #define the following macro before #including NiFpga.h:

+    *

+    *    #define NiFpga_Inline inline

+    */

+   #define NiFpga_Inline

+#endif

+

+/*

+ * Define exact-width integer types, if they have not already been defined.

+ */

+#if NiFpga_ExactWidthIntegerTypesDefined \

+ || defined(_STDINT) \

+ || defined(_STDINT_H) \

+ || defined(_STDINT_H_) \

+ || defined(_INTTYPES_H) \

+ || defined(_INTTYPES_H_) \

+ || defined(_SYS_STDINT_H) \

+ || defined(_SYS_STDINT_H_) \

+ || defined(_SYS_INTTYPES_H) \

+ || defined(_SYS_INTTYPES_H_) \

+ || defined(_STDINT_H_INCLUDED) \

+ || defined(_MSC_STDINT_H_) \

+ || defined(_PSTDINT_H_INCLUDED)

+   /* Assume that exact-width integer types have already been defined. */

+#elif NiFpga_VxWorks

+   /* VxWorks (at least 6.3 and earlier) did not have stdint.h. */

+   #include <types/vxTypes.h>

+#elif NiFpga_C99 \

+   || NiFpga_Gcc /* GCC (at least since 3.0) has a stdint.h. */ \

+   || defined(HAVE_STDINT_H)

+   /* Assume that stdint.h can be included. */

+   #include <stdint.h>

+#elif NiFpga_Msvc \

+   || NiFpga_Cvi

+   /* Manually define exact-width integer types. */

+   typedef   signed    char  int8_t;

+   typedef unsigned    char uint8_t;

+   typedef            short  int16_t;

+   typedef unsigned   short uint16_t;

+   typedef              int  int32_t;

+   typedef unsigned     int uint32_t;

+   typedef          __int64  int64_t;

+   typedef unsigned __int64 uint64_t;

+#else

+   /*

+    * Exact-width integer types must be defined by the user, and the following

+    * macro must be #defined, before #including NiFpga.h:

+    *

+    *    #define NiFpga_ExactWidthIntegerTypesDefined 1

+    */

+   #error Exact-width integer types must be defined by the user. See comment.

+#endif

+

+/* Included for definition of size_t. */

+#include <stddef.h>

+

+#if NiFpga_Cpp

+extern "C"

+{

+#endif

+

+/**

+ * A boolean value; either NiFpga_False or NiFpga_True.

+ */

+typedef uint8_t NiFpga_Bool;

+

+/**

+ * Represents a false condition.

+ */

+static const NiFpga_Bool NiFpga_False = 0;

+

+/**

+ * Represents a true condition.

+ */

+static const NiFpga_Bool NiFpga_True = 1;

+

+/**

+ * Represents the resulting status of a function call through its return value.

+ * 0 is success, negative values are errors, and positive values are warnings.

+ */

+typedef int32_t NiFpga_Status;

+

+/**

+ * No errors or warnings.

+ */

+static const NiFpga_Status NiFpga_Status_Success = 0;

+

+/**

+ * The timeout expired before the FIFO operation could complete.

+ */

+static const NiFpga_Status NiFpga_Status_FifoTimeout = -50400;

+

+/**

+ * No transfer is in progress because the transfer was aborted by the client.

+ * The operation could not be completed as specified.

+ */

+static const NiFpga_Status NiFpga_Status_TransferAborted = -50405;

+

+/**

+ * A memory allocation failed. Try again after rebooting.

+ */

+static const NiFpga_Status NiFpga_Status_MemoryFull = -52000;

+

+/**

+ * An unexpected software error occurred.

+ */

+static const NiFpga_Status NiFpga_Status_SoftwareFault = -52003;

+

+/**

+ * A parameter to a function was not valid. This could be a NULL pointer, a bad

+ * value, etc.

+ */

+static const NiFpga_Status NiFpga_Status_InvalidParameter = -52005;

+

+/**

+ * A required resource was not found. The NiFpga.* library, the RIO resource, or

+ * some other resource may be missing.

+ */

+static const NiFpga_Status NiFpga_Status_ResourceNotFound = -52006;

+

+/**

+ * A required resource was not properly initialized. This could occur if

+ * NiFpga_Initialize was not called or a required NiFpga_IrqContext was not

+ * reserved.

+ */

+static const NiFpga_Status NiFpga_Status_ResourceNotInitialized = -52010;

+

+/**

+ * A hardware failure has occurred. The operation could not be completed as

+ * specified.

+ */

+static const NiFpga_Status NiFpga_Status_HardwareFault = -52018;

+

+/**

+ * The FPGA is already running.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaAlreadyRunning = -61003;

+

+/**

+ * An error occurred downloading the VI to the FPGA device. Verify that

+ * the target is connected and powered and that the resource of the target

+ * is properly configured.

+ */

+static const NiFpga_Status NiFpga_Status_DownloadError = -61018;

+

+/**

+ * The bitfile was not compiled for the specified resource's device type.

+ */

+static const NiFpga_Status NiFpga_Status_DeviceTypeMismatch = -61024;

+

+/**

+ * An error was detected in the communication between the host computer and the

+ * FPGA target.

+ */

+static const NiFpga_Status NiFpga_Status_CommunicationTimeout = -61046;

+

+/**

+ * The timeout expired before any of the IRQs were asserted.

+ */

+static const NiFpga_Status NiFpga_Status_IrqTimeout = -61060;

+

+/**

+ * The specified bitfile is invalid or corrupt.

+ */

+static const NiFpga_Status NiFpga_Status_CorruptBitfile = -61070;

+

+/**

+ * The requested FIFO depth is invalid. It is either 0 or an amount not

+ * supported by the hardware.

+ */

+static const NiFpga_Status NiFpga_Status_BadDepth = -61072;

+

+/**

+ * The number of FIFO elements is invalid. Either the number is greater than the

+ * depth of the host memory DMA FIFO, or more elements were requested for

+ * release than had been acquired.

+ */

+static const NiFpga_Status NiFpga_Status_BadReadWriteCount = -61073;

+

+/**

+ * A hardware clocking error occurred. A derived clock lost lock with its base

+ * clock during the execution of the LabVIEW FPGA VI. If any base clocks with

+ * derived clocks are referencing an external source, make sure that the

+ * external source is connected and within the supported frequency, jitter,

+ * accuracy, duty cycle, and voltage specifications. Also verify that the

+ * characteristics of the base clock match the configuration specified in the

+ * FPGA Base Clock Properties. If all base clocks with derived clocks are

+ * generated from free-running, on-board sources, please contact National

+ * Instruments technical support at ni.com/support.

+ */

+static const NiFpga_Status NiFpga_Status_ClockLostLock = -61083;

+

+/**

+ * The operation could not be performed because the FPGA is busy. Stop all

+ * activities on the FPGA before requesting this operation. If the target is in

+ * Scan Interface programming mode, put it in FPGA Interface programming mode.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaBusy = -61141;

+

+/**

+ * The operation could not be performed because the FPGA is busy operating in

+ * FPGA Interface C API mode. Stop all activities on the FPGA before requesting

+ * this operation.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterfaceCApi = -61200;

+

+/**

+ * The chassis is in Scan Interface programming mode. In order to run FPGA VIs,

+ * you must go to the chassis properties page, select FPGA programming mode, and

+ * deploy settings.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaBusyScanInterface = -61201;

+

+/**

+ * The operation could not be performed because the FPGA is busy operating in

+ * FPGA Interface mode. Stop all activities on the FPGA before requesting this

+ * operation.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterface = -61202;

+

+/**

+ * The operation could not be performed because the FPGA is busy operating in

+ * Interactive mode. Stop all activities on the FPGA before requesting this

+ * operation.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaBusyInteractive = -61203;

+

+/**

+ * The operation could not be performed because the FPGA is busy operating in

+ * Emulation mode. Stop all activities on the FPGA before requesting this

+ * operation.

+ */

+static const NiFpga_Status NiFpga_Status_FpgaBusyEmulation = -61204;

+

+/**

+ * LabVIEW FPGA does not support the Reset method for bitfiles that allow

+ * removal of implicit enable signals in single-cycle Timed Loops.

+ */

+static const NiFpga_Status NiFpga_Status_ResetCalledWithImplicitEnableRemoval = -61211;

+

+/**

+ * LabVIEW FPGA does not support the Abort method for bitfiles that allow

+ * removal of implicit enable signals in single-cycle Timed Loops.

+ */

+static const NiFpga_Status NiFpga_Status_AbortCalledWithImplicitEnableRemoval = -61212;

+

+/**

+ * LabVIEW FPGA does not support Close and Reset if Last Reference for bitfiles

+ * that allow removal of implicit enable signals in single-cycle Timed Loops.

+ * Pass the NiFpga_CloseAttribute_NoResetIfLastSession attribute to NiFpga_Close

+ * instead of 0.

+ */

+static const NiFpga_Status NiFpga_Status_CloseAndResetCalledWithImplicitEnableRemoval = -61213;

+

+/**

+ * For bitfiles that allow removal of implicit enable signals in single-cycle

+ * Timed Loops, LabVIEW FPGA does not support this method prior to running the

+ * bitfile.

+ */

+static const NiFpga_Status NiFpga_Status_ImplicitEnableRemovalButNotYetRun = -61214;

+

+/**

+ * Bitfiles that allow removal of implicit enable signals in single-cycle Timed

+ * Loops can run only once. Download the bitfile again before re-running the VI.

+ */

+static const NiFpga_Status NiFpga_Status_RunAfterStoppedCalledWithImplicitEnableRemoval = -61215;

+

+/**

+ * A gated clock has violated the handshaking protocol. If you are using

+ * external gated clocks, ensure that they follow the required clock gating

+ * protocol. If you are generating your clocks internally, please contact

+ * National Instruments Technical Support.

+ */

+static const NiFpga_Status NiFpga_Status_GatedClockHandshakingViolation = -61216;

+

+/**

+ * The number of elements requested must be less than or equal to the number of

+ * unacquired elements left in the host memory DMA FIFO. There are currently

+ * fewer unacquired elements left in the FIFO than are being requested. Release

+ * some acquired elements before acquiring more elements.

+ */

+static const NiFpga_Status NiFpga_Status_ElementsNotPermissibleToBeAcquired = -61219;

+

+/**

+ * An unexpected internal error occurred.

+ */

+static const NiFpga_Status NiFpga_Status_InternalError = -61499;

+

+/**

+ * The NI-RIO driver was unable to allocate memory for a FIFO. This can happen

+ * when the combined depth of all DMA FIFOs exceeds the maximum depth for the

+ * controller, or when the controller runs out of system memory. You may be able

+ * to reconfigure the controller with a greater maximum FIFO depth. For more

+ * information, refer to the NI KnowledgeBase article 65OF2ERQ.

+ */

+static const NiFpga_Status NiFpga_Status_TotalDmaFifoDepthExceeded = -63003;

+

+/**

+ * Access to the remote system was denied. Use MAX to check the Remote Device

+ * Access settings under Software>>NI-RIO>>NI-RIO Settings on the remote system.

+ */

+static const NiFpga_Status NiFpga_Status_AccessDenied = -63033;

+

+/**

+ * The NI-RIO software on the host is not compatible with the software on the

+ * target. Upgrade the NI-RIO software on the host in order to connect to this

+ * target.

+ */

+static const NiFpga_Status NiFpga_Status_HostVersionMismatch = -63038;

+

+/**

+ * A connection could not be established to the specified remote device. Ensure

+ * that the device is on and accessible over the network, that NI-RIO software

+ * is installed, and that the RIO server is running and properly configured.

+ */

+static const NiFpga_Status NiFpga_Status_RpcConnectionError = -63040;

+

+/**

+ * The RPC session is invalid. The target may have reset or been rebooted. Check

+ * the network connection and retry the operation.

+ */

+static const NiFpga_Status NiFpga_Status_RpcSessionError = -63043;

+

+/**

+ * The operation could not complete because another session is accessing the

+ * FIFO. Close the other session and retry.

+ */

+static const NiFpga_Status NiFpga_Status_FifoReserved = -63082;

+

+/**

+ * A Configure FIFO, Stop FIFO, Read FIFO, or Write FIFO function was called

+ * while the host had acquired elements of the FIFO. Release all acquired

+ * elements before configuring, stopping, reading, or writing.

+ */

+static const NiFpga_Status NiFpga_Status_FifoElementsCurrentlyAcquired = -63083;

+

+/**

+ * A function was called using a misaligned address. The address must be a

+ * multiple of the size of the datatype.

+ */

+static const NiFpga_Status NiFpga_Status_MisalignedAccess = -63084;

+

+/**

+ * The FPGA Read/Write Control Function is accessing a control or indicator

+ * with data that exceeds the maximum size supported on the current target.

+ * Refer to the hardware documentation for the limitations on data types for

+ * this target.

+ */

+static const NiFpga_Status NiFpga_Status_ControlOrIndicatorTooLarge = -63085;

+

+/**

+ * A valid .lvbitx bitfile is required. If you are using a valid .lvbitx

+ * bitfile, the bitfile may not be compatible with the software you are using.

+ * Determine which version of LabVIEW was used to make the bitfile, update your

+ * software to that version or later, and try again.

+ */

+static const NiFpga_Status NiFpga_Status_BitfileReadError = -63101;

+

+/**

+ * The specified signature does not match the signature of the bitfile. If the

+ * bitfile has been recompiled, regenerate the C API and rebuild the

+ * application.

+ */

+static const NiFpga_Status NiFpga_Status_SignatureMismatch = -63106;

+

+/**

+ * The bitfile you are trying to use is not compatible with the version of

+ * NI-RIO installed on the target and/or the host. Determine which versions of

+ * NI-RIO and LabVIEW were used to make the bitfile, update the software on the

+ * target and host to that version or later, and try again.

+ */

+static const NiFpga_Status NiFpga_Status_IncompatibleBitfile = -63107;

+

+/**

+ * Either the supplied resource name is invalid as a RIO resource name, or the

+ * device was not found. Use MAX to find the proper resource name for the

+ * intended device.

+ */

+static const NiFpga_Status NiFpga_Status_InvalidResourceName = -63192;

+

+/**

+ * The requested feature is not supported.

+ */

+static const NiFpga_Status NiFpga_Status_FeatureNotSupported = -63193;

+

+/**

+ * The NI-RIO software on the target system is not compatible with this

+ * software. Upgrade the NI-RIO software on the target system.

+ */

+static const NiFpga_Status NiFpga_Status_VersionMismatch = -63194;

+

+/**

+ * The session is invalid or has been closed.

+ */

+static const NiFpga_Status NiFpga_Status_InvalidSession = -63195;

+

+/**

+ * The maximum number of open FPGA sessions has been reached. Close some open

+ * sessions.

+ */

+static const NiFpga_Status NiFpga_Status_OutOfHandles = -63198;

+

+/**

+ * Tests whether a status is an error.

+ *

+ * @param status status to check for an error

+ * @return whether the status was an error

+ */

+static NiFpga_Inline NiFpga_Bool NiFpga_IsError(const NiFpga_Status status)

+{

+   return status < NiFpga_Status_Success;

+}

+

+/**

+ * Tests whether a status is not an error. Success and warnings are not errors.

+ *

+ * @param status status to check for an error

+ * @return whether the status was a success or warning

+ */

+static NiFpga_Inline NiFpga_Bool NiFpga_IsNotError(const NiFpga_Status status)

+{

+   return status >= NiFpga_Status_Success;

+}

+

+/**

+ * Conditionally sets the status to a new value. The previous status is

+ * preserved unless the new status is more of an error, which means that

+ * warnings and errors overwrite successes, and errors overwrite warnings. New

+ * errors do not overwrite older errors, and new warnings do not overwrite

+ * older warnings.

+ *

+ * @param status status to conditionally set

+ * @param newStatus new status value that may be set

+ * @return the resulting status

+ */

+static NiFpga_Inline NiFpga_Status NiFpga_MergeStatus(

+                                               NiFpga_Status* const status,

+                                               const NiFpga_Status  newStatus)

+{

+   if (!status)

+      return NiFpga_Status_InvalidParameter;

+   if (NiFpga_IsNotError(*status)

+   &&  (*status == NiFpga_Status_Success || NiFpga_IsError(newStatus)))

+      *status = newStatus;

+   return *status;

+}

+

+/**

+ * This macro evaluates the expression only if the status is not an error. The

+ * expression must evaluate to an NiFpga_Status, such as a call to any NiFpga_*

+ * function, because the status will be set to the returned status if the

+ * expression is evaluated.

+ *

+ * You can use this macro to mimic status chaining in LabVIEW, where the status

+ * does not have to be explicitly checked after each call. Such code may look

+ * like the following example.

+ *

+ *    NiFpga_Status status = NiFpga_Status_Success;

+ *    NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));

+ *    NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));

+ *    NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));

+ *

+ * @param status status to check for an error

+ * @param expression expression to call if the incoming status is not an error

+ */

+#define NiFpga_IfIsNotError(status, expression) \

+   if (NiFpga_IsNotError(status)) \

+      NiFpga_MergeStatus(&status, (expression)); \

+

+/**

+ * You must call this function before all other function calls. This function

+ * loads the NiFpga library so that all the other functions will work. If this

+ * function succeeds, you must call NiFpga_Finalize after all other function

+ * calls.

+ *

+ * @warning This function is not thread safe.

+ *

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Initialize(void);

+

+/**

+ * You must call this function after all other function calls if

+ * NiFpga_Initialize succeeds. This function unloads the NiFpga library.

+ *

+ * @warning This function is not thread safe.

+ *

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Finalize(void);

+

+/**

+ * A handle to an FPGA session.

+ */

+typedef uint32_t NiFpga_Session;

+

+/**

+ * Attributes that NiFpga_Open accepts.

+ */

+typedef enum

+{

+   NiFpga_OpenAttribute_NoRun = 1

+} NiFpga_OpenAttribute;

+

+/**

+ * Opens a session to the FPGA. This call ensures that the contents of the

+ * bitfile are programmed to the FPGA. The FPGA runs unless the

+ * NiFpga_OpenAttribute_NoRun attribute is used.

+ *

+ * Because different operating systems have different default current working

+ * directories for applications, you must pass an absolute path for the bitfile

+ * parameter. If you pass only the filename instead of an absolute path, the

+ * operating system may not be able to locate the bitfile. For example, the

+ * default current working directories are C:\ni-rt\system\ for Phar Lap ETS and

+ * /c/ for VxWorks. Because the generated *_Bitfile constant is a #define to a

+ * string literal, you can use C/C++ string-literal concatenation to form an

+ * absolute path. For example, if the bitfile is in the root directory of a

+ * Phar Lap ETS system, pass the following for the bitfile parameter.

+ *

+ *    "C:\\" NiFpga_MyApplication_Bitfile

+ *

+ * @param bitfile path to the bitfile

+ * @param signature signature of the bitfile

+ * @param resource RIO resource string to open ("RIO0" or "rio://mysystem/RIO")

+ * @param attribute bitwise OR of any NiFpga_OpenAttributes, or 0

+ * @param session outputs the session handle, which must be closed when no

+ *                longer needed

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Open(const char*     bitfile,

+                          const char*     signature,

+                          const char*     resource,

+                          uint32_t        attribute,

+                          NiFpga_Session* session);

+

+/**

+ * Attributes that NiFpga_Close accepts.

+ */

+typedef enum

+{

+   NiFpga_CloseAttribute_NoResetIfLastSession = 1

+} NiFpga_CloseAttribute;

+

+/**

+ * Closes the session to the FPGA. The FPGA resets unless either another session

+ * is still open or you use the NiFpga_CloseAttribute_NoResetIfLastSession

+ * attribute.

+ *

+ * @param session handle to a currently open session

+ * @param attribute bitwise OR of any NiFpga_CloseAttributes, or 0

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Close(NiFpga_Session session,

+                           uint32_t       attribute);

+

+/**

+ * Attributes that NiFpga_Run accepts.

+ */

+typedef enum

+{

+   NiFpga_RunAttribute_WaitUntilDone = 1

+} NiFpga_RunAttribute;

+

+/**

+ * Runs the FPGA VI on the target. If you use NiFpga_RunAttribute_WaitUntilDone,

+ * NiFpga_Run blocks the thread until the FPGA finishes running.

+ *

+ * @param session handle to a currently open session

+ * @param attribute bitwise OR of any NiFpga_RunAttributes, or 0

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Run(NiFpga_Session session,

+                         uint32_t       attribute);

+

+/**

+ * Aborts the FPGA VI.

+ *

+ * @param session handle to a currently open session

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Abort(NiFpga_Session session);

+

+/**

+ * Resets the FPGA VI.

+ *

+ * @param session handle to a currently open session

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Reset(NiFpga_Session session);

+

+/**

+ * Re-downloads the FPGA bitstream to the target.

+ *

+ * @param session handle to a currently open session

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_Download(NiFpga_Session session);

+

+/**

+ * Reads a boolean value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadBool(NiFpga_Session session,

+                              uint32_t       indicator,

+                              NiFpga_Bool*   value);

+

+/**

+ * Reads a signed 8-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadI8(NiFpga_Session session,

+                            uint32_t       indicator,

+                            int8_t*        value);

+

+/**

+ * Reads an unsigned 8-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadU8(NiFpga_Session session,

+                            uint32_t       indicator,

+                            uint8_t*       value);

+

+/**

+ * Reads a signed 16-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadI16(NiFpga_Session session,

+                             uint32_t       indicator,

+                             int16_t*       value);

+

+/**

+ * Reads an unsigned 16-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadU16(NiFpga_Session session,

+                             uint32_t       indicator,

+                             uint16_t*      value);

+

+/**

+ * Reads a signed 32-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadI32(NiFpga_Session session,

+                             uint32_t       indicator,

+                             int32_t*       value);

+

+/**

+ * Reads an unsigned 32-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadU32(NiFpga_Session session,

+                             uint32_t       indicator,

+                             uint32_t*      value);

+

+/**

+ * Reads a signed 64-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadI64(NiFpga_Session session,

+                             uint32_t       indicator,

+                             int64_t*       value);

+

+/**

+ * Reads an unsigned 64-bit integer value from a given indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param value outputs the value that was read

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadU64(NiFpga_Session session,

+                             uint32_t       indicator,

+                             uint64_t*      value);

+

+/**

+ * Writes a boolean value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteBool(NiFpga_Session session,

+                               uint32_t       control,

+                               NiFpga_Bool    value);

+

+/**

+ * Writes a signed 8-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteI8(NiFpga_Session session,

+                             uint32_t       control,

+                             int8_t         value);

+

+/**

+ * Writes an unsigned 8-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteU8(NiFpga_Session session,

+                             uint32_t       control,

+                             uint8_t        value);

+

+/**

+ * Writes a signed 16-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteI16(NiFpga_Session session,

+                              uint32_t       control,

+                              int16_t        value);

+

+/**

+ * Writes an unsigned 16-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteU16(NiFpga_Session session,

+                              uint32_t       control,

+                              uint16_t       value);

+

+/**

+ * Writes a signed 32-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteI32(NiFpga_Session session,

+                              uint32_t       control,

+                              int32_t        value);

+

+/**

+ * Writes an unsigned 32-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteU32(NiFpga_Session session,

+                              uint32_t       control,

+                              uint32_t       value);

+

+/**

+ * Writes a signed 64-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteI64(NiFpga_Session session,

+                              uint32_t       control,

+                              int64_t        value);

+

+/**

+ * Writes an unsigned 64-bit integer value to a given control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param value value to write

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteU64(NiFpga_Session session,

+                              uint32_t       control,

+                              uint64_t       value);

+

+/**

+ * Reads an entire array of boolean values from a given array indicator or

+ * control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayBool(NiFpga_Session session,

+                                   uint32_t       indicator,

+                                   NiFpga_Bool*   array,

+                                   size_t         size);

+

+/**

+ * Reads an entire array of signed 8-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayI8(NiFpga_Session session,

+                                 uint32_t       indicator,

+                                 int8_t*        array,

+                                 size_t         size);

+

+/**

+ * Reads an entire array of unsigned 8-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayU8(NiFpga_Session session,

+                                 uint32_t       indicator,

+                                 uint8_t*       array,

+                                 size_t         size);

+

+/**

+ * Reads an entire array of signed 16-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayI16(NiFpga_Session session,

+                                  uint32_t       indicator,

+                                  int16_t*       array,

+                                  size_t         size);

+

+/**

+ * Reads an entire array of unsigned 16-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayU16(NiFpga_Session session,

+                                  uint32_t       indicator,

+                                  uint16_t*      array,

+                                  size_t         size);

+

+/**

+ * Reads an entire array of signed 32-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayI32(NiFpga_Session session,

+                                  uint32_t       indicator,

+                                  int32_t*       array,

+                                  size_t         size);

+

+/**

+ * Reads an entire array of unsigned 32-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayU32(NiFpga_Session session,

+                                  uint32_t       indicator,

+                                  uint32_t*      array,

+                                  size_t         size);

+

+/**

+ * Reads an entire array of signed 64-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayI64(NiFpga_Session session,

+                                  uint32_t       indicator,

+                                  int64_t*       array,

+                                  size_t         size);

+

+/**

+ * Reads an entire array of unsigned 64-bit integer values from a given array

+ * indicator or control.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          indicator or control.

+ *

+ * @param session handle to a currently open session

+ * @param indicator indicator or control from which to read

+ * @param array outputs the entire array that was read

+ * @param size exact number of elements in the indicator or control

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadArrayU64(NiFpga_Session session,

+                                  uint32_t       indicator,

+                                  uint64_t*      array,

+                                  size_t         size);

+

+/**

+ * Writes an entire array of boolean values to a given array control or

+ * indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayBool(NiFpga_Session     session,

+                                    uint32_t           control,

+                                    const NiFpga_Bool* array,

+                                    size_t             size);

+

+/**

+ * Writes an entire array of signed 8-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayI8(NiFpga_Session session,

+                                  uint32_t       control,

+                                  const int8_t*  array,

+                                  size_t         size);

+

+/**

+ * Writes an entire array of unsigned 8-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayU8(NiFpga_Session session,

+                                  uint32_t       control,

+                                  const uint8_t* array,

+                                  size_t         size);

+

+/**

+ * Writes an entire array of signed 16-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayI16(NiFpga_Session session,

+                                   uint32_t       control,

+                                   const int16_t* array,

+                                   size_t         size);

+

+/**

+ * Writes an entire array of unsigned 16-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayU16(NiFpga_Session  session,

+                                   uint32_t        control,

+                                   const uint16_t* array,

+                                   size_t          size);

+

+/**

+ * Writes an entire array of signed 32-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayI32(NiFpga_Session session,

+                                   uint32_t       control,

+                                   const int32_t* array,

+                                   size_t         size);

+

+/**

+ * Writes an entire array of unsigned 32-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayU32(NiFpga_Session  session,

+                                   uint32_t        control,

+                                   const uint32_t* array,

+                                   size_t          size);

+

+/**

+ * Writes an entire array of signed 64-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayI64(NiFpga_Session session,

+                                   uint32_t       control,

+                                   const int64_t* array,

+                                   size_t         size);

+

+/**

+ * Writes an entire array of unsigned 64-bit integer values to a given array

+ * control or indicator.

+ *

+ * @warning The size passed must be the exact number of elements in the

+ *          control or indicator.

+ *

+ * @param session handle to a currently open session

+ * @param control control or indicator to which to write

+ * @param array entire array to write

+ * @param size exact number of elements in the control or indicator

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteArrayU64(NiFpga_Session  session,

+                                   uint32_t        control,

+                                   const uint64_t* array,

+                                   size_t          size);

+

+/**

+ * Enumeration of all 32 possible IRQs. Multiple IRQs can be bitwise ORed

+ * together like this:

+ *

+ *    NiFpga_Irq_3 | NiFpga_Irq_23

+ */

+typedef enum

+{

+   NiFpga_Irq_0  = 1 << 0,

+   NiFpga_Irq_1  = 1 << 1,

+   NiFpga_Irq_2  = 1 << 2,

+   NiFpga_Irq_3  = 1 << 3,

+   NiFpga_Irq_4  = 1 << 4,

+   NiFpga_Irq_5  = 1 << 5,

+   NiFpga_Irq_6  = 1 << 6,

+   NiFpga_Irq_7  = 1 << 7,

+   NiFpga_Irq_8  = 1 << 8,

+   NiFpga_Irq_9  = 1 << 9,

+   NiFpga_Irq_10 = 1 << 10,

+   NiFpga_Irq_11 = 1 << 11,

+   NiFpga_Irq_12 = 1 << 12,

+   NiFpga_Irq_13 = 1 << 13,

+   NiFpga_Irq_14 = 1 << 14,

+   NiFpga_Irq_15 = 1 << 15,

+   NiFpga_Irq_16 = 1 << 16,

+   NiFpga_Irq_17 = 1 << 17,

+   NiFpga_Irq_18 = 1 << 18,

+   NiFpga_Irq_19 = 1 << 19,

+   NiFpga_Irq_20 = 1 << 20,

+   NiFpga_Irq_21 = 1 << 21,

+   NiFpga_Irq_22 = 1 << 22,

+   NiFpga_Irq_23 = 1 << 23,

+   NiFpga_Irq_24 = 1 << 24,

+   NiFpga_Irq_25 = 1 << 25,

+   NiFpga_Irq_26 = 1 << 26,

+   NiFpga_Irq_27 = 1 << 27,

+   NiFpga_Irq_28 = 1 << 28,

+   NiFpga_Irq_29 = 1 << 29,

+   NiFpga_Irq_30 = 1 << 30,

+   NiFpga_Irq_31 = 1U << 31

+} NiFpga_Irq;

+

+/**

+ * Represents an infinite timeout.

+ */

+static const uint32_t NiFpga_InfiniteTimeout = 0xFFFFFFFF;

+

+/**

+ * See NiFpga_ReserveIrqContext for more information.

+ */

+typedef void* NiFpga_IrqContext;

+

+/**

+ * IRQ contexts are single-threaded; only one thread can wait with a

+ * particular context at any given time. To minimize jitter when first

+ * waiting on IRQs, reserve as many contexts as the application

+ * requires.

+ *

+ * If a context is successfully reserved (the returned status is not an error),

+ * it must be unreserved later. Otherwise a memory leak will occur.

+ *

+ * @param session handle to a currently open session

+ * @param context outputs the IRQ context

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReserveIrqContext(NiFpga_Session     session,

+                                       NiFpga_IrqContext* context);

+

+/**

+ * Unreserves an IRQ context obtained from NiFpga_ReserveIrqContext.

+ *

+ * @param session handle to a currently open session

+ * @param context IRQ context to unreserve

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_UnreserveIrqContext(NiFpga_Session    session,

+                                         NiFpga_IrqContext context);

+

+/**

+ * This is a blocking function that stops the calling thread until the

+ * FPGA asserts any IRQ in the irqs parameter, or until the function

+ * call times out.  Before calling this function, use

+ * NiFpga_ReserveIrqContext to reserve an IRQ context. No other

+ * threads can use the same context when this function is called.

+ *

+ * You can use the irqsAsserted parameter to determine which IRQs were asserted

+ * for each function call.

+ *

+ * @param session handle to a currently open session

+ * @param context IRQ context with which to wait

+ * @param irqs bitwise OR of NiFpga_Irqs

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param irqsAsserted if non-NULL, outputs bitwise OR of IRQs that were

+ *                     asserted

+ * @param timedOut if non-NULL, outputs whether the timeout expired

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WaitOnIrqs(NiFpga_Session    session,

+                                NiFpga_IrqContext context,

+                                uint32_t          irqs,

+                                uint32_t          timeout,

+                                uint32_t*         irqsAsserted,

+                                NiFpga_Bool*      timedOut);

+

+/**

+ * Acknowledges an IRQ or set of IRQs.

+ *

+ * @param session handle to a currently open session

+ * @param irqs bitwise OR of NiFpga_Irqs

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcknowledgeIrqs(NiFpga_Session session,

+                                     uint32_t       irqs);

+

+/**

+ * Specifies the depth of the host memory part of the DMA FIFO. This method is

+ * optional. In order to see the actual depth configured, use

+ * NiFpga_ConfigureFifo2.

+ *

+ * @param session handle to a currently open session

+ * @param fifo FIFO to configure

+ * @param depth requested number of elements in the host memory part of the

+ *              DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ConfigureFifo(NiFpga_Session session,

+                                   uint32_t       fifo,

+                                   size_t         depth);

+

+/**

+ * Specifies the depth of the host memory part of the DMA FIFO. This method is

+ * optional.

+ *

+ * @param session handle to a currently open session

+ * @param fifo FIFO to configure

+ * @param requestedDepth requested number of elements in the host memory part

+ *                       of the DMA FIFO

+ * @param actualDepth if non-NULL, outputs the actual number of elements in the

+ *                    host memory part of the DMA FIFO, which may be more than

+ *                    the requested number

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ConfigureFifo2(NiFpga_Session session,

+                                    uint32_t       fifo,

+                                    size_t         requestedDepth,

+                                    size_t*        actualDepth);

+

+/**

+ * Starts a FIFO. This method is optional.

+ *

+ * @param session handle to a currently open session

+ * @param fifo FIFO to start

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_StartFifo(NiFpga_Session session,

+                               uint32_t       fifo);

+

+/**

+ * Stops a FIFO. This method is optional.

+ *

+ * @param session handle to a currently open session

+ * @param fifo FIFO to stop

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_StopFifo(NiFpga_Session session,

+                              uint32_t       fifo);

+

+/**

+ * Reads from a target-to-host FIFO of booleans.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoBool(NiFpga_Session session,

+                                  uint32_t       fifo,

+                                  NiFpga_Bool*   data,

+                                  size_t         numberOfElements,

+                                  uint32_t       timeout,

+                                  size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of signed 8-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoI8(NiFpga_Session session,

+                                uint32_t       fifo,

+                                int8_t*        data,

+                                size_t         numberOfElements,

+                                uint32_t       timeout,

+                                size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of unsigned 8-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoU8(NiFpga_Session session,

+                                uint32_t       fifo,

+                                uint8_t*       data,

+                                size_t         numberOfElements,

+                                uint32_t       timeout,

+                                size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of signed 16-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoI16(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 int16_t*       data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of unsigned 16-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoU16(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 uint16_t*      data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of signed 32-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoI32(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 int32_t*       data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of unsigned 32-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoU32(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 uint32_t*      data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of signed 64-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoI64(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 int64_t*       data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        elementsRemaining);

+

+/**

+ * Reads from a target-to-host FIFO of unsigned 64-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param data outputs the data that was read

+ * @param numberOfElements number of elements to read

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReadFifoU64(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 uint64_t*      data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        elementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of booleans.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoBool(NiFpga_Session     session,

+                                   uint32_t           fifo,

+                                   const NiFpga_Bool* data,

+                                   size_t             numberOfElements,

+                                   uint32_t           timeout,

+                                   size_t*            emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of signed 8-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoI8(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 const int8_t*  data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of unsigned 8-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoU8(NiFpga_Session session,

+                                 uint32_t       fifo,

+                                 const uint8_t* data,

+                                 size_t         numberOfElements,

+                                 uint32_t       timeout,

+                                 size_t*        emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of signed 16-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoI16(NiFpga_Session session,

+                                  uint32_t       fifo,

+                                  const int16_t* data,

+                                  size_t         numberOfElements,

+                                  uint32_t       timeout,

+                                  size_t*        emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of unsigned 16-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoU16(NiFpga_Session  session,

+                                  uint32_t        fifo,

+                                  const uint16_t* data,

+                                  size_t          numberOfElements,

+                                  uint32_t        timeout,

+                                  size_t*         emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of signed 32-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoI32(NiFpga_Session session,

+                                  uint32_t       fifo,

+                                  const int32_t* data,

+                                  size_t         numberOfElements,

+                                  uint32_t       timeout,

+                                  size_t*        emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of unsigned 32-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoU32(NiFpga_Session  session,

+                                  uint32_t        fifo,

+                                  const uint32_t* data,

+                                  size_t          numberOfElements,

+                                  uint32_t        timeout,

+                                  size_t*         emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of signed 64-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoI64(NiFpga_Session session,

+                                  uint32_t       fifo,

+                                  const int64_t* data,

+                                  size_t         numberOfElements,

+                                  uint32_t       timeout,

+                                  size_t*        emptyElementsRemaining);

+

+/**

+ * Writes to a host-to-target FIFO of unsigned 64-bit integers.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param data data to write

+ * @param numberOfElements number of elements to write

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty

+ *                               elements remaining in the host memory part of

+ *                               the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_WriteFifoU64(NiFpga_Session  session,

+                                  uint32_t        fifo,

+                                  const uint64_t* data,

+                                  size_t          numberOfElements,

+                                  uint32_t        timeout,

+                                  size_t*         emptyElementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of booleans.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsBool(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             NiFpga_Bool**  elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of signed 8-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsI8(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             int8_t**       elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of unsigned 8-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsU8(

+                                            NiFpga_Session  session,

+                                            uint32_t        fifo,

+                                            uint8_t**       elements,

+                                            size_t          elementsRequested,

+                                            uint32_t        timeout,

+                                            size_t*         elementsAcquired,

+                                            size_t*         elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of signed 16-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsI16(

+                                            NiFpga_Session  session,

+                                            uint32_t        fifo,

+                                            int16_t**       elements,

+                                            size_t          elementsRequested,

+                                            uint32_t        timeout,

+                                            size_t*         elementsAcquired,

+                                            size_t*         elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of unsigned 16-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsU16(

+                                           NiFpga_Session   session,

+                                           uint32_t         fifo,

+                                           uint16_t**       elements,

+                                           size_t           elementsRequested,

+                                           uint32_t         timeout,

+                                           size_t*          elementsAcquired,

+                                           size_t*          elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of signed 32-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsI32(

+                                            NiFpga_Session  session,

+                                            uint32_t        fifo,

+                                            int32_t**       elements,

+                                            size_t          elementsRequested,

+                                            uint32_t        timeout,

+                                            size_t*         elementsAcquired,

+                                            size_t*         elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of unsigned 32-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsU32(

+                                           NiFpga_Session   session,

+                                           uint32_t         fifo,

+                                           uint32_t**       elements,

+                                           size_t           elementsRequested,

+                                           uint32_t         timeout,

+                                           size_t*          elementsAcquired,

+                                           size_t*          elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of signed 64-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsI64(

+                                            NiFpga_Session  session,

+                                            uint32_t        fifo,

+                                            int64_t**       elements,

+                                            size_t          elementsRequested,

+                                            uint32_t        timeout,

+                                            size_t*         elementsAcquired,

+                                            size_t*         elementsRemaining);

+

+/**

+ * Acquires elements for reading from a target-to-host FIFO of unsigned 64-bit

+ * integers.

+ *

+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy

+ * the contents of elements from the host memory buffer to a separate

+ * user-allocated buffer before reading. The FPGA target cannot write to

+ * elements acquired by the host. Therefore, the host must release elements

+ * after reading them. The number of elements acquired may differ from the

+ * number of elements requested if, for example, the number of elements

+ * requested reaches the end of the host memory buffer. Always release all

+ * acquired elements before closing the session. Do not attempt to access FIFO

+ * elements after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo target-to-host FIFO from which to read

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoReadElementsU64(

+                                           NiFpga_Session   session,

+                                           uint32_t         fifo,

+                                           uint64_t**       elements,

+                                           size_t           elementsRequested,

+                                           uint32_t         timeout,

+                                           size_t*          elementsAcquired,

+                                           size_t*          elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of booleans.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsBool(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             NiFpga_Bool**  elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of signed 8-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsI8(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             int8_t**       elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of unsigned 8-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsU8(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             uint8_t**      elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of signed 16-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsI16(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             int16_t**      elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of unsigned 16-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsU16(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             uint16_t**     elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of signed 32-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsI32(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             int32_t**      elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of unsigned 32-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsU32(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             uint32_t**     elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of signed 64-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsI64(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             int64_t**      elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Acquires elements for writing to a host-to-target FIFO of unsigned 64-bit

+ * integers.

+ *

+ * Acquiring, writing, and releasing FIFO elements prevents the need to write

+ * first into a separate user-allocated buffer and then copy the contents of

+ * elements to the host memory buffer. The FPGA target cannot read elements

+ * acquired by the host. Therefore, the host must release elements after

+ * writing to them. The number of elements acquired may differ from the number

+ * of elements requested if, for example, the number of elements requested

+ * reaches the end of the host memory buffer. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo host-to-target FIFO to which to write

+ * @param elements outputs a pointer to the elements acquired

+ * @param elementsRequested requested number of elements

+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout

+ * @param elementsAcquired actual number of elements acquired, which may be

+ *                         less than the requested number

+ * @param elementsRemaining if non-NULL, outputs the number of elements

+ *                          remaining in the host memory part of the DMA FIFO

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_AcquireFifoWriteElementsU64(

+                                             NiFpga_Session session,

+                                             uint32_t       fifo,

+                                             uint64_t**     elements,

+                                             size_t         elementsRequested,

+                                             uint32_t       timeout,

+                                             size_t*        elementsAcquired,

+                                             size_t*        elementsRemaining);

+

+/**

+ * Releases previously acquired FIFO elements.

+ *

+ * The FPGA target cannot read elements acquired by the host. Therefore, the

+ * host must release elements after acquiring them. Always release all acquired

+ * elements before closing the session. Do not attempt to access FIFO elements

+ * after the elements are released or the session is closed.

+ *

+ * @param session handle to a currently open session

+ * @param fifo FIFO from which to release elements

+ * @param elements number of elements to release

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_ReleaseFifoElements(NiFpga_Session session,

+                                         uint32_t       fifo,

+                                         size_t         elements);

+

+/**

+ * Gets an endpoint reference to a peer-to-peer FIFO.

+ *

+ * @param session handle to a currently open session

+ * @param fifo peer-to-peer FIFO

+ * @param endpoint outputs the endpoint reference

+ * @return result of the call

+ */

+NiFpga_Status NiFpga_GetPeerToPeerFifoEndpoint(NiFpga_Session session,

+                                               uint32_t       fifo,

+                                               uint32_t*      endpoint);

+

+#if NiFpga_Cpp

+}

+#endif

+

+#endif

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/nInterfaceGlobals.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/nInterfaceGlobals.h
new file mode 100644
index 0000000..abd07d4
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/nInterfaceGlobals.h
@@ -0,0 +1,15 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_C0EF_1_1_0_nInterfaceGlobals_h__

+#define __nFRC_C0EF_1_1_0_nInterfaceGlobals_h__

+

+namespace nFPGA

+{

+namespace nFRC_C0EF_1_1_0

+{

+   extern unsigned int g_currentTargetClass;

+}

+}

+

+#endif // __nFRC_C0EF_1_1_0_nInterfaceGlobals_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tAI.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tAI.h
new file mode 100644
index 0000000..14121b5
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tAI.h
@@ -0,0 +1,73 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_C0EF_1_1_0_AI_h__

+#define __nFRC_C0EF_1_1_0_AI_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_C0EF_1_1_0

+{

+

+class tAI

+{

+public:

+   tAI(){}

+   virtual ~tAI(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAI* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 2,

+   } tIfaceConstants;

+

+

+

+   typedef enum

+   {

+   } tCalOK_IfaceConstants;

+

+   virtual bool readCalOK(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDoneTime_IfaceConstants;

+

+   virtual unsigned int readDoneTime(tRioStatusCode *status) = 0;

+

+

+

+

+   typedef enum

+   {

+      kNumOffsetRegisters = 8,

+   } tOffset_IfaceConstants;

+

+   virtual signed int readOffset(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumLSBWeightRegisters = 8,

+   } tLSBWeight_IfaceConstants;

+

+   virtual unsigned int readLSBWeight(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+

+private:

+   tAI(const tAI&);

+   void operator=(const tAI&);

+};

+

+}

+}

+

+#endif // __nFRC_C0EF_1_1_0_AI_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tGlobal.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tGlobal.h
new file mode 100644
index 0000000..0b74117
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tGlobal.h
@@ -0,0 +1,69 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_C0EF_1_1_0_Global_h__

+#define __nFRC_C0EF_1_1_0_Global_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_C0EF_1_1_0

+{

+

+class tGlobal

+{

+public:

+   tGlobal(){}

+   virtual ~tGlobal(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tGlobal* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tVersion_IfaceConstants;

+

+   virtual unsigned short readVersion(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLocalTime_IfaceConstants;

+

+   virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tRevision_IfaceConstants;

+

+   virtual unsigned int readRevision(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReserved_IfaceConstants;

+

+   virtual unsigned char readReserved(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tGlobal(const tGlobal&);

+   void operator=(const tGlobal&);

+};

+

+}

+}

+

+#endif // __nFRC_C0EF_1_1_0_Global_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tLoadOut.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tLoadOut.h
new file mode 100644
index 0000000..a7c4ebb
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tLoadOut.h
@@ -0,0 +1,79 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_C0EF_1_1_0_LoadOut_h__

+#define __nFRC_C0EF_1_1_0_LoadOut_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_C0EF_1_1_0

+{

+

+class tLoadOut

+{

+public:

+   tLoadOut(){}

+   virtual ~tLoadOut(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tLoadOut* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tReady_IfaceConstants;

+

+   virtual bool readReady(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDoneTime_IfaceConstants;

+

+   virtual unsigned int readDoneTime(tRioStatusCode *status) = 0;

+

+

+

+

+   typedef enum

+   {

+      kNumVendorIDRegisters = 8,

+   } tVendorID_IfaceConstants;

+

+   virtual unsigned short readVendorID(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumSerialNumberRegisters = 8,

+   } tSerialNumber_IfaceConstants;

+

+   virtual unsigned int readSerialNumber(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumModuleIDRegisters = 8,

+   } tModuleID_IfaceConstants;

+

+   virtual unsigned short readModuleID(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+private:

+   tLoadOut(const tLoadOut&);

+   void operator=(const tLoadOut&);

+};

+

+}

+}

+

+#endif // __nFRC_C0EF_1_1_0_LoadOut_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h
new file mode 100644
index 0000000..9ff5a0e
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h
@@ -0,0 +1,15 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_nInterfaceGlobals_h__

+#define __nFRC_2015_1_0_A_nInterfaceGlobals_h__

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+   extern unsigned int g_currentTargetClass;

+}

+}

+

+#endif // __nFRC_2015_1_0_A_nInterfaceGlobals_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h
new file mode 100644
index 0000000..2a8f614
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h
@@ -0,0 +1,143 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_AI_h__

+#define __nFRC_2015_1_0_A_AI_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tAI

+{

+public:

+   tAI(){}

+   virtual ~tAI(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAI* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ScanSize : 3;

+         unsigned ConvertRate : 26;

+#else

+         unsigned ConvertRate : 26;

+         unsigned ScanSize : 3;

+#endif

+      };

+      struct{

+         unsigned value : 29;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Channel : 3;

+         unsigned Averaged : 1;

+#else

+         unsigned Averaged : 1;

+         unsigned Channel : 3;

+#endif

+      };

+      struct{

+         unsigned value : 4;

+      };

+   } tReadSelect;

+

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual signed int readOutput(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ScanSize(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ConvertRate(unsigned int value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ScanSize(tRioStatusCode *status) = 0;

+   virtual unsigned int readConfig_ConvertRate(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLoopTiming_IfaceConstants;

+

+   virtual unsigned int readLoopTiming(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumOversampleBitsElements = 8,

+   } tOversampleBits_IfaceConstants;

+

+   virtual void writeOversampleBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readOversampleBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumAverageBitsElements = 8,

+   } tAverageBits_IfaceConstants;

+

+   virtual void writeAverageBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readAverageBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumScanListElements = 8,

+   } tScanList_IfaceConstants;

+

+   virtual void writeScanList(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readScanList(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLatchOutput_IfaceConstants;

+

+   virtual void strobeLatchOutput(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReadSelect_IfaceConstants;

+

+   virtual void writeReadSelect(tReadSelect value, tRioStatusCode *status) = 0;

+   virtual void writeReadSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeReadSelect_Averaged(bool value, tRioStatusCode *status) = 0;

+   virtual tReadSelect readReadSelect(tRioStatusCode *status) = 0;

+   virtual unsigned char readReadSelect_Channel(tRioStatusCode *status) = 0;

+   virtual bool readReadSelect_Averaged(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAI(const tAI&);

+   void operator=(const tAI&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_AI_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h
new file mode 100644
index 0000000..7160f04
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h
@@ -0,0 +1,50 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_AO_h__

+#define __nFRC_2015_1_0_A_AO_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tAO

+{

+public:

+   tAO(){}

+   virtual ~tAO(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAO* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+

+

+   typedef enum

+   {

+      kNumMXPRegisters = 2,

+   } tMXP_IfaceConstants;

+

+   virtual void writeMXP(unsigned char reg_index, unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readMXP(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+private:

+   tAO(const tAO&);

+   void operator=(const tAO&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_AO_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h
new file mode 100644
index 0000000..02318de
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h
@@ -0,0 +1,102 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Accel_h__

+#define __nFRC_2015_1_0_A_Accel_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tAccel

+{

+public:

+   tAccel(){}

+   virtual ~tAccel(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAccel* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tSTAT_IfaceConstants;

+

+   virtual unsigned char readSTAT(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tCNTR_IfaceConstants;

+

+   virtual void writeCNTR(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readCNTR(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDATO_IfaceConstants;

+

+   virtual void writeDATO(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readDATO(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tCNFG_IfaceConstants;

+

+   virtual void writeCNFG(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readCNFG(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tCNTL_IfaceConstants;

+

+   virtual void writeCNTL(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readCNTL(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDATI_IfaceConstants;

+

+   virtual unsigned char readDATI(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tGO_IfaceConstants;

+

+   virtual void strobeGO(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tADDR_IfaceConstants;

+

+   virtual void writeADDR(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readADDR(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAccel(const tAccel&);

+   void operator=(const tAccel&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Accel_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h
new file mode 100644
index 0000000..991c5fb
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h
@@ -0,0 +1,87 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Accumulator_h__

+#define __nFRC_2015_1_0_A_Accumulator_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tAccumulator

+{

+public:

+   tAccumulator(){}

+   virtual ~tAccumulator(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAccumulator* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 2,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+         signed long long Value;

+         unsigned Count : 32;

+      };

+      struct{

+         unsigned value : 32;

+         unsigned value2 : 32;

+         unsigned value3 : 32;

+      };

+   } tOutput;

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(tRioStatusCode *status) = 0;

+   virtual signed long long readOutput_Value(tRioStatusCode *status) = 0;

+   virtual unsigned int readOutput_Count(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tCenter_IfaceConstants;

+

+   virtual void writeCenter(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readCenter(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDeadband_IfaceConstants;

+

+   virtual void writeDeadband(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readDeadband(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tAccumulator(const tAccumulator&);

+   void operator=(const tAccumulator&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Accumulator_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h
new file mode 100644
index 0000000..8739405
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h
@@ -0,0 +1,57 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Alarm_h__

+#define __nFRC_2015_1_0_A_Alarm_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tAlarm

+{

+public:

+   tAlarm(){}

+   virtual ~tAlarm(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAlarm* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tEnable_IfaceConstants;

+

+   virtual void writeEnable(bool value, tRioStatusCode *status) = 0;

+   virtual bool readEnable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTriggerTime_IfaceConstants;

+

+   virtual void writeTriggerTime(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readTriggerTime(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAlarm(const tAlarm&);

+   void operator=(const tAlarm&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Alarm_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h
new file mode 100644
index 0000000..6b89bc2
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h
@@ -0,0 +1,129 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_AnalogTrigger_h__

+#define __nFRC_2015_1_0_A_AnalogTrigger_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tAnalogTrigger

+{

+public:

+   tAnalogTrigger(){}

+   virtual ~tAnalogTrigger(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAnalogTrigger* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned InHysteresis : 1;

+         unsigned OverLimit : 1;

+         unsigned Rising : 1;

+         unsigned Falling : 1;

+#else

+         unsigned Falling : 1;

+         unsigned Rising : 1;

+         unsigned OverLimit : 1;

+         unsigned InHysteresis : 1;

+#endif

+      };

+      struct{

+         unsigned value : 4;

+      };

+   } tOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Channel : 3;

+         unsigned Averaged : 1;

+         unsigned Filter : 1;

+         unsigned FloatingRollover : 1;

+         signed RolloverLimit : 8;

+#else

+         signed RolloverLimit : 8;

+         unsigned FloatingRollover : 1;

+         unsigned Filter : 1;

+         unsigned Averaged : 1;

+         unsigned Channel : 3;

+#endif

+      };

+      struct{

+         unsigned value : 14;

+      };

+   } tSourceSelect;

+

+

+   typedef enum

+   {

+   } tSourceSelect_IfaceConstants;

+

+   virtual void writeSourceSelect(tSourceSelect value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Averaged(bool value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Filter(bool value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_FloatingRollover(bool value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_RolloverLimit(signed short value, tRioStatusCode *status) = 0;

+   virtual tSourceSelect readSourceSelect(tRioStatusCode *status) = 0;

+   virtual unsigned char readSourceSelect_Channel(tRioStatusCode *status) = 0;

+   virtual bool readSourceSelect_Averaged(tRioStatusCode *status) = 0;

+   virtual bool readSourceSelect_Filter(tRioStatusCode *status) = 0;

+   virtual bool readSourceSelect_FloatingRollover(tRioStatusCode *status) = 0;

+   virtual signed short readSourceSelect_RolloverLimit(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUpperLimit_IfaceConstants;

+

+   virtual void writeUpperLimit(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readUpperLimit(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLowerLimit_IfaceConstants;

+

+   virtual void writeLowerLimit(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readLowerLimit(tRioStatusCode *status) = 0;

+

+

+

+   typedef enum

+   {

+      kNumOutputElements = 8,

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_InHysteresis(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_OverLimit(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_Rising(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_Falling(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAnalogTrigger(const tAnalogTrigger&);

+   void operator=(const tAnalogTrigger&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_AnalogTrigger_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h
new file mode 100644
index 0000000..41b8626
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h
@@ -0,0 +1,90 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_BIST_h__

+#define __nFRC_2015_1_0_A_BIST_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tBIST

+{

+public:

+   tBIST(){}

+   virtual ~tBIST(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tBIST* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tDO0SquareTicks_IfaceConstants;

+

+   virtual void writeDO0SquareTicks(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readDO0SquareTicks(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tEnable_IfaceConstants;

+

+   virtual void writeEnable(bool value, tRioStatusCode *status) = 0;

+   virtual bool readEnable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDO1SquareEnable_IfaceConstants;

+

+   virtual void writeDO1SquareEnable(bool value, tRioStatusCode *status) = 0;

+   virtual bool readDO1SquareEnable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDO0SquareEnable_IfaceConstants;

+

+   virtual void writeDO0SquareEnable(bool value, tRioStatusCode *status) = 0;

+   virtual bool readDO0SquareEnable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDO1SquareTicks_IfaceConstants;

+

+   virtual void writeDO1SquareTicks(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readDO1SquareTicks(tRioStatusCode *status) = 0;

+

+

+

+

+   typedef enum

+   {

+      kNumDORegisters = 2,

+   } tDO_IfaceConstants;

+

+   virtual void writeDO(unsigned char reg_index, bool value, tRioStatusCode *status) = 0;

+   virtual bool readDO(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+private:

+   tBIST(const tBIST&);

+   void operator=(const tBIST&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_BIST_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h
new file mode 100644
index 0000000..6eff544
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h
@@ -0,0 +1,219 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Counter_h__

+#define __nFRC_2015_1_0_A_Counter_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tCounter

+{

+public:

+   tCounter(){}

+   virtual ~tCounter(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tCounter* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Direction : 1;

+         signed Value : 31;

+#else

+         signed Value : 31;

+         unsigned Direction : 1;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned UpSource_Channel : 4;

+         unsigned UpSource_Module : 1;

+         unsigned UpSource_AnalogTrigger : 1;

+         unsigned DownSource_Channel : 4;

+         unsigned DownSource_Module : 1;

+         unsigned DownSource_AnalogTrigger : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned IndexEdgeSensitive : 1;

+         unsigned UpRisingEdge : 1;

+         unsigned UpFallingEdge : 1;

+         unsigned DownRisingEdge : 1;

+         unsigned DownFallingEdge : 1;

+         unsigned Mode : 2;

+         unsigned PulseLengthThreshold : 6;

+#else

+         unsigned PulseLengthThreshold : 6;

+         unsigned Mode : 2;

+         unsigned DownFallingEdge : 1;

+         unsigned DownRisingEdge : 1;

+         unsigned UpFallingEdge : 1;

+         unsigned UpRisingEdge : 1;

+         unsigned IndexEdgeSensitive : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned DownSource_AnalogTrigger : 1;

+         unsigned DownSource_Module : 1;

+         unsigned DownSource_Channel : 4;

+         unsigned UpSource_AnalogTrigger : 1;

+         unsigned UpSource_Module : 1;

+         unsigned UpSource_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Period : 23;

+         signed Count : 8;

+         unsigned Stalled : 1;

+#else

+         unsigned Stalled : 1;

+         signed Count : 8;

+         unsigned Period : 23;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned StallPeriod : 24;

+         unsigned AverageSize : 7;

+         unsigned UpdateWhenEmpty : 1;

+#else

+         unsigned UpdateWhenEmpty : 1;

+         unsigned AverageSize : 7;

+         unsigned StallPeriod : 24;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerConfig;

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(tRioStatusCode *status) = 0;

+   virtual bool readOutput_Direction(tRioStatusCode *status) = 0;

+   virtual signed int readOutput_Value(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexEdgeSensitive(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpRisingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpFallingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownRisingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownFallingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Mode(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_PulseLengthThreshold(unsigned short value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_UpSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_UpSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_UpSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_DownSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_DownSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DownSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexEdgeSensitive(tRioStatusCode *status) = 0;

+   virtual bool readConfig_UpRisingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_UpFallingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DownRisingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DownFallingEdge(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_Mode(tRioStatusCode *status) = 0;

+   virtual unsigned short readConfig_PulseLengthThreshold(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerOutput_IfaceConstants;

+

+   virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;

+   virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;

+   virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerConfig_IfaceConstants;

+

+   virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;

+   virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;

+   virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;

+   virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tCounter(const tCounter&);

+   void operator=(const tCounter&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Counter_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h
new file mode 100644
index 0000000..0d9659b
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h
@@ -0,0 +1,248 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_DIO_h__

+#define __nFRC_2015_1_0_A_DIO_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tDIO

+{

+public:

+   tDIO(){}

+   virtual ~tDIO(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tDIO* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Headers : 10;

+         unsigned Reserved : 6;

+         unsigned MXP : 16;

+#else

+         unsigned MXP : 16;

+         unsigned Reserved : 6;

+         unsigned Headers : 10;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tDO;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Headers : 10;

+         unsigned Reserved : 6;

+         unsigned MXP : 16;

+#else

+         unsigned MXP : 16;

+         unsigned Reserved : 6;

+         unsigned Headers : 10;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tOutputEnable;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Headers : 10;

+         unsigned Reserved : 6;

+         unsigned MXP : 16;

+#else

+         unsigned MXP : 16;

+         unsigned Reserved : 6;

+         unsigned Headers : 10;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tPulse;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Headers : 10;

+         unsigned Reserved : 6;

+         unsigned MXP : 16;

+#else

+         unsigned MXP : 16;

+         unsigned Reserved : 6;

+         unsigned Headers : 10;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tDI;

+

+

+

+   typedef enum

+   {

+   } tDO_IfaceConstants;

+

+   virtual void writeDO(tDO value, tRioStatusCode *status) = 0;

+   virtual void writeDO_Headers(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writeDO_Reserved(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeDO_MXP(unsigned short value, tRioStatusCode *status) = 0;

+   virtual tDO readDO(tRioStatusCode *status) = 0;

+   virtual unsigned short readDO_Headers(tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_Reserved(tRioStatusCode *status) = 0;

+   virtual unsigned short readDO_MXP(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumPWMDutyCycleAElements = 4,

+   } tPWMDutyCycleA_IfaceConstants;

+

+   virtual void writePWMDutyCycleA(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPWMDutyCycleA(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumPWMDutyCycleBElements = 2,

+   } tPWMDutyCycleB_IfaceConstants;

+

+   virtual void writePWMDutyCycleB(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPWMDutyCycleB(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumFilterSelectHdrElements = 16,

+   } tFilterSelectHdr_IfaceConstants;

+

+   virtual void writeFilterSelectHdr(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readFilterSelectHdr(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tOutputEnable_IfaceConstants;

+

+   virtual void writeOutputEnable(tOutputEnable value, tRioStatusCode *status) = 0;

+   virtual void writeOutputEnable_Headers(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writeOutputEnable_Reserved(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeOutputEnable_MXP(unsigned short value, tRioStatusCode *status) = 0;

+   virtual tOutputEnable readOutputEnable(tRioStatusCode *status) = 0;

+   virtual unsigned short readOutputEnable_Headers(tRioStatusCode *status) = 0;

+   virtual unsigned char readOutputEnable_Reserved(tRioStatusCode *status) = 0;

+   virtual unsigned short readOutputEnable_MXP(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumPWMOutputSelectElements = 6,

+   } tPWMOutputSelect_IfaceConstants;

+

+   virtual void writePWMOutputSelect(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPWMOutputSelect(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tPulse_IfaceConstants;

+

+   virtual void writePulse(tPulse value, tRioStatusCode *status) = 0;

+   virtual void writePulse_Headers(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writePulse_Reserved(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writePulse_MXP(unsigned short value, tRioStatusCode *status) = 0;

+   virtual tPulse readPulse(tRioStatusCode *status) = 0;

+   virtual unsigned short readPulse_Headers(tRioStatusCode *status) = 0;

+   virtual unsigned char readPulse_Reserved(tRioStatusCode *status) = 0;

+   virtual unsigned short readPulse_MXP(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDI_IfaceConstants;

+

+   virtual tDI readDI(tRioStatusCode *status) = 0;

+   virtual unsigned short readDI_Headers(tRioStatusCode *status) = 0;

+   virtual unsigned char readDI_Reserved(tRioStatusCode *status) = 0;

+   virtual unsigned short readDI_MXP(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tEnableMXPSpecialFunction_IfaceConstants;

+

+   virtual void writeEnableMXPSpecialFunction(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readEnableMXPSpecialFunction(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumFilterSelectMXPElements = 16,

+   } tFilterSelectMXP_IfaceConstants;

+

+   virtual void writeFilterSelectMXP(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readFilterSelectMXP(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tPulseLength_IfaceConstants;

+

+   virtual void writePulseLength(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPulseLength(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tPWMPeriodPower_IfaceConstants;

+

+   virtual void writePWMPeriodPower(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readPWMPeriodPower(tRioStatusCode *status) = 0;

+

+

+

+

+   typedef enum

+   {

+      kNumFilterPeriodMXPRegisters = 3,

+   } tFilterPeriodMXP_IfaceConstants;

+

+   virtual void writeFilterPeriodMXP(unsigned char reg_index, unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readFilterPeriodMXP(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumFilterPeriodHdrRegisters = 3,

+   } tFilterPeriodHdr_IfaceConstants;

+

+   virtual void writeFilterPeriodHdr(unsigned char reg_index, unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readFilterPeriodHdr(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+private:

+   tDIO(const tDIO&);

+   void operator=(const tDIO&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_DIO_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h
new file mode 100644
index 0000000..4b57edf
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h
@@ -0,0 +1,188 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_DMA_h__

+#define __nFRC_2015_1_0_A_DMA_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tDMA

+{

+public:

+   tDMA(){}

+   virtual ~tDMA(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tDMA* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Pause : 1;

+         unsigned Enable_AI0_Low : 1;

+         unsigned Enable_AI0_High : 1;

+         unsigned Enable_AIAveraged0_Low : 1;

+         unsigned Enable_AIAveraged0_High : 1;

+         unsigned Enable_AI1_Low : 1;

+         unsigned Enable_AI1_High : 1;

+         unsigned Enable_AIAveraged1_Low : 1;

+         unsigned Enable_AIAveraged1_High : 1;

+         unsigned Enable_Accumulator0 : 1;

+         unsigned Enable_Accumulator1 : 1;

+         unsigned Enable_DI : 1;

+         unsigned Enable_AnalogTriggers : 1;

+         unsigned Enable_Counters_Low : 1;

+         unsigned Enable_Counters_High : 1;

+         unsigned Enable_CounterTimers_Low : 1;

+         unsigned Enable_CounterTimers_High : 1;

+         unsigned Enable_Encoders : 1;

+         unsigned Enable_EncoderTimers : 1;

+         unsigned ExternalClock : 1;

+#else

+         unsigned ExternalClock : 1;

+         unsigned Enable_EncoderTimers : 1;

+         unsigned Enable_Encoders : 1;

+         unsigned Enable_CounterTimers_High : 1;

+         unsigned Enable_CounterTimers_Low : 1;

+         unsigned Enable_Counters_High : 1;

+         unsigned Enable_Counters_Low : 1;

+         unsigned Enable_AnalogTriggers : 1;

+         unsigned Enable_DI : 1;

+         unsigned Enable_Accumulator1 : 1;

+         unsigned Enable_Accumulator0 : 1;

+         unsigned Enable_AIAveraged1_High : 1;

+         unsigned Enable_AIAveraged1_Low : 1;

+         unsigned Enable_AI1_High : 1;

+         unsigned Enable_AI1_Low : 1;

+         unsigned Enable_AIAveraged0_High : 1;

+         unsigned Enable_AIAveraged0_Low : 1;

+         unsigned Enable_AI0_High : 1;

+         unsigned Enable_AI0_Low : 1;

+         unsigned Pause : 1;

+#endif

+      };

+      struct{

+         unsigned value : 20;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ExternalClockSource_Channel : 4;

+         unsigned ExternalClockSource_Module : 1;

+         unsigned ExternalClockSource_AnalogTrigger : 1;

+         unsigned RisingEdge : 1;

+         unsigned FallingEdge : 1;

+#else

+         unsigned FallingEdge : 1;

+         unsigned RisingEdge : 1;

+         unsigned ExternalClockSource_AnalogTrigger : 1;

+         unsigned ExternalClockSource_Module : 1;

+         unsigned ExternalClockSource_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 8;

+      };

+   } tExternalTriggers;

+

+

+

+   typedef enum

+   {

+   } tRate_IfaceConstants;

+

+   virtual void writeRate(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readRate(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Pause(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI0_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI0_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged0_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged0_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI1_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI1_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged1_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged1_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Accumulator0(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Accumulator1(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_DI(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AnalogTriggers(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Counters_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Counters_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_CounterTimers_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_CounterTimers_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Encoders(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_EncoderTimers(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ExternalClock(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Pause(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI0_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI0_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged0_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged0_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI1_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI1_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged1_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged1_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Accumulator0(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Accumulator1(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_DI(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AnalogTriggers(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Counters_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Counters_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_CounterTimers_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_CounterTimers_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Encoders(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_EncoderTimers(tRioStatusCode *status) = 0;

+   virtual bool readConfig_ExternalClock(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumExternalTriggersElements = 4,

+   } tExternalTriggers_IfaceConstants;

+

+   virtual void writeExternalTriggers(unsigned char bitfield_index, tExternalTriggers value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_RisingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_FallingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual tExternalTriggers readExternalTriggers(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual unsigned char readExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual unsigned char readExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readExternalTriggers_RisingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readExternalTriggers_FallingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tDMA(const tDMA&);

+   void operator=(const tDMA&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_DMA_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h
new file mode 100644
index 0000000..466b9c1
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h
@@ -0,0 +1,199 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Encoder_h__

+#define __nFRC_2015_1_0_A_Encoder_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tEncoder

+{

+public:

+   tEncoder(){}

+   virtual ~tEncoder(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tEncoder* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Direction : 1;

+         signed Value : 31;

+#else

+         signed Value : 31;

+         unsigned Direction : 1;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ASource_Channel : 4;

+         unsigned ASource_Module : 1;

+         unsigned ASource_AnalogTrigger : 1;

+         unsigned BSource_Channel : 4;

+         unsigned BSource_Module : 1;

+         unsigned BSource_AnalogTrigger : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned IndexEdgeSensitive : 1;

+         unsigned Reverse : 1;

+#else

+         unsigned Reverse : 1;

+         unsigned IndexEdgeSensitive : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned BSource_AnalogTrigger : 1;

+         unsigned BSource_Module : 1;

+         unsigned BSource_Channel : 4;

+         unsigned ASource_AnalogTrigger : 1;

+         unsigned ASource_Module : 1;

+         unsigned ASource_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 21;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Period : 23;

+         signed Count : 8;

+         unsigned Stalled : 1;

+#else

+         unsigned Stalled : 1;

+         signed Count : 8;

+         unsigned Period : 23;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned StallPeriod : 24;

+         unsigned AverageSize : 7;

+         unsigned UpdateWhenEmpty : 1;

+#else

+         unsigned UpdateWhenEmpty : 1;

+         unsigned AverageSize : 7;

+         unsigned StallPeriod : 24;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerConfig;

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(tRioStatusCode *status) = 0;

+   virtual bool readOutput_Direction(tRioStatusCode *status) = 0;

+   virtual signed int readOutput_Value(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ASource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ASource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ASource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexEdgeSensitive(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Reverse(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ASource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ASource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_ASource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_BSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_BSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_BSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexEdgeSensitive(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Reverse(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerOutput_IfaceConstants;

+

+   virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;

+   virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;

+   virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerConfig_IfaceConstants;

+

+   virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;

+   virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;

+   virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;

+   virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tEncoder(const tEncoder&);

+   void operator=(const tEncoder&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Encoder_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h
new file mode 100644
index 0000000..e2014de
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h
@@ -0,0 +1,104 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Global_h__

+#define __nFRC_2015_1_0_A_Global_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tGlobal

+{

+public:

+   tGlobal(){}

+   virtual ~tGlobal(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tGlobal* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Radio : 8;

+         unsigned Comm : 8;

+         unsigned Mode : 8;

+         unsigned RSL : 1;

+#else

+         unsigned RSL : 1;

+         unsigned Mode : 8;

+         unsigned Comm : 8;

+         unsigned Radio : 8;

+#endif

+      };

+      struct{

+         unsigned value : 25;

+      };

+   } tLEDs;

+

+

+

+   typedef enum

+   {

+   } tLEDs_IfaceConstants;

+

+   virtual void writeLEDs(tLEDs value, tRioStatusCode *status) = 0;

+   virtual void writeLEDs_Radio(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeLEDs_Comm(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeLEDs_Mode(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeLEDs_RSL(bool value, tRioStatusCode *status) = 0;

+   virtual tLEDs readLEDs(tRioStatusCode *status) = 0;

+   virtual unsigned char readLEDs_Radio(tRioStatusCode *status) = 0;

+   virtual unsigned char readLEDs_Comm(tRioStatusCode *status) = 0;

+   virtual unsigned char readLEDs_Mode(tRioStatusCode *status) = 0;

+   virtual bool readLEDs_RSL(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tVersion_IfaceConstants;

+

+   virtual unsigned short readVersion(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLocalTime_IfaceConstants;

+

+   virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUserButton_IfaceConstants;

+

+   virtual bool readUserButton(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tRevision_IfaceConstants;

+

+   virtual unsigned int readRevision(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tGlobal(const tGlobal&);

+   void operator=(const tGlobal&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Global_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h
new file mode 100644
index 0000000..16233e1
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h
@@ -0,0 +1,100 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Interrupt_h__

+#define __nFRC_2015_1_0_A_Interrupt_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tInterrupt

+{

+public:

+   tInterrupt(){}

+   virtual ~tInterrupt(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tInterrupt* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Source_Channel : 4;

+         unsigned Source_Module : 1;

+         unsigned Source_AnalogTrigger : 1;

+         unsigned RisingEdge : 1;

+         unsigned FallingEdge : 1;

+         unsigned WaitForAck : 1;

+#else

+         unsigned WaitForAck : 1;

+         unsigned FallingEdge : 1;

+         unsigned RisingEdge : 1;

+         unsigned Source_AnalogTrigger : 1;

+         unsigned Source_Module : 1;

+         unsigned Source_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 9;

+      };

+   } tConfig;

+

+

+   typedef enum

+   {

+   } tFallingTimeStamp_IfaceConstants;

+

+   virtual unsigned int readFallingTimeStamp(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Source_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Source_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Source_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_RisingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_FallingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_WaitForAck(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_Source_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_Source_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Source_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual bool readConfig_RisingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_FallingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_WaitForAck(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tRisingTimeStamp_IfaceConstants;

+

+   virtual unsigned int readRisingTimeStamp(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tInterrupt(const tInterrupt&);

+   void operator=(const tInterrupt&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Interrupt_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h
new file mode 100644
index 0000000..5dcf5e2
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h
@@ -0,0 +1,120 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_PWM_h__

+#define __nFRC_2015_1_0_A_PWM_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tPWM

+{

+public:

+   tPWM(){}

+   virtual ~tPWM(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tPWM* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Period : 16;

+         unsigned MinHigh : 16;

+#else

+         unsigned MinHigh : 16;

+         unsigned Period : 16;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tConfig;

+

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Period(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_MinHigh(unsigned short value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned short readConfig_Period(tRioStatusCode *status) = 0;

+   virtual unsigned short readConfig_MinHigh(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLoopTiming_IfaceConstants;

+

+   virtual unsigned short readLoopTiming(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumPeriodScaleMXPElements = 10,

+   } tPeriodScaleMXP_IfaceConstants;

+

+   virtual void writePeriodScaleMXP(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPeriodScaleMXP(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumPeriodScaleHdrElements = 10,

+   } tPeriodScaleHdr_IfaceConstants;

+

+   virtual void writePeriodScaleHdr(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPeriodScaleHdr(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumZeroLatchElements = 20,

+   } tZeroLatch_IfaceConstants;

+

+   virtual void writeZeroLatch(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual bool readZeroLatch(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+

+   typedef enum

+   {

+      kNumHdrRegisters = 10,

+   } tHdr_IfaceConstants;

+

+   virtual void writeHdr(unsigned char reg_index, unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readHdr(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumMXPRegisters = 10,

+   } tMXP_IfaceConstants;

+

+   virtual void writeMXP(unsigned char reg_index, unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readMXP(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+private:

+   tPWM(const tPWM&);

+   void operator=(const tPWM&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_PWM_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h
new file mode 100644
index 0000000..6084c66
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h
@@ -0,0 +1,217 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Power_h__

+#define __nFRC_2015_1_0_A_Power_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tPower

+{

+public:

+   tPower(){}

+   virtual ~tPower(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tPower* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned User3V3 : 8;

+         unsigned User5V : 8;

+         unsigned User6V : 8;

+#else

+         unsigned User6V : 8;

+         unsigned User5V : 8;

+         unsigned User3V3 : 8;

+#endif

+      };

+      struct{

+         unsigned value : 24;

+      };

+   } tStatus;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned OverCurrentFaultCount3V3 : 10;

+         unsigned OverCurrentFaultCount5V : 10;

+         unsigned OverCurrentFaultCount6V : 10;

+#else

+         unsigned OverCurrentFaultCount6V : 10;

+         unsigned OverCurrentFaultCount5V : 10;

+         unsigned OverCurrentFaultCount3V3 : 10;

+#endif

+      };

+      struct{

+         unsigned value : 30;

+      };

+   } tOverCurrentFaultCounts;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned User3V3 : 1;

+         unsigned User5V : 1;

+         unsigned User6V : 1;

+#else

+         unsigned User6V : 1;

+         unsigned User5V : 1;

+         unsigned User3V3 : 1;

+#endif

+      };

+      struct{

+         unsigned value : 3;

+      };

+   } tDisable;

+

+

+

+   typedef enum

+   {

+   } tUserVoltage3V3_IfaceConstants;

+

+   virtual unsigned short readUserVoltage3V3(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tStatus_IfaceConstants;

+

+   virtual tStatus readStatus(tRioStatusCode *status) = 0;

+   virtual unsigned char readStatus_User3V3(tRioStatusCode *status) = 0;

+   virtual unsigned char readStatus_User5V(tRioStatusCode *status) = 0;

+   virtual unsigned char readStatus_User6V(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUserVoltage6V_IfaceConstants;

+

+   virtual unsigned short readUserVoltage6V(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tOnChipTemperature_IfaceConstants;

+

+   virtual unsigned short readOnChipTemperature(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUserVoltage5V_IfaceConstants;

+

+   virtual unsigned short readUserVoltage5V(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tResetFaultCounts_IfaceConstants;

+

+   virtual void strobeResetFaultCounts(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tOverCurrentFaultCounts_IfaceConstants;

+

+   virtual tOverCurrentFaultCounts readOverCurrentFaultCounts(tRioStatusCode *status) = 0;

+   virtual unsigned short readOverCurrentFaultCounts_OverCurrentFaultCount3V3(tRioStatusCode *status) = 0;

+   virtual unsigned short readOverCurrentFaultCounts_OverCurrentFaultCount5V(tRioStatusCode *status) = 0;

+   virtual unsigned short readOverCurrentFaultCounts_OverCurrentFaultCount6V(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tIntegratedIO_IfaceConstants;

+

+   virtual unsigned short readIntegratedIO(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tMXP_DIOVoltage_IfaceConstants;

+

+   virtual unsigned short readMXP_DIOVoltage(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUserCurrent3V3_IfaceConstants;

+

+   virtual unsigned short readUserCurrent3V3(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tVinVoltage_IfaceConstants;

+

+   virtual unsigned short readVinVoltage(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUserCurrent6V_IfaceConstants;

+

+   virtual unsigned short readUserCurrent6V(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUserCurrent5V_IfaceConstants;

+

+   virtual unsigned short readUserCurrent5V(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tAOVoltage_IfaceConstants;

+

+   virtual unsigned short readAOVoltage(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tVinCurrent_IfaceConstants;

+

+   virtual unsigned short readVinCurrent(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDisable_IfaceConstants;

+

+   virtual void writeDisable(tDisable value, tRioStatusCode *status) = 0;

+   virtual void writeDisable_User3V3(bool value, tRioStatusCode *status) = 0;

+   virtual void writeDisable_User5V(bool value, tRioStatusCode *status) = 0;

+   virtual void writeDisable_User6V(bool value, tRioStatusCode *status) = 0;

+   virtual tDisable readDisable(tRioStatusCode *status) = 0;

+   virtual bool readDisable_User3V3(tRioStatusCode *status) = 0;

+   virtual bool readDisable_User5V(tRioStatusCode *status) = 0;

+   virtual bool readDisable_User6V(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tPower(const tPower&);

+   void operator=(const tPower&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Power_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h
new file mode 100644
index 0000000..e3f0286
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h
@@ -0,0 +1,68 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_Relay_h__

+#define __nFRC_2015_1_0_A_Relay_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tRelay

+{

+public:

+   tRelay(){}

+   virtual ~tRelay(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tRelay* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Forward : 4;

+         unsigned Reverse : 4;

+#else

+         unsigned Reverse : 4;

+         unsigned Forward : 4;

+#endif

+      };

+      struct{

+         unsigned value : 8;

+      };

+   } tValue;

+

+

+

+   typedef enum

+   {

+   } tValue_IfaceConstants;

+

+   virtual void writeValue(tValue value, tRioStatusCode *status) = 0;

+   virtual void writeValue_Forward(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeValue_Reverse(unsigned char value, tRioStatusCode *status) = 0;

+   virtual tValue readValue(tRioStatusCode *status) = 0;

+   virtual unsigned char readValue_Forward(tRioStatusCode *status) = 0;

+   virtual unsigned char readValue_Reverse(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tRelay(const tRelay&);

+   void operator=(const tRelay&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_Relay_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h
new file mode 100644
index 0000000..93a2b3e
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h
@@ -0,0 +1,68 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_SPI_h__

+#define __nFRC_2015_1_0_A_SPI_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tSPI

+{

+public:

+   tSPI(){}

+   virtual ~tSPI(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tSPI* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Hdr : 4;

+         unsigned MXP : 1;

+#else

+         unsigned MXP : 1;

+         unsigned Hdr : 4;

+#endif

+      };

+      struct{

+         unsigned value : 5;

+      };

+   } tChipSelectActiveHigh;

+

+

+

+   typedef enum

+   {

+   } tChipSelectActiveHigh_IfaceConstants;

+

+   virtual void writeChipSelectActiveHigh(tChipSelectActiveHigh value, tRioStatusCode *status) = 0;

+   virtual void writeChipSelectActiveHigh_Hdr(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChipSelectActiveHigh_MXP(unsigned char value, tRioStatusCode *status) = 0;

+   virtual tChipSelectActiveHigh readChipSelectActiveHigh(tRioStatusCode *status) = 0;

+   virtual unsigned char readChipSelectActiveHigh_Hdr(tRioStatusCode *status) = 0;

+   virtual unsigned char readChipSelectActiveHigh_MXP(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tSPI(const tSPI&);

+   void operator=(const tSPI&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_SPI_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h
new file mode 100644
index 0000000..67dcd13
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h
@@ -0,0 +1,108 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2015_1_0_A_SysWatchdog_h__

+#define __nFRC_2015_1_0_A_SysWatchdog_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2015_1_0_A

+{

+

+class tSysWatchdog

+{

+public:

+   tSysWatchdog(){}

+   virtual ~tSysWatchdog(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tSysWatchdog* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned SystemActive : 1;

+         unsigned PowerAlive : 1;

+         unsigned SysDisableCount : 15;

+         unsigned PowerDisableCount : 15;

+#else

+         unsigned PowerDisableCount : 15;

+         unsigned SysDisableCount : 15;

+         unsigned PowerAlive : 1;

+         unsigned SystemActive : 1;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tStatus;

+

+

+

+   typedef enum

+   {

+   } tStatus_IfaceConstants;

+

+   virtual tStatus readStatus(tRioStatusCode *status) = 0;

+   virtual bool readStatus_SystemActive(tRioStatusCode *status) = 0;

+   virtual bool readStatus_PowerAlive(tRioStatusCode *status) = 0;

+   virtual unsigned short readStatus_SysDisableCount(tRioStatusCode *status) = 0;

+   virtual unsigned short readStatus_PowerDisableCount(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tCommand_IfaceConstants;

+

+   virtual void writeCommand(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readCommand(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tChallenge_IfaceConstants;

+

+   virtual unsigned char readChallenge(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tActive_IfaceConstants;

+

+   virtual void writeActive(bool value, tRioStatusCode *status) = 0;

+   virtual bool readActive(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimer_IfaceConstants;

+

+   virtual unsigned int readTimer(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tForcedKills_IfaceConstants;

+

+   virtual unsigned short readForcedKills(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tSysWatchdog(const tSysWatchdog&);

+   void operator=(const tSysWatchdog&);

+};

+

+}

+}

+

+#endif // __nFRC_2015_1_0_A_SysWatchdog_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/nInterfaceGlobals.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/nInterfaceGlobals.h
new file mode 100644
index 0000000..f34cc74
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/nInterfaceGlobals.h
@@ -0,0 +1,15 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_nInterfaceGlobals_h__

+#define __nFRC_2012_1_6_4_nInterfaceGlobals_h__

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+   extern unsigned int g_currentTargetClass;

+}

+}

+

+#endif // __nFRC_2012_1_6_4_nInterfaceGlobals_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAI.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAI.h
new file mode 100644
index 0000000..78c423a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAI.h
@@ -0,0 +1,149 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_AI_h__

+#define __nFRC_2012_1_6_4_AI_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tAI

+{

+public:

+   tAI(){}

+   virtual ~tAI(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAI* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 2,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Channel : 3;

+         unsigned Module : 1;

+         unsigned Averaged : 1;

+#else

+         unsigned Averaged : 1;

+         unsigned Module : 1;

+         unsigned Channel : 3;

+#endif

+      };

+      struct{

+         unsigned value : 5;

+      };

+   } tReadSelect;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ScanSize : 3;

+         unsigned ConvertRate : 26;

+#else

+         unsigned ConvertRate : 26;

+         unsigned ScanSize : 3;

+#endif

+      };

+      struct{

+         unsigned value : 29;

+      };

+   } tConfig;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ScanSize(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ConvertRate(unsigned int value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ScanSize(tRioStatusCode *status) = 0;

+   virtual unsigned int readConfig_ConvertRate(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLoopTiming_IfaceConstants;

+

+   virtual unsigned int readLoopTiming(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumOversampleBitsElements = 8,

+   } tOversampleBits_IfaceConstants;

+

+   virtual void writeOversampleBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readOversampleBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumAverageBitsElements = 8,

+   } tAverageBits_IfaceConstants;

+

+   virtual void writeAverageBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readAverageBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumScanListElements = 8,

+   } tScanList_IfaceConstants;

+

+   virtual void writeScanList(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readScanList(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual signed int readOutput(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLatchOutput_IfaceConstants;

+

+   virtual void strobeLatchOutput(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReadSelect_IfaceConstants;

+

+   virtual void writeReadSelect(tReadSelect value, tRioStatusCode *status) = 0;

+   virtual void writeReadSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeReadSelect_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeReadSelect_Averaged(bool value, tRioStatusCode *status) = 0;

+   virtual tReadSelect readReadSelect(tRioStatusCode *status) = 0;

+   virtual unsigned char readReadSelect_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readReadSelect_Module(tRioStatusCode *status) = 0;

+   virtual bool readReadSelect_Averaged(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAI(const tAI&);

+   void operator=(const tAI&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_AI_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAccumulator.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAccumulator.h
new file mode 100644
index 0000000..1a0972a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAccumulator.h
@@ -0,0 +1,87 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Accumulator_h__

+#define __nFRC_2012_1_6_4_Accumulator_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tAccumulator

+{

+public:

+   tAccumulator(){}

+   virtual ~tAccumulator(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAccumulator* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 2,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+         signed long long Value;

+         unsigned Count : 32;

+      };

+      struct{

+         unsigned value : 32;

+         unsigned value2 : 32;

+         unsigned value3 : 32;

+      };

+   } tOutput;

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(tRioStatusCode *status) = 0;

+   virtual signed long long readOutput_Value(tRioStatusCode *status) = 0;

+   virtual unsigned int readOutput_Count(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tCenter_IfaceConstants;

+

+   virtual void writeCenter(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readCenter(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDeadband_IfaceConstants;

+

+   virtual void writeDeadband(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readDeadband(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tAccumulator(const tAccumulator&);

+   void operator=(const tAccumulator&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Accumulator_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAlarm.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAlarm.h
new file mode 100644
index 0000000..f3eb33f
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAlarm.h
@@ -0,0 +1,57 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Alarm_h__

+#define __nFRC_2012_1_6_4_Alarm_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tAlarm

+{

+public:

+   tAlarm(){}

+   virtual ~tAlarm(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAlarm* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tEnable_IfaceConstants;

+

+   virtual void writeEnable(bool value, tRioStatusCode *status) = 0;

+   virtual bool readEnable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTriggerTime_IfaceConstants;

+

+   virtual void writeTriggerTime(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readTriggerTime(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAlarm(const tAlarm&);

+   void operator=(const tAlarm&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Alarm_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAnalogTrigger.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAnalogTrigger.h
new file mode 100644
index 0000000..43150f7
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAnalogTrigger.h
@@ -0,0 +1,133 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_AnalogTrigger_h__

+#define __nFRC_2012_1_6_4_AnalogTrigger_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tAnalogTrigger

+{

+public:

+   tAnalogTrigger(){}

+   virtual ~tAnalogTrigger(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tAnalogTrigger* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned InHysteresis : 1;

+         unsigned OverLimit : 1;

+         unsigned Rising : 1;

+         unsigned Falling : 1;

+#else

+         unsigned Falling : 1;

+         unsigned Rising : 1;

+         unsigned OverLimit : 1;

+         unsigned InHysteresis : 1;

+#endif

+      };

+      struct{

+         unsigned value : 4;

+      };

+   } tOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Channel : 3;

+         unsigned Module : 1;

+         unsigned Averaged : 1;

+         unsigned Filter : 1;

+         unsigned FloatingRollover : 1;

+         signed RolloverLimit : 8;

+#else

+         signed RolloverLimit : 8;

+         unsigned FloatingRollover : 1;

+         unsigned Filter : 1;

+         unsigned Averaged : 1;

+         unsigned Module : 1;

+         unsigned Channel : 3;

+#endif

+      };

+      struct{

+         unsigned value : 15;

+      };

+   } tSourceSelect;

+

+

+   typedef enum

+   {

+   } tSourceSelect_IfaceConstants;

+

+   virtual void writeSourceSelect(tSourceSelect value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Averaged(bool value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_Filter(bool value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_FloatingRollover(bool value, tRioStatusCode *status) = 0;

+   virtual void writeSourceSelect_RolloverLimit(signed short value, tRioStatusCode *status) = 0;

+   virtual tSourceSelect readSourceSelect(tRioStatusCode *status) = 0;

+   virtual unsigned char readSourceSelect_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readSourceSelect_Module(tRioStatusCode *status) = 0;

+   virtual bool readSourceSelect_Averaged(tRioStatusCode *status) = 0;

+   virtual bool readSourceSelect_Filter(tRioStatusCode *status) = 0;

+   virtual bool readSourceSelect_FloatingRollover(tRioStatusCode *status) = 0;

+   virtual signed short readSourceSelect_RolloverLimit(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tUpperLimit_IfaceConstants;

+

+   virtual void writeUpperLimit(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readUpperLimit(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLowerLimit_IfaceConstants;

+

+   virtual void writeLowerLimit(signed int value, tRioStatusCode *status) = 0;

+   virtual signed int readLowerLimit(tRioStatusCode *status) = 0;

+

+

+

+   typedef enum

+   {

+      kNumOutputElements = 8,

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_InHysteresis(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_OverLimit(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_Rising(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readOutput_Falling(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tAnalogTrigger(const tAnalogTrigger&);

+   void operator=(const tAnalogTrigger&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_AnalogTrigger_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tCounter.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tCounter.h
new file mode 100644
index 0000000..b23a7f0
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tCounter.h
@@ -0,0 +1,219 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Counter_h__

+#define __nFRC_2012_1_6_4_Counter_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tCounter

+{

+public:

+   tCounter(){}

+   virtual ~tCounter(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tCounter* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Direction : 1;

+         signed Value : 31;

+#else

+         signed Value : 31;

+         unsigned Direction : 1;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned UpSource_Channel : 4;

+         unsigned UpSource_Module : 1;

+         unsigned UpSource_AnalogTrigger : 1;

+         unsigned DownSource_Channel : 4;

+         unsigned DownSource_Module : 1;

+         unsigned DownSource_AnalogTrigger : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned UpRisingEdge : 1;

+         unsigned UpFallingEdge : 1;

+         unsigned DownRisingEdge : 1;

+         unsigned DownFallingEdge : 1;

+         unsigned Mode : 2;

+         unsigned PulseLengthThreshold : 6;

+         unsigned Enable : 1;

+#else

+         unsigned Enable : 1;

+         unsigned PulseLengthThreshold : 6;

+         unsigned Mode : 2;

+         unsigned DownFallingEdge : 1;

+         unsigned DownRisingEdge : 1;

+         unsigned UpFallingEdge : 1;

+         unsigned UpRisingEdge : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned DownSource_AnalogTrigger : 1;

+         unsigned DownSource_Module : 1;

+         unsigned DownSource_Channel : 4;

+         unsigned UpSource_AnalogTrigger : 1;

+         unsigned UpSource_Module : 1;

+         unsigned UpSource_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Period : 23;

+         signed Count : 8;

+         unsigned Stalled : 1;

+#else

+         unsigned Stalled : 1;

+         signed Count : 8;

+         unsigned Period : 23;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned StallPeriod : 24;

+         unsigned AverageSize : 7;

+         unsigned UpdateWhenEmpty : 1;

+#else

+         unsigned UpdateWhenEmpty : 1;

+         unsigned AverageSize : 7;

+         unsigned StallPeriod : 24;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerConfig;

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(tRioStatusCode *status) = 0;

+   virtual bool readOutput_Direction(tRioStatusCode *status) = 0;

+   virtual signed int readOutput_Value(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpRisingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_UpFallingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownRisingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DownFallingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Mode(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_PulseLengthThreshold(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_UpSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_UpSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_UpSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_DownSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_DownSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DownSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;

+   virtual bool readConfig_UpRisingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_UpFallingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DownRisingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DownFallingEdge(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_Mode(tRioStatusCode *status) = 0;

+   virtual unsigned short readConfig_PulseLengthThreshold(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerOutput_IfaceConstants;

+

+   virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;

+   virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;

+   virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerConfig_IfaceConstants;

+

+   virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;

+   virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;

+   virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;

+   virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tCounter(const tCounter&);

+   void operator=(const tCounter&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Counter_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDIO.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDIO.h
new file mode 100644
index 0000000..babb691
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDIO.h
@@ -0,0 +1,330 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_DIO_h__

+#define __nFRC_2012_1_6_4_DIO_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tDIO

+{

+public:

+   tDIO(){}

+   virtual ~tDIO(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tDIO* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 2,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Period : 16;

+         unsigned MinHigh : 16;

+#else

+         unsigned MinHigh : 16;

+         unsigned Period : 16;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tPWMConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned RelayFwd : 8;

+         unsigned RelayRev : 8;

+         unsigned I2CHeader : 4;

+#else

+         unsigned I2CHeader : 4;

+         unsigned RelayRev : 8;

+         unsigned RelayFwd : 8;

+#endif

+      };

+      struct{

+         unsigned value : 20;

+      };

+   } tSlowValue;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Transaction : 1;

+         unsigned Done : 1;

+         unsigned Aborted : 1;

+         unsigned DataReceivedHigh : 24;

+#else

+         unsigned DataReceivedHigh : 24;

+         unsigned Aborted : 1;

+         unsigned Done : 1;

+         unsigned Transaction : 1;

+#endif

+      };

+      struct{

+         unsigned value : 27;

+      };

+   } tI2CStatus;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Address : 8;

+         unsigned BytesToRead : 3;

+         unsigned BytesToWrite : 3;

+         unsigned DataToSendHigh : 16;

+         unsigned BitwiseHandshake : 1;

+#else

+         unsigned BitwiseHandshake : 1;

+         unsigned DataToSendHigh : 16;

+         unsigned BytesToWrite : 3;

+         unsigned BytesToRead : 3;

+         unsigned Address : 8;

+#endif

+      };

+      struct{

+         unsigned value : 31;

+      };

+   } tI2CConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned PeriodPower : 4;

+         unsigned OutputSelect_0 : 4;

+         unsigned OutputSelect_1 : 4;

+         unsigned OutputSelect_2 : 4;

+         unsigned OutputSelect_3 : 4;

+#else

+         unsigned OutputSelect_3 : 4;

+         unsigned OutputSelect_2 : 4;

+         unsigned OutputSelect_1 : 4;

+         unsigned OutputSelect_0 : 4;

+         unsigned PeriodPower : 4;

+#endif

+      };

+      struct{

+         unsigned value : 20;

+      };

+   } tDO_PWMConfig;

+

+

+   typedef enum

+   {

+      kNumFilterSelectElements = 16,

+   } tFilterSelect_IfaceConstants;

+

+   virtual void writeFilterSelect(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readFilterSelect(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tI2CDataToSend_IfaceConstants;

+

+   virtual void writeI2CDataToSend(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readI2CDataToSend(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDO_IfaceConstants;

+

+   virtual void writeDO(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readDO(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumFilterPeriodElements = 3,

+   } tFilterPeriod_IfaceConstants;

+

+   virtual void writeFilterPeriod(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readFilterPeriod(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tOutputEnable_IfaceConstants;

+

+   virtual void writeOutputEnable(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readOutputEnable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tPulse_IfaceConstants;

+

+   virtual void writePulse(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readPulse(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tSlowValue_IfaceConstants;

+

+   virtual void writeSlowValue(tSlowValue value, tRioStatusCode *status) = 0;

+   virtual void writeSlowValue_RelayFwd(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeSlowValue_RelayRev(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeSlowValue_I2CHeader(unsigned char value, tRioStatusCode *status) = 0;

+   virtual tSlowValue readSlowValue(tRioStatusCode *status) = 0;

+   virtual unsigned char readSlowValue_RelayFwd(tRioStatusCode *status) = 0;

+   virtual unsigned char readSlowValue_RelayRev(tRioStatusCode *status) = 0;

+   virtual unsigned char readSlowValue_I2CHeader(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tI2CStatus_IfaceConstants;

+

+   virtual tI2CStatus readI2CStatus(tRioStatusCode *status) = 0;

+   virtual unsigned char readI2CStatus_Transaction(tRioStatusCode *status) = 0;

+   virtual bool readI2CStatus_Done(tRioStatusCode *status) = 0;

+   virtual bool readI2CStatus_Aborted(tRioStatusCode *status) = 0;

+   virtual unsigned int readI2CStatus_DataReceivedHigh(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tI2CDataReceived_IfaceConstants;

+

+   virtual unsigned int readI2CDataReceived(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDI_IfaceConstants;

+

+   virtual unsigned short readDI(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tPulseLength_IfaceConstants;

+

+   virtual void writePulseLength(unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPulseLength(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumPWMPeriodScaleElements = 10,

+   } tPWMPeriodScale_IfaceConstants;

+

+   virtual void writePWMPeriodScale(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPWMPeriodScale(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumDO_PWMDutyCycleElements = 4,

+   } tDO_PWMDutyCycle_IfaceConstants;

+

+   virtual void writeDO_PWMDutyCycle(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_PWMDutyCycle(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tBFL_IfaceConstants;

+

+   virtual void writeBFL(bool value, tRioStatusCode *status) = 0;

+   virtual bool readBFL(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tI2CConfig_IfaceConstants;

+

+   virtual void writeI2CConfig(tI2CConfig value, tRioStatusCode *status) = 0;

+   virtual void writeI2CConfig_Address(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeI2CConfig_BytesToRead(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeI2CConfig_BytesToWrite(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeI2CConfig_DataToSendHigh(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writeI2CConfig_BitwiseHandshake(bool value, tRioStatusCode *status) = 0;

+   virtual tI2CConfig readI2CConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readI2CConfig_Address(tRioStatusCode *status) = 0;

+   virtual unsigned char readI2CConfig_BytesToRead(tRioStatusCode *status) = 0;

+   virtual unsigned char readI2CConfig_BytesToWrite(tRioStatusCode *status) = 0;

+   virtual unsigned short readI2CConfig_DataToSendHigh(tRioStatusCode *status) = 0;

+   virtual bool readI2CConfig_BitwiseHandshake(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDO_PWMConfig_IfaceConstants;

+

+   virtual void writeDO_PWMConfig(tDO_PWMConfig value, tRioStatusCode *status) = 0;

+   virtual void writeDO_PWMConfig_PeriodPower(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeDO_PWMConfig_OutputSelect_0(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeDO_PWMConfig_OutputSelect_1(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeDO_PWMConfig_OutputSelect_2(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeDO_PWMConfig_OutputSelect_3(unsigned char value, tRioStatusCode *status) = 0;

+   virtual tDO_PWMConfig readDO_PWMConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_PWMConfig_PeriodPower(tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_PWMConfig_OutputSelect_0(tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_PWMConfig_OutputSelect_1(tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_PWMConfig_OutputSelect_2(tRioStatusCode *status) = 0;

+   virtual unsigned char readDO_PWMConfig_OutputSelect_3(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tI2CStart_IfaceConstants;

+

+   virtual void strobeI2CStart(tRioStatusCode *status) = 0;

+

+

+

+   typedef enum

+   {

+   } tLoopTiming_IfaceConstants;

+

+   virtual unsigned short readLoopTiming(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tPWMConfig_IfaceConstants;

+

+   virtual void writePWMConfig(tPWMConfig value, tRioStatusCode *status) = 0;

+   virtual void writePWMConfig_Period(unsigned short value, tRioStatusCode *status) = 0;

+   virtual void writePWMConfig_MinHigh(unsigned short value, tRioStatusCode *status) = 0;

+   virtual tPWMConfig readPWMConfig(tRioStatusCode *status) = 0;

+   virtual unsigned short readPWMConfig_Period(tRioStatusCode *status) = 0;

+   virtual unsigned short readPWMConfig_MinHigh(tRioStatusCode *status) = 0;

+

+

+

+   typedef enum

+   {

+      kNumPWMValueRegisters = 10,

+   } tPWMValue_IfaceConstants;

+

+   virtual void writePWMValue(unsigned char reg_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readPWMValue(unsigned char reg_index, tRioStatusCode *status) = 0;

+

+

+

+private:

+   tDIO(const tDIO&);

+   void operator=(const tDIO&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_DIO_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDMA.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDMA.h
new file mode 100644
index 0000000..006ec60
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDMA.h
@@ -0,0 +1,188 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_DMA_h__

+#define __nFRC_2012_1_6_4_DMA_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tDMA

+{

+public:

+   tDMA(){}

+   virtual ~tDMA(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tDMA* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Pause : 1;

+         unsigned Enable_AI0_Low : 1;

+         unsigned Enable_AI0_High : 1;

+         unsigned Enable_AIAveraged0_Low : 1;

+         unsigned Enable_AIAveraged0_High : 1;

+         unsigned Enable_AI1_Low : 1;

+         unsigned Enable_AI1_High : 1;

+         unsigned Enable_AIAveraged1_Low : 1;

+         unsigned Enable_AIAveraged1_High : 1;

+         unsigned Enable_Accumulator0 : 1;

+         unsigned Enable_Accumulator1 : 1;

+         unsigned Enable_DI : 1;

+         unsigned Enable_AnalogTriggers : 1;

+         unsigned Enable_Counters_Low : 1;

+         unsigned Enable_Counters_High : 1;

+         unsigned Enable_CounterTimers_Low : 1;

+         unsigned Enable_CounterTimers_High : 1;

+         unsigned Enable_Encoders : 1;

+         unsigned Enable_EncoderTimers : 1;

+         unsigned ExternalClock : 1;

+#else

+         unsigned ExternalClock : 1;

+         unsigned Enable_EncoderTimers : 1;

+         unsigned Enable_Encoders : 1;

+         unsigned Enable_CounterTimers_High : 1;

+         unsigned Enable_CounterTimers_Low : 1;

+         unsigned Enable_Counters_High : 1;

+         unsigned Enable_Counters_Low : 1;

+         unsigned Enable_AnalogTriggers : 1;

+         unsigned Enable_DI : 1;

+         unsigned Enable_Accumulator1 : 1;

+         unsigned Enable_Accumulator0 : 1;

+         unsigned Enable_AIAveraged1_High : 1;

+         unsigned Enable_AIAveraged1_Low : 1;

+         unsigned Enable_AI1_High : 1;

+         unsigned Enable_AI1_Low : 1;

+         unsigned Enable_AIAveraged0_High : 1;

+         unsigned Enable_AIAveraged0_Low : 1;

+         unsigned Enable_AI0_High : 1;

+         unsigned Enable_AI0_Low : 1;

+         unsigned Pause : 1;

+#endif

+      };

+      struct{

+         unsigned value : 20;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ExternalClockSource_Channel : 4;

+         unsigned ExternalClockSource_Module : 1;

+         unsigned ExternalClockSource_AnalogTrigger : 1;

+         unsigned RisingEdge : 1;

+         unsigned FallingEdge : 1;

+#else

+         unsigned FallingEdge : 1;

+         unsigned RisingEdge : 1;

+         unsigned ExternalClockSource_AnalogTrigger : 1;

+         unsigned ExternalClockSource_Module : 1;

+         unsigned ExternalClockSource_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 8;

+      };

+   } tExternalTriggers;

+

+

+

+   typedef enum

+   {

+   } tRate_IfaceConstants;

+

+   virtual void writeRate(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readRate(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Pause(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI0_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI0_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged0_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged0_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI1_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AI1_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged1_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AIAveraged1_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Accumulator0(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Accumulator1(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_DI(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_AnalogTriggers(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Counters_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Counters_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_CounterTimers_Low(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_CounterTimers_High(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_Encoders(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable_EncoderTimers(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ExternalClock(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Pause(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI0_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI0_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged0_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged0_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI1_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AI1_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged1_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AIAveraged1_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Accumulator0(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Accumulator1(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_DI(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_AnalogTriggers(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Counters_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Counters_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_CounterTimers_Low(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_CounterTimers_High(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_Encoders(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable_EncoderTimers(tRioStatusCode *status) = 0;

+   virtual bool readConfig_ExternalClock(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+      kNumExternalTriggersElements = 4,

+   } tExternalTriggers_IfaceConstants;

+

+   virtual void writeExternalTriggers(unsigned char bitfield_index, tExternalTriggers value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_RisingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual void writeExternalTriggers_FallingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;

+   virtual tExternalTriggers readExternalTriggers(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual unsigned char readExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual unsigned char readExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readExternalTriggers_RisingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+   virtual bool readExternalTriggers_FallingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tDMA(const tDMA&);

+   void operator=(const tDMA&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_DMA_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tEncoder.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tEncoder.h
new file mode 100644
index 0000000..7255920
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tEncoder.h
@@ -0,0 +1,199 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Encoder_h__

+#define __nFRC_2012_1_6_4_Encoder_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tEncoder

+{

+public:

+   tEncoder(){}

+   virtual ~tEncoder(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tEncoder* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 4,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Direction : 1;

+         signed Value : 31;

+#else

+         signed Value : 31;

+         unsigned Direction : 1;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ASource_Channel : 4;

+         unsigned ASource_Module : 1;

+         unsigned ASource_AnalogTrigger : 1;

+         unsigned BSource_Channel : 4;

+         unsigned BSource_Module : 1;

+         unsigned BSource_AnalogTrigger : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned Reverse : 1;

+         unsigned Enable : 1;

+#else

+         unsigned Enable : 1;

+         unsigned Reverse : 1;

+         unsigned IndexActiveHigh : 1;

+         unsigned IndexSource_AnalogTrigger : 1;

+         unsigned IndexSource_Module : 1;

+         unsigned IndexSource_Channel : 4;

+         unsigned BSource_AnalogTrigger : 1;

+         unsigned BSource_Module : 1;

+         unsigned BSource_Channel : 4;

+         unsigned ASource_AnalogTrigger : 1;

+         unsigned ASource_Module : 1;

+         unsigned ASource_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 21;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Period : 23;

+         signed Count : 8;

+         unsigned Stalled : 1;

+#else

+         unsigned Stalled : 1;

+         signed Count : 8;

+         unsigned Period : 23;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerOutput;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned StallPeriod : 24;

+         unsigned AverageSize : 7;

+         unsigned UpdateWhenEmpty : 1;

+#else

+         unsigned UpdateWhenEmpty : 1;

+         unsigned AverageSize : 7;

+         unsigned StallPeriod : 24;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tTimerConfig;

+

+

+   typedef enum

+   {

+   } tOutput_IfaceConstants;

+

+   virtual tOutput readOutput(tRioStatusCode *status) = 0;

+   virtual bool readOutput_Direction(tRioStatusCode *status) = 0;

+   virtual signed int readOutput_Value(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ASource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ASource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ASource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Reverse(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Enable(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ASource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ASource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_ASource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_BSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_BSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_BSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Reverse(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Enable(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerOutput_IfaceConstants;

+

+   virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;

+   virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;

+   virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimerConfig_IfaceConstants;

+

+   virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;

+   virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;

+   virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;

+   virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;

+   virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tEncoder(const tEncoder&);

+   void operator=(const tEncoder&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Encoder_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tGlobal.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tGlobal.h
new file mode 100644
index 0000000..0782f35
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tGlobal.h
@@ -0,0 +1,70 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Global_h__

+#define __nFRC_2012_1_6_4_Global_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tGlobal

+{

+public:

+   tGlobal(){}

+   virtual ~tGlobal(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tGlobal* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tVersion_IfaceConstants;

+

+   virtual unsigned short readVersion(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLocalTime_IfaceConstants;

+

+   virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tFPGA_LED_IfaceConstants;

+

+   virtual void writeFPGA_LED(bool value, tRioStatusCode *status) = 0;

+   virtual bool readFPGA_LED(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tRevision_IfaceConstants;

+

+   virtual unsigned int readRevision(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tGlobal(const tGlobal&);

+   void operator=(const tGlobal&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Global_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tInterrupt.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tInterrupt.h
new file mode 100644
index 0000000..40186e5
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tInterrupt.h
@@ -0,0 +1,93 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Interrupt_h__

+#define __nFRC_2012_1_6_4_Interrupt_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tInterrupt

+{

+public:

+   tInterrupt(){}

+   virtual ~tInterrupt(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tInterrupt* create(unsigned char sys_index, tRioStatusCode *status);

+   virtual unsigned char getSystemIndex() = 0;

+

+

+   typedef enum

+   {

+      kNumSystems = 8,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned Source_Channel : 4;

+         unsigned Source_Module : 1;

+         unsigned Source_AnalogTrigger : 1;

+         unsigned RisingEdge : 1;

+         unsigned FallingEdge : 1;

+         unsigned WaitForAck : 1;

+#else

+         unsigned WaitForAck : 1;

+         unsigned FallingEdge : 1;

+         unsigned RisingEdge : 1;

+         unsigned Source_AnalogTrigger : 1;

+         unsigned Source_Module : 1;

+         unsigned Source_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 9;

+      };

+   } tConfig;

+

+

+   typedef enum

+   {

+   } tTimeStamp_IfaceConstants;

+

+   virtual unsigned int readTimeStamp(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Source_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Source_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_Source_AnalogTrigger(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_RisingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_FallingEdge(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_WaitForAck(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_Source_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_Source_Module(tRioStatusCode *status) = 0;

+   virtual bool readConfig_Source_AnalogTrigger(tRioStatusCode *status) = 0;

+   virtual bool readConfig_RisingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_FallingEdge(tRioStatusCode *status) = 0;

+   virtual bool readConfig_WaitForAck(tRioStatusCode *status) = 0;

+

+

+

+

+

+private:

+   tInterrupt(const tInterrupt&);

+   void operator=(const tInterrupt&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Interrupt_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSPI.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSPI.h
new file mode 100644
index 0000000..45c208c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSPI.h
@@ -0,0 +1,228 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_SPI_h__

+#define __nFRC_2012_1_6_4_SPI_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tSPI

+{

+public:

+   tSPI(){}

+   virtual ~tSPI(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tSPI* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned ReceivedDataOverflow : 1;

+         unsigned Idle : 1;

+#else

+         unsigned Idle : 1;

+         unsigned ReceivedDataOverflow : 1;

+#endif

+      };

+      struct{

+         unsigned value : 2;

+      };

+   } tStatus;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned BusBitWidth : 8;

+         unsigned ClockHalfPeriodDelay : 8;

+         unsigned MSBfirst : 1;

+         unsigned DataOnFalling : 1;

+         unsigned LatchFirst : 1;

+         unsigned LatchLast : 1;

+         unsigned FramePolarity : 1;

+         unsigned WriteOnly : 1;

+         unsigned ClockPolarity : 1;

+#else

+         unsigned ClockPolarity : 1;

+         unsigned WriteOnly : 1;

+         unsigned FramePolarity : 1;

+         unsigned LatchLast : 1;

+         unsigned LatchFirst : 1;

+         unsigned DataOnFalling : 1;

+         unsigned MSBfirst : 1;

+         unsigned ClockHalfPeriodDelay : 8;

+         unsigned BusBitWidth : 8;

+#endif

+      };

+      struct{

+         unsigned value : 23;

+      };

+   } tConfig;

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned SCLK_Channel : 4;

+         unsigned SCLK_Module : 1;

+         unsigned MOSI_Channel : 4;

+         unsigned MOSI_Module : 1;

+         unsigned MISO_Channel : 4;

+         unsigned MISO_Module : 1;

+         unsigned SS_Channel : 4;

+         unsigned SS_Module : 1;

+#else

+         unsigned SS_Module : 1;

+         unsigned SS_Channel : 4;

+         unsigned MISO_Module : 1;

+         unsigned MISO_Channel : 4;

+         unsigned MOSI_Module : 1;

+         unsigned MOSI_Channel : 4;

+         unsigned SCLK_Module : 1;

+         unsigned SCLK_Channel : 4;

+#endif

+      };

+      struct{

+         unsigned value : 20;

+      };

+   } tChannels;

+

+

+

+   typedef enum

+   {

+   } tStatus_IfaceConstants;

+

+   virtual tStatus readStatus(tRioStatusCode *status) = 0;

+   virtual bool readStatus_ReceivedDataOverflow(tRioStatusCode *status) = 0;

+   virtual bool readStatus_Idle(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReceivedData_IfaceConstants;

+

+   virtual unsigned int readReceivedData(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tDataToLoad_IfaceConstants;

+

+   virtual void writeDataToLoad(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readDataToLoad(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tConfig_IfaceConstants;

+

+   virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_BusBitWidth(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ClockHalfPeriodDelay(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_MSBfirst(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_DataOnFalling(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_LatchFirst(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_LatchLast(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_FramePolarity(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_WriteOnly(bool value, tRioStatusCode *status) = 0;

+   virtual void writeConfig_ClockPolarity(bool value, tRioStatusCode *status) = 0;

+   virtual tConfig readConfig(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_BusBitWidth(tRioStatusCode *status) = 0;

+   virtual unsigned char readConfig_ClockHalfPeriodDelay(tRioStatusCode *status) = 0;

+   virtual bool readConfig_MSBfirst(tRioStatusCode *status) = 0;

+   virtual bool readConfig_DataOnFalling(tRioStatusCode *status) = 0;

+   virtual bool readConfig_LatchFirst(tRioStatusCode *status) = 0;

+   virtual bool readConfig_LatchLast(tRioStatusCode *status) = 0;

+   virtual bool readConfig_FramePolarity(tRioStatusCode *status) = 0;

+   virtual bool readConfig_WriteOnly(tRioStatusCode *status) = 0;

+   virtual bool readConfig_ClockPolarity(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tClearReceivedData_IfaceConstants;

+

+   virtual void strobeClearReceivedData(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReceivedElements_IfaceConstants;

+

+   virtual unsigned short readReceivedElements(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tLoad_IfaceConstants;

+

+   virtual void strobeLoad(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReset_IfaceConstants;

+

+   virtual void strobeReset(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tChannels_IfaceConstants;

+

+   virtual void writeChannels(tChannels value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_SCLK_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_SCLK_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_MOSI_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_MOSI_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_MISO_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_MISO_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_SS_Channel(unsigned char value, tRioStatusCode *status) = 0;

+   virtual void writeChannels_SS_Module(unsigned char value, tRioStatusCode *status) = 0;

+   virtual tChannels readChannels(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_SCLK_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_SCLK_Module(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_MOSI_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_MOSI_Module(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_MISO_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_MISO_Module(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_SS_Channel(tRioStatusCode *status) = 0;

+   virtual unsigned char readChannels_SS_Module(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tAvailableToLoad_IfaceConstants;

+

+   virtual unsigned short readAvailableToLoad(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tReadReceivedData_IfaceConstants;

+

+   virtual void strobeReadReceivedData(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tSPI(const tSPI&);

+   void operator=(const tSPI&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_SPI_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSolenoid.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSolenoid.h
new file mode 100644
index 0000000..8627eea
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSolenoid.h
@@ -0,0 +1,50 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Solenoid_h__

+#define __nFRC_2012_1_6_4_Solenoid_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tSolenoid

+{

+public:

+   tSolenoid(){}

+   virtual ~tSolenoid(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tSolenoid* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+      kNumDO7_0Elements = 2,

+   } tDO7_0_IfaceConstants;

+

+   virtual void writeDO7_0(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;

+   virtual unsigned char readDO7_0(unsigned char bitfield_index, tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tSolenoid(const tSolenoid&);

+   void operator=(const tSolenoid&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Solenoid_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSysWatchdog.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSysWatchdog.h
new file mode 100644
index 0000000..2ef01ff
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSysWatchdog.h
@@ -0,0 +1,71 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_SysWatchdog_h__

+#define __nFRC_2012_1_6_4_SysWatchdog_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tSysWatchdog

+{

+public:

+   tSysWatchdog(){}

+   virtual ~tSysWatchdog(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tSysWatchdog* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+

+

+

+   typedef enum

+   {

+   } tCommand_IfaceConstants;

+

+   virtual void writeCommand(unsigned short value, tRioStatusCode *status) = 0;

+   virtual unsigned short readCommand(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tChallenge_IfaceConstants;

+

+   virtual unsigned char readChallenge(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tActive_IfaceConstants;

+

+   virtual void writeActive(bool value, tRioStatusCode *status) = 0;

+   virtual bool readActive(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimer_IfaceConstants;

+

+   virtual unsigned int readTimer(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tSysWatchdog(const tSysWatchdog&);

+   void operator=(const tSysWatchdog&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_SysWatchdog_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tWatchdog.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tWatchdog.h
new file mode 100644
index 0000000..a589eda
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tWatchdog.h
@@ -0,0 +1,108 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+// Do Not Edit... this file is generated!

+

+#ifndef __nFRC_2012_1_6_4_Watchdog_h__

+#define __nFRC_2012_1_6_4_Watchdog_h__

+

+#include "tSystemInterface.h"

+

+namespace nFPGA

+{

+namespace nFRC_2012_1_6_4

+{

+

+class tWatchdog

+{

+public:

+   tWatchdog(){}

+   virtual ~tWatchdog(){}

+

+   virtual tSystemInterface* getSystemInterface() = 0;

+   static tWatchdog* create(tRioStatusCode *status);

+

+   typedef enum

+   {

+      kNumSystems = 1,

+   } tIfaceConstants;

+

+   typedef

+   union{

+      struct{

+#ifdef __vxworks

+         unsigned SystemActive : 1;

+         unsigned Alive : 1;

+         unsigned SysDisableCount : 15;

+         unsigned DisableCount : 15;

+#else

+         unsigned DisableCount : 15;

+         unsigned SysDisableCount : 15;

+         unsigned Alive : 1;

+         unsigned SystemActive : 1;

+#endif

+      };

+      struct{

+         unsigned value : 32;

+      };

+   } tStatus;

+

+

+

+   typedef enum

+   {

+   } tStatus_IfaceConstants;

+

+   virtual tStatus readStatus(tRioStatusCode *status) = 0;

+   virtual bool readStatus_SystemActive(tRioStatusCode *status) = 0;

+   virtual bool readStatus_Alive(tRioStatusCode *status) = 0;

+   virtual unsigned short readStatus_SysDisableCount(tRioStatusCode *status) = 0;

+   virtual unsigned short readStatus_DisableCount(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tKill_IfaceConstants;

+

+   virtual void strobeKill(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tFeed_IfaceConstants;

+

+   virtual void strobeFeed(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tTimer_IfaceConstants;

+

+   virtual unsigned int readTimer(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tExpiration_IfaceConstants;

+

+   virtual void writeExpiration(unsigned int value, tRioStatusCode *status) = 0;

+   virtual unsigned int readExpiration(tRioStatusCode *status) = 0;

+

+

+   typedef enum

+   {

+   } tImmortal_IfaceConstants;

+

+   virtual void writeImmortal(bool value, tRioStatusCode *status) = 0;

+   virtual bool readImmortal(tRioStatusCode *status) = 0;

+

+

+

+

+private:

+   tWatchdog(const tWatchdog&);

+   void operator=(const tWatchdog&);

+};

+

+}

+}

+

+#endif // __nFRC_2012_1_6_4_Watchdog_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/printFpgaVersion.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/printFpgaVersion.h
new file mode 100644
index 0000000..788f1df
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/printFpgaVersion.h
@@ -0,0 +1,42 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+

+#ifndef __printFPGAVersion_h__

+#define __printFPGAVersion_h__

+

+namespace nFPGA

+{

+

+template<typename ttGlobal>

+inline void printFPGAVersion(ttGlobal &global)

+{

+   tRioStatusCode cleanStatus=0;

+   uint32_t hardwareGuid[4];

+   tSystemInterface &system = *global.getSystemInterface();

+   system.getHardwareFpgaSignature(hardwareGuid, &cleanStatus);

+   const uint32_t *softwareGuid = system.getExpectedFPGASignature();

+   printf("FPGA Hardware GUID: 0x");

+   for(int i=0; i<4; i++)

+   {

+      printf("%08X", hardwareGuid[i]);

+   }

+   printf("\n");

+   printf("FPGA Software GUID: 0x");

+   for(int i=0; i<4; i++)

+   {

+      printf("%08X", softwareGuid[i]);

+   }

+   printf("\n");

+   uint16_t fpgaHardwareVersion = global.readVersion(&cleanStatus);

+   uint16_t fpgaSoftwareVersion = system.getExpectedFPGAVersion();

+   printf("FPGA Hardware Version: %X\n", fpgaHardwareVersion);

+   printf("FPGA Software Version: %X\n", fpgaSoftwareVersion);

+   uint32_t fpgaHardwareRevision = global.readRevision(&cleanStatus);

+   uint32_t fpgaSoftwareRevision = system.getExpectedFPGARevision();

+   printf("FPGA Hardware Revision: %X.%X.%X\n", (fpgaHardwareRevision >> 20) & 0xFFF, (fpgaHardwareRevision >> 12) & 0xFF, fpgaHardwareRevision & 0xFFF);

+   printf("FPGA Software Revision: %X.%X.%X\n", (fpgaSoftwareRevision >> 20) & 0xFFF, (fpgaSoftwareRevision >> 12) & 0xFF, fpgaSoftwareRevision & 0xFFF);

+}

+

+}

+

+#endif // __printFPGAVersion_h__

+

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAChannelDescriptor.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAChannelDescriptor.h
new file mode 100644
index 0000000..8fa5935
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAChannelDescriptor.h
@@ -0,0 +1,17 @@
+// Describes the information needed to configure a DMA channel.

+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+

+#include <stdint.h>

+

+#ifndef __tDMAChannelDescriptor_h__

+#define __tDMAChannelDescriptor_h__

+

+struct tDMAChannelDescriptor

+{

+   uint32_t channel;

+   uint32_t baseAddress;

+   uint32_t depth;

+   bool targetToHost;

+};

+

+#endif // __tDMAChannelDescriptor_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAManager.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAManager.h
new file mode 100644
index 0000000..cb95203
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAManager.h
@@ -0,0 +1,41 @@
+// Class for handling DMA transfers.

+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+

+#ifndef __tDMAManager_h__

+#define __tDMAManager_h__

+

+#include "tSystem.h"

+#include <stdint.h>

+

+namespace nFPGA

+{

+class tDMAManager : public tSystem

+{

+public:

+   tDMAManager(uint32_t dmaChannel, uint32_t hostBufferSize, tRioStatusCode *status);

+   ~tDMAManager();

+   void start(tRioStatusCode *status);

+   void stop(tRioStatusCode *status);

+   bool isStarted() {return _started;}

+   void read(

+      uint32_t*      buf,

+      size_t         num,

+      uint32_t       timeout,

+      size_t*        remaining,

+      tRioStatusCode *status);

+   void write(

+      uint32_t*      buf,

+      size_t         num,

+      uint32_t       timeout,

+      size_t*        remaining,

+      tRioStatusCode *status);

+private:

+   bool _started;

+   uint32_t _dmaChannel;

+   uint32_t _hostBufferSize;

+

+};

+

+}

+

+#endif // __tDMAManager_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tInterruptManager.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tInterruptManager.h
new file mode 100644
index 0000000..cb6783d
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tInterruptManager.h
@@ -0,0 +1,61 @@
+// Class for handling interrupts.

+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+

+#ifndef __tInterruptManager_h__

+#define __tInterruptManager_h__

+

+#include "tSystem.h"

+

+namespace ni

+{

+   namespace dsc

+   {

+      namespace osdep

+      {

+         class CriticalSection;

+      }

+   }

+}

+

+namespace nFPGA

+{

+

+typedef void (*tInterruptHandler)(uint32_t interruptAssertedMask, void *param);

+

+class tInterruptManager : public tSystem

+{

+public:

+   tInterruptManager(uint32_t interruptMask, bool watcher, tRioStatusCode *status);

+   ~tInterruptManager();

+   void registerHandler(tInterruptHandler handler, void *param, tRioStatusCode *status);

+   uint32_t watch(int32_t timeoutInMs, bool ignorePrevious, tRioStatusCode *status);

+   void enable(tRioStatusCode *status);

+   void disable(tRioStatusCode *status);

+   bool isEnabled(tRioStatusCode *status);

+private:

+   class tInterruptThread;

+   friend class tInterruptThread;

+   void handler();

+   static int handlerWrapper(tInterruptManager *pInterrupt);

+

+   void acknowledge(tRioStatusCode *status);

+   void reserve(tRioStatusCode *status);

+   void unreserve(tRioStatusCode *status);

+   tInterruptHandler _handler;

+   uint32_t _interruptMask;

+   tInterruptThread *_thread;

+   NiFpga_IrqContext _rioContext;

+   bool _watcher;

+   bool _enabled;

+   void *_userParam;

+

+   // maintain the interrupts that are already dealt with.

+   static uint32_t _globalInterruptMask;

+   static ni::dsc::osdep::CriticalSection *_globalInterruptMaskSemaphore;

+};

+

+}

+

+

+#endif // __tInterruptManager_h__

+

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tSystem.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tSystem.h
new file mode 100644
index 0000000..b059e51
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tSystem.h
@@ -0,0 +1,48 @@
+// Base class for generated chip objects

+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+

+#ifndef __tSystem_h__

+#define __tSystem_h__

+

+#include "fpgainterfacecapi/NiFpga.h"

+typedef NiFpga_Status tRioStatusCode;

+

+#define FRC_FPGA_PRELOAD_BITFILE

+

+typedef uint32_t NiFpga_Session;

+

+namespace nFPGA

+{

+

+class tSystem

+{

+public:

+   tSystem(tRioStatusCode *status);

+   ~tSystem();

+   void getFpgaGuid(uint32_t *guid_ptr, tRioStatusCode *status);

+   void reset(tRioStatusCode *status);

+

+protected:

+   static NiFpga_Session _DeviceHandle;

+

+#ifdef FRC_FPGA_PRELOAD_BITFILE

+   void NiFpga_SharedOpen_common(const char*     bitfile);

+   NiFpga_Status NiFpga_SharedOpen(const char*     bitfile,

+                            const char*     signature,

+                            const char*     resource,

+                            uint32_t        attribute,

+                            NiFpga_Session* session);

+   NiFpga_Status NiFpgaLv_SharedOpen(const char* const     bitfile,

+                            const char* const     apiSignature,

+                            const char* const     resource,

+                            const uint32_t        attribute,

+                            NiFpga_Session* const session);

+private:

+    static char *_FileName;

+    static char *_Bitfile;

+#endif

+};

+

+}

+

+#endif // __tSystem_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tSystemInterface.h b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tSystemInterface.h
new file mode 100644
index 0000000..8594187
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/FRC_FPGA_ChipObject/tSystemInterface.h
@@ -0,0 +1,27 @@
+// Copyright (c) National Instruments 2008.  All Rights Reserved.

+

+#ifndef __tSystemInterface_h__

+#define __tSystemInterface_h__

+

+namespace nFPGA

+{

+

+class tSystemInterface

+{

+public:

+   tSystemInterface(){}

+   virtual ~tSystemInterface(){}

+

+   virtual const uint16_t getExpectedFPGAVersion()=0;

+   virtual const uint32_t getExpectedFPGARevision()=0;

+   virtual const uint32_t * const getExpectedFPGASignature()=0;

+   virtual void getHardwareFpgaSignature(uint32_t *guid_ptr, tRioStatusCode *status)=0;

+   virtual uint32_t getLVHandle(tRioStatusCode *status)=0;

+   virtual uint32_t getHandle()=0;

+   virtual void reset(tRioStatusCode *status)=0;

+};

+

+}

+

+#endif // __tSystemInterface_h__

+

diff --git a/aos/externals/allwpilib/hal/lib/Athena/HAL.cpp b/aos/externals/allwpilib/hal/lib/Athena/HAL.cpp
new file mode 100644
index 0000000..98a0126
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/HAL.cpp
@@ -0,0 +1,371 @@
+#include "HAL/HAL.hpp"
+
+#include "Port.h"
+#include "HAL/Errors.hpp"
+#include "ctre/ctre.h"
+#include "visa/visa.h"
+#include "ChipObject.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/UsageReporting.h"
+#include "NetworkCommunication/LoadOut.h"
+#include "NetworkCommunication/CANSessionMux.h"
+#include <fstream>
+#include <iostream>
+#include <unistd.h>
+#include <sys/prctl.h>
+#include <signal.h> // linux for kill
+const uint32_t solenoid_kNumDO7_0Elements = 8;
+const uint32_t dio_kNumSystems = tDIO::kNumSystems;
+const uint32_t interrupt_kNumSystems = tInterrupt::kNumSystems;
+const uint32_t kSystemClockTicksPerMicrosecond = 40;
+
+static tGlobal *global;
+static tSysWatchdog *watchdog;
+
+void* getPort(uint8_t pin)
+{
+	Port* port = new Port();
+	port->pin = pin;
+	port->module = 1;
+	return port;
+}
+
+/**
+ * @deprecated Uses module numbers
+ */
+void* getPortWithModule(uint8_t module, uint8_t pin)
+{
+	Port* port = new Port();
+	port->pin = pin;
+	port->module = module;
+	return port;
+}
+
+const char* getHALErrorMessage(int32_t code)
+{
+	switch(code) {
+		case 0:
+			return "";
+		case CTR_RxTimeout:
+			return CTR_RxTimeout_MESSAGE;
+		case CTR_TxTimeout:
+			return CTR_TxTimeout_MESSAGE;
+		case CTR_InvalidParamValue:
+			return CTR_InvalidParamValue_MESSAGE;
+		case CTR_UnexpectedArbId:
+			return CTR_UnexpectedArbId_MESSAGE;
+                case CTR_TxFailed:
+			return CTR_TxFailed_MESSAGE;
+                case CTR_SigNotUpdated:
+			return CTR_SigNotUpdated_MESSAGE;
+		case NiFpga_Status_FifoTimeout:
+			return NiFpga_Status_FifoTimeout_MESSAGE;
+		case NiFpga_Status_TransferAborted:
+			return NiFpga_Status_TransferAborted_MESSAGE;
+		case NiFpga_Status_MemoryFull: 
+			return NiFpga_Status_MemoryFull_MESSAGE;
+		case NiFpga_Status_SoftwareFault:
+			return NiFpga_Status_SoftwareFault_MESSAGE;
+		case NiFpga_Status_InvalidParameter:
+			return NiFpga_Status_InvalidParameter_MESSAGE;
+		case NiFpga_Status_ResourceNotFound:
+			return NiFpga_Status_ResourceNotFound_MESSAGE; 
+		case NiFpga_Status_ResourceNotInitialized:
+			return NiFpga_Status_ResourceNotInitialized_MESSAGE; 
+		case NiFpga_Status_HardwareFault:
+			return NiFpga_Status_HardwareFault_MESSAGE;
+		case NiFpga_Status_IrqTimeout:
+			return NiFpga_Status_IrqTimeout_MESSAGE;
+		case SAMPLE_RATE_TOO_HIGH:
+			return SAMPLE_RATE_TOO_HIGH_MESSAGE;
+		case VOLTAGE_OUT_OF_RANGE:
+			return VOLTAGE_OUT_OF_RANGE_MESSAGE;
+		case LOOP_TIMING_ERROR:
+			return LOOP_TIMING_ERROR_MESSAGE;
+		case SPI_WRITE_NO_MOSI:
+			return SPI_WRITE_NO_MOSI_MESSAGE;
+		case SPI_READ_NO_MISO:
+			return SPI_READ_NO_MISO_MESSAGE;
+		case SPI_READ_NO_DATA:
+			return SPI_READ_NO_DATA_MESSAGE;
+		case INCOMPATIBLE_STATE:
+			return INCOMPATIBLE_STATE_MESSAGE;
+		case NO_AVAILABLE_RESOURCES:
+			return NO_AVAILABLE_RESOURCES_MESSAGE;
+		case NULL_PARAMETER:
+			return NULL_PARAMETER_MESSAGE;
+		case ANALOG_TRIGGER_LIMIT_ORDER_ERROR:
+			return ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE;
+		case ANALOG_TRIGGER_PULSE_OUTPUT_ERROR:
+			return ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE;
+		case PARAMETER_OUT_OF_RANGE:
+			return PARAMETER_OUT_OF_RANGE_MESSAGE;
+		case ERR_CANSessionMux_InvalidBuffer:
+			return ERR_CANSessionMux_InvalidBuffer_MESSAGE;
+		case ERR_CANSessionMux_MessageNotFound:
+			return ERR_CANSessionMux_MessageNotFound_MESSAGE;
+		case WARN_CANSessionMux_NoToken:
+			return WARN_CANSessionMux_NoToken_MESSAGE;
+		case ERR_CANSessionMux_NotAllowed:
+			return ERR_CANSessionMux_NotAllowed_MESSAGE;
+		case ERR_CANSessionMux_NotInitialized:
+			return ERR_CANSessionMux_NotInitialized_MESSAGE;
+		case VI_ERROR_SYSTEM_ERROR:
+			return VI_ERROR_SYSTEM_ERROR_MESSAGE;
+		case VI_ERROR_INV_OBJECT:
+			return VI_ERROR_INV_OBJECT_MESSAGE;
+		case VI_ERROR_RSRC_LOCKED:
+			return VI_ERROR_RSRC_LOCKED_MESSAGE;
+		case VI_ERROR_RSRC_NFOUND:
+			return VI_ERROR_RSRC_NFOUND_MESSAGE;
+		case VI_ERROR_INV_RSRC_NAME:
+			return VI_ERROR_INV_RSRC_NAME_MESSAGE;
+		case VI_ERROR_QUEUE_OVERFLOW:
+			return VI_ERROR_QUEUE_OVERFLOW_MESSAGE;
+		case VI_ERROR_IO:
+			return VI_ERROR_IO_MESSAGE;
+		case VI_ERROR_ASRL_PARITY:
+			return VI_ERROR_ASRL_PARITY_MESSAGE;
+		case VI_ERROR_ASRL_FRAMING:
+			return VI_ERROR_ASRL_FRAMING_MESSAGE;
+		case VI_ERROR_ASRL_OVERRUN:
+			return VI_ERROR_ASRL_OVERRUN_MESSAGE;
+		case VI_ERROR_RSRC_BUSY:
+			return VI_ERROR_RSRC_BUSY_MESSAGE;
+		case VI_ERROR_INV_PARAMETER:
+			return VI_ERROR_INV_PARAMETER_MESSAGE;
+		default:
+			return "Unknown error status";
+	}
+}
+
+/**
+ * Return the FPGA Version number.
+ * For now, expect this to be competition year.
+ * @return FPGA Version number.
+ */
+uint16_t getFPGAVersion(int32_t *status)
+{
+	return global->readVersion(status);
+}
+
+/**
+ * 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)
+{
+	return global->readRevision(status);
+}
+
+/**
+ * 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)
+{
+	return global->readLocalTime(status);
+}
+
+/**
+ * Get the state of the "USER" button on the RoboRIO
+ * @return true if the button is currently pressed down
+ */
+bool getFPGAButton(int32_t *status)
+{
+	return global->readUserButton(status);
+}
+
+int HALSetErrorData(const char *errors, int errorsLength, int wait_ms)
+{
+	return setErrorData(errors, errorsLength, wait_ms);
+}
+
+int HALGetControlWord(HALControlWord *data)
+{
+	return FRC_NetworkCommunication_getControlWord((ControlWord_t*) data);
+}
+
+int HALGetAllianceStation(enum HALAllianceStationID *allianceStation)
+{
+	return FRC_NetworkCommunication_getAllianceStation((AllianceStationID_t*) allianceStation);
+}
+
+int HALGetJoystickAxes(uint8_t joystickNum, HALJoystickAxes *axes)
+{
+	return FRC_NetworkCommunication_getJoystickAxes(joystickNum, (JoystickAxes_t*) axes, kMaxJoystickAxes);
+}
+
+int HALGetJoystickPOVs(uint8_t joystickNum, HALJoystickPOVs *povs)
+{
+	return FRC_NetworkCommunication_getJoystickPOVs(joystickNum, (JoystickPOV_t*) povs, kMaxJoystickPOVs);
+}
+
+int HALGetJoystickButtons(uint8_t joystickNum, HALJoystickButtons *buttons)
+{
+	return FRC_NetworkCommunication_getJoystickButtons(joystickNum, &buttons->buttons, &buttons->count);
+}
+
+int HALGetJoystickDescriptor(uint8_t joystickNum, HALJoystickDescriptor *desc)
+{
+	return FRC_NetworkCommunication_getJoystickDesc(joystickNum, &desc->isXbox, &desc->type, (char *)(&desc->name), 
+		&desc->axisCount, &desc->axisTypes, &desc->buttonCount, &desc->povCount);
+}
+
+int HALSetJoystickOutputs(uint8_t joystickNum, uint32_t outputs, uint16_t leftRumble, uint16_t rightRumble)
+{
+	return FRC_NetworkCommunication_setJoystickOutputs(joystickNum, outputs, leftRumble, rightRumble);
+}
+
+int HALGetMatchTime(float *matchTime)
+{
+	return FRC_NetworkCommunication_getMatchTime(matchTime);
+}
+
+void HALSetNewDataSem(MULTIWAIT_ID sem)
+{
+	setNewDataSem(sem);
+}
+
+bool HALGetSystemActive(int32_t *status)
+{
+	return watchdog->readStatus_SystemActive(status);
+}
+	
+bool HALGetBrownedOut(int32_t *status)
+{
+	return !(watchdog->readStatus_PowerAlive(status));
+}
+
+/**
+ * Call this to start up HAL. This is required for robot programs.
+ */
+int HALInitialize(int mode)
+{
+    setlinebuf(stdin);
+    setlinebuf(stdout);
+
+    prctl(PR_SET_PDEATHSIG, SIGTERM);
+
+	FRC_NetworkCommunication_Reserve(nullptr);
+	// image 4; Fixes errors caused by multiple processes. Talk to NI about this
+	nFPGA::nRoboRIO_FPGANamespace::g_currentTargetClass =
+			nLoadOut::kTargetClass_RoboRIO;
+
+	int32_t status;
+	global = tGlobal::create(&status);
+	watchdog = tSysWatchdog::create(&status);
+
+	// Kill any previous robot programs
+	std::fstream fs;
+	// By making this both in/out, it won't give us an error if it doesnt exist
+	fs.open("/var/lock/frc.pid", std::fstream::in | std::fstream::out);
+	if (fs.bad())
+		return 0;
+
+	pid_t pid = 0;
+	if (!fs.eof() && !fs.fail())
+	{
+		fs >> pid;
+		//see if the pid is around, but we don't want to mess with init id=1, or ourselves
+		if (pid >= 2 && kill(pid, 0) == 0 && pid != getpid())
+		{
+			std::cout << "Killing previously running FRC program..."
+					<< std::endl;
+			kill(pid, SIGTERM); // try to kill it
+			delayMillis(100);
+			if (kill(pid, 0) == 0)
+			{
+				// still not successfull
+				if (mode == 0)
+				{
+					std::cout << "FRC pid " << pid
+							<< " did not die within 110ms. Aborting"
+							<< std::endl;
+					return 0; // just fail
+				}
+				else if (mode == 1) // kill -9 it
+					kill(pid, SIGKILL);
+				else
+				{
+					std::cout << "WARNING: FRC pid " << pid
+							<< " did not die within 110ms." << std::endl;
+				}
+			}
+
+		}
+	}
+	fs.close();
+	// we will re-open it write only to truncate the file
+	fs.open("/var/lock/frc.pid", std::fstream::out | std::fstream::trunc);
+	fs.seekp(0);
+	pid = getpid();
+	fs << pid << std::endl;
+	fs.close();
+	return 1;
+}
+
+void HALNetworkCommunicationObserveUserProgramStarting(void)
+{
+	FRC_NetworkCommunication_observeUserProgramStarting();
+}
+
+void HALNetworkCommunicationObserveUserProgramDisabled(void)
+{
+	FRC_NetworkCommunication_observeUserProgramDisabled();
+}
+
+void HALNetworkCommunicationObserveUserProgramAutonomous(void)
+{
+	FRC_NetworkCommunication_observeUserProgramAutonomous();
+}
+
+void HALNetworkCommunicationObserveUserProgramTeleop(void)
+{
+	FRC_NetworkCommunication_observeUserProgramTeleop();
+}
+
+void HALNetworkCommunicationObserveUserProgramTest(void)
+{
+	FRC_NetworkCommunication_observeUserProgramTest();
+}
+
+uint32_t HALReport(uint8_t resource, uint8_t instanceNumber, uint8_t context,
+		const char *feature)
+{
+	if(feature == NULL)
+	{
+		feature = "";
+	}
+
+	return FRC_NetworkCommunication_nUsageReporting_report(resource, instanceNumber, context, feature);
+}
+
+// TODO: HACKS
+void NumericArrayResize()
+{
+}
+void RTSetCleanupProc()
+{
+}
+void EDVR_CreateReference()
+{
+}
+void Occur()
+{
+}
+
+void imaqGetErrorText()
+{
+}
+void imaqGetLastError()
+{
+}
+void niTimestamp64()
+{
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Interrupts.cpp b/aos/externals/allwpilib/hal/lib/Athena/Interrupts.cpp
new file mode 100644
index 0000000..49bd2c9
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Interrupts.cpp
@@ -0,0 +1,120 @@
+#include "HAL/Interrupts.hpp"
+#include "ChipObject.h"
+
+struct Interrupt // FIXME: why is this internal?
+{
+	tInterrupt *anInterrupt;
+	tInterruptManager *manager;
+};
+
+void* initializeInterrupts(uint32_t interruptIndex, bool watcher, int32_t *status)
+{
+	Interrupt* anInterrupt = new Interrupt();
+	// Expects the calling leaf class to allocate an interrupt index.
+	anInterrupt->anInterrupt = tInterrupt::create(interruptIndex, status);
+	anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
+	anInterrupt->manager = new tInterruptManager(
+		(1 << interruptIndex) | (1 << (interruptIndex + 8)), watcher, status);
+	return anInterrupt;
+}
+
+void cleanInterrupts(void* interrupt_pointer, int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	delete anInterrupt->anInterrupt;
+	delete anInterrupt->manager;
+	anInterrupt->anInterrupt = NULL;
+	anInterrupt->manager = NULL;
+}
+
+/**
+ * In synchronous mode, wait for the defined interrupt to occur.
+ * @param timeout Timeout in seconds
+ * @param ignorePrevious If true, ignore interrupts that happened before
+ * waitForInterrupt was called.
+ * @return The mask of interrupts that fired.
+ */
+uint32_t waitForInterrupt(void* interrupt_pointer, double timeout, bool ignorePrevious, int32_t *status)
+{
+	uint32_t result;
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+
+	result = anInterrupt->manager->watch((int32_t)(timeout * 1e3), ignorePrevious, status);
+
+	// Don't report a timeout as an error - the return code is enough to tell
+	// that a timeout happened.
+	if(*status == -NiFpga_Status_IrqTimeout) {
+		*status = NiFpga_Status_Success;
+	}
+
+	return 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 enableInterrupts(void* interrupt_pointer, int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	anInterrupt->manager->enable(status);
+}
+
+/**
+ * Disable Interrupts without without deallocating structures.
+ */
+void disableInterrupts(void* interrupt_pointer, int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	anInterrupt->manager->disable(status);
+}
+
+/**
+ * Return the timestamp for the rising interrupt that occurred most recently.
+ * This is in the same time domain as GetClock().
+ * @return Timestamp in seconds since boot.
+ */
+double readRisingTimestamp(void* interrupt_pointer, int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	uint32_t timestamp = anInterrupt->anInterrupt->readRisingTimeStamp(status);
+	return timestamp * 1e-6;
+}
+
+/**
+* Return the timestamp for the falling interrupt that occurred most recently.
+* This is in the same time domain as GetClock().
+* @return Timestamp in seconds since boot.
+*/
+double readFallingTimestamp(void* interrupt_pointer, int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	uint32_t timestamp = anInterrupt->anInterrupt->readFallingTimeStamp(status);
+	return timestamp * 1e-6;
+}
+
+void requestInterrupts(void* interrupt_pointer, uint8_t routing_module, uint32_t routing_pin,
+		bool routing_analog_trigger, int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
+	anInterrupt->anInterrupt->writeConfig_Source_AnalogTrigger(routing_analog_trigger, status);
+	anInterrupt->anInterrupt->writeConfig_Source_Channel(routing_pin, status);
+	anInterrupt->anInterrupt->writeConfig_Source_Module(routing_module, status);
+}
+
+void attachInterruptHandler(void* interrupt_pointer, InterruptHandlerFunction handler, void* param,
+		int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	anInterrupt->manager->registerHandler(handler, param, status);
+}
+
+void setInterruptUpSourceEdge(void* interrupt_pointer, bool risingEdge, bool fallingEdge,
+		int32_t *status)
+{
+	Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+	anInterrupt->anInterrupt->writeConfig_RisingEdge(risingEdge, status);
+	anInterrupt->anInterrupt->writeConfig_FallingEdge(fallingEdge, status);
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/AICalibration.h b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/AICalibration.h
new file mode 100644
index 0000000..b2f366c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/AICalibration.h
@@ -0,0 +1,19 @@
+

+#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/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/CANInterfacePlugin.h b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/CANInterfacePlugin.h
new file mode 100644
index 0000000..77d992c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/CANInterfacePlugin.h
@@ -0,0 +1,82 @@
+// 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 NULL 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 NULL, unregister the current plugin.

+ */

+void FRC_NetworkCommunication_CANSessionMux_registerInterface(CANInterfacePlugin* interface);

+

+#endif // __CANInterfacePlugin_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/CANSessionMux.h b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/CANSessionMux.h
new file mode 100644
index 0000000..3f8a6f1
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/CANSessionMux.h
@@ -0,0 +1,64 @@
+// 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__

+

+#if defined(__vxworks)

+#include <vxWorks.h>

+#else

+#include <stdint.h>

+#endif

+

+#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/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/FRCComm.h b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/FRCComm.h
new file mode 100644
index 0000000..d708136
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/FRCComm.h
@@ -0,0 +1,129 @@
+/*************************************************************

+ * 					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

+#if defined(__vxworks)

+#include <vxWorks.h>

+#define EXPORT_FUNC

+#else

+#include <stdint.h>

+#include <pthread.h>

+#define EXPORT_FUNC

+#endif

+#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 {

+#ifndef __vxworks

+	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;

+#else

+	uint32_t control_reserved : 26;

+	uint32_t dsAttached:1;

+	uint32_t fmsAttached:1;

+	uint32_t eStop : 1;

+	uint32_t test :1;

+	uint32_t autonomous : 1;

+	uint32_t enabled : 1;

+#endif

+};

+

+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

+# if defined (__vxworks)

+	void EXPORT_FUNC setNewDataSem(SEM_ID);

+# else

+	void EXPORT_FUNC setNewDataSem(pthread_cond_t *);

+# endif

+#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/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/LoadOut.h b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/LoadOut.h
new file mode 100644
index 0000000..fce88a2
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/LoadOut.h
@@ -0,0 +1,58 @@
+

+#ifndef __LoadOut_h__

+#define __LoadOut_h__

+

+#ifdef SIMULATION

+#include <vxWorks_compat.h>

+#define EXPORT_FUNC __declspec(dllexport) __cdecl

+#elif defined (__vxworks)

+#include <vxWorks.h>

+#define EXPORT_FUNC

+#else

+#include <stdint.h>

+#define EXPORT_FUNC

+#endif

+

+#define kMaxModuleNumber 2

+namespace nLoadOut

+{

+#if defined(__vxworks) || 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(__vxworks) || 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(__vxworks) || 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/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/UsageReporting.h b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/UsageReporting.h
new file mode 100644
index 0000000..0ec2a3a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/NetworkCommunication/UsageReporting.h
@@ -0,0 +1,143 @@
+

+#ifndef __UsageReporting_h__

+#define __UsageReporting_h__

+

+#ifdef SIMULATION

+#include <vxWorks_compat.h>

+#define EXPORT_FUNC __declspec(dllexport) __cdecl

+#elif defined (__vxworks)

+#include <vxWorks.h>

+#define EXPORT_FUNC

+#else

+#include <stdint.h>

+#include <stdlib.h>

+#define EXPORT_FUNC

+#endif

+

+#define kUsageReporting_version 1

+

+namespace nUsageReporting

+{

+    typedef enum

+    {

+        kResourceType_Controller,

+        kResourceType_Module,

+        kResourceType_Language,

+        kResourceType_CANPlugin,

+        kResourceType_Accelerometer,

+        kResourceType_ADXL345,

+        kResourceType_AnalogChannel,

+        kResourceType_AnalogTrigger,

+        kResourceType_AnalogTriggerOutput,

+        kResourceType_CANJaguar,

+        kResourceType_Compressor,

+        kResourceType_Counter,

+        kResourceType_Dashboard,

+        kResourceType_DigitalInput,

+        kResourceType_DigitalOutput,

+        kResourceType_DriverStationCIO,

+        kResourceType_DriverStationEIO,

+        kResourceType_DriverStationLCD,

+        kResourceType_Encoder,

+        kResourceType_GearTooth,

+        kResourceType_Gyro,

+        kResourceType_I2C,

+        kResourceType_Framework,

+        kResourceType_Jaguar,

+        kResourceType_Joystick,

+        kResourceType_Kinect,

+        kResourceType_KinectStick,

+        kResourceType_PIDController,

+        kResourceType_Preferences,

+        kResourceType_PWM,

+        kResourceType_Relay,

+        kResourceType_RobotDrive,

+        kResourceType_SerialPort,

+        kResourceType_Servo,

+        kResourceType_Solenoid,

+        kResourceType_SPI,

+        kResourceType_Task,

+        kResourceType_Ultrasonic,

+        kResourceType_Victor,

+        kResourceType_Button,

+        kResourceType_Command,

+        kResourceType_AxisCamera,

+        kResourceType_PCVideoServer,

+        kResourceType_SmartDashboard,

+        kResourceType_Talon,

+        kResourceType_HiTechnicColorSensor,

+        kResourceType_HiTechnicAccel,

+        kResourceType_HiTechnicCompass,

+        kResourceType_SRF08,

+        kResourceType_AnalogOutput,

+        kResourceType_VictorSP,

+        kResourceType_TalonSRX,

+        kResourceType_CANTalonSRX,

+    } tResourceType;

+

+    typedef enum

+    {

+        kLanguage_LabVIEW = 1,

+        kLanguage_CPlusPlus = 2,

+        kLanguage_Java = 3,

+        kLanguage_Python = 4,

+

+        kCANPlugin_BlackJagBridge = 1,

+        kCANPlugin_2CAN = 2,

+

+        kFramework_Iterative = 1,

+        kFramework_Simple = 2,

+

+        kRobotDrive_ArcadeStandard = 1,

+        kRobotDrive_ArcadeButtonSpin = 2,

+        kRobotDrive_ArcadeRatioCurve = 3,

+        kRobotDrive_Tank = 4,

+        kRobotDrive_MecanumPolar = 5,

+        kRobotDrive_MecanumCartesian = 6,

+

+        kDriverStationCIO_Analog = 1,

+        kDriverStationCIO_DigitalIn = 2,

+        kDriverStationCIO_DigitalOut = 3,

+

+        kDriverStationEIO_Acceleration = 1,

+        kDriverStationEIO_AnalogIn = 2,

+        kDriverStationEIO_AnalogOut = 3,

+        kDriverStationEIO_Button = 4,

+        kDriverStationEIO_LED = 5,

+        kDriverStationEIO_DigitalIn = 6,

+        kDriverStationEIO_DigitalOut = 7,

+        kDriverStationEIO_FixedDigitalOut = 8,

+        kDriverStationEIO_PWM = 9,

+        kDriverStationEIO_Encoder = 10,

+        kDriverStationEIO_TouchSlider = 11,

+

+        kADXL345_SPI = 1,

+        kADXL345_I2C = 2,

+

+        kCommand_Scheduler = 1,

+

+        kSmartDashboard_Instance = 1,

+    } tInstances;

+

+    /**

+     * Report the usage of a resource of interest.

+     * 

+     * @param resource one of the values in the tResourceType above (max value 51).

+     * @param instanceNumber an index that identifies the resource instance.

+     * @param context an optional additional context number for some cases (such as module number).  Set to 0 to omit.

+     * @param feature a string to be included describing features in use on a specific resource.  Setting the same resource more than once allows you to change the feature string.

+     */

+    uint32_t EXPORT_FUNC report(tResourceType resource, uint8_t instanceNumber, uint8_t context = 0, const char *feature = NULL);

+}

+

+#ifdef __cplusplus

+extern "C" {

+#endif

+

+    uint32_t EXPORT_FUNC FRC_NetworkCommunication_nUsageReporting_report(uint8_t resource, uint8_t instanceNumber, uint8_t context, const char *feature);

+

+#ifdef __cplusplus

+}

+#endif

+

+#endif // __UsageReporting_h__

diff --git a/aos/externals/allwpilib/hal/lib/Athena/Notifier.cpp b/aos/externals/allwpilib/hal/lib/Athena/Notifier.cpp
new file mode 100644
index 0000000..c532512
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Notifier.cpp
@@ -0,0 +1,40 @@
+#include "HAL/Notifier.hpp"
+#include "ChipObject.h"
+
+static const uint32_t kTimerInterruptNumber = 28;
+
+struct Notifier
+{
+	tAlarm *alarm;
+	tInterruptManager *manager;
+};
+
+void* initializeNotifier(void (*ProcessQueue)(uint32_t, void*), int32_t *status)
+{
+	Notifier* notifier = new Notifier();
+	notifier->manager = new tInterruptManager(1 << kTimerInterruptNumber, false, status);
+	notifier->manager->registerHandler(ProcessQueue, NULL, status);
+	notifier->manager->enable(status);
+	notifier->alarm = tAlarm::create(status);
+	return notifier;
+}
+
+void cleanNotifier(void* notifier_pointer, int32_t *status)
+{
+	Notifier* notifier = (Notifier*)notifier_pointer;
+	notifier->alarm->writeEnable(false, status);
+	delete notifier->alarm;
+	notifier->alarm = NULL;
+	notifier->manager->disable(status);
+	delete notifier->manager;
+	notifier->manager = NULL;
+}
+
+void updateNotifierAlarm(void* notifier_pointer, uint32_t triggerTime, int32_t *status)
+{
+	Notifier* notifier = (Notifier*)notifier_pointer;
+	// write the first item in the queue into the trigger time
+	notifier->alarm->writeTriggerTime(triggerTime, status);
+	// Enable the alarm.  The hardware disables itself after each alarm.
+	notifier->alarm->writeEnable(true, status);
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/PDP.cpp b/aos/externals/allwpilib/hal/lib/Athena/PDP.cpp
new file mode 100644
index 0000000..6129c06
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/PDP.cpp
@@ -0,0 +1,61 @@
+#include "HAL/PDP.hpp"
+#include "ctre/PDP.h"
+static PDP pdp;
+
+double getPDPTemperature(int32_t *status) {
+	double temperature;
+	
+	*status = pdp.GetTemperature(temperature);
+	
+	return temperature;
+}
+
+double getPDPVoltage(int32_t *status) {
+	double voltage;
+	
+	*status = pdp.GetVoltage(voltage);
+	
+	return voltage;
+}
+
+double getPDPChannelCurrent(uint8_t channel, int32_t *status) {
+	double current;
+	
+	*status = pdp.GetChannelCurrent(channel, current);
+	
+	return current;
+}
+
+double getPDPTotalCurrent(int32_t *status) {
+	double current;
+	
+	*status = pdp.GetTotalCurrent(current);
+	
+	return current;
+}
+
+double getPDPTotalPower(int32_t *status) {
+	double power;
+	
+	*status = pdp.GetTotalPower(power);
+	
+	return power;
+}
+
+double getPDPTotalEnergy(int32_t *status) {
+	double energy;
+	
+	*status = pdp.GetTotalEnergy(energy);
+	
+	return energy;
+}
+
+void resetPDPTotalEnergy(int32_t *status) {
+	*status = pdp.ResetEnergy();
+}
+
+void clearPDPStickyFaults(int32_t *status) {
+	*status = pdp.ClearStickyFaults();
+}
+
+
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Port.h b/aos/externals/allwpilib/hal/lib/Athena/Port.h
new file mode 100644
index 0000000..8679c26
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Port.h
@@ -0,0 +1,7 @@
+#pragma once
+
+typedef struct port_t
+{
+	uint8_t pin;
+	uint8_t module;
+} Port;
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Power.cpp b/aos/externals/allwpilib/hal/lib/Athena/Power.cpp
new file mode 100644
index 0000000..34db043
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Power.cpp
@@ -0,0 +1,127 @@
+#include "HAL/Power.hpp"
+#include "ChipObject.h"
+
+static tPower *power = NULL;
+
+static void initializePower(int32_t *status) {
+	if(power == NULL) {
+		power = tPower::create(status);
+	}
+}
+
+/**
+ * Get the roboRIO input voltage
+ */
+float getVinVoltage(int32_t *status) {
+	initializePower(status);
+	return power->readVinVoltage(status) / 4.096f * 0.025733f - 0.029f;
+}
+
+/**
+ * Get the roboRIO input current
+ */
+float getVinCurrent(int32_t *status) {
+	initializePower(status);
+	return power->readVinCurrent(status) / 4.096f * 0.017042 - 0.071f;
+}
+
+/**
+ * Get the 6V rail voltage
+ */
+float getUserVoltage6V(int32_t *status) {
+	initializePower(status);
+	return power->readUserVoltage6V(status) / 4.096f * 0.007019f - 0.014f;
+}
+
+/**
+ * Get the 6V rail current
+ */
+float getUserCurrent6V(int32_t *status) {
+	initializePower(status);
+	return power->readUserCurrent6V(status) / 4.096f * 0.005566f - 0.009f;
+}
+
+/**
+ * Get the active state of the 6V rail
+ */
+bool getUserActive6V(int32_t *status) {
+	initializePower(status);
+	return power->readStatus_User6V(status) == 4;
+}
+
+/**
+ * Get the fault count for the 6V rail
+ */
+int getUserCurrentFaults6V(int32_t *status) {
+	initializePower(status);
+	return (int)power->readOverCurrentFaultCounts_OverCurrentFaultCount6V(status);
+}
+
+/**
+ * Get the 5V rail voltage
+ */
+float getUserVoltage5V(int32_t *status) {
+	initializePower(status);
+	return power->readUserVoltage5V(status) / 4.096f * 0.005962f - 0.013f;
+}
+
+/**
+ * Get the 5V rail current
+ */
+float getUserCurrent5V(int32_t *status) {
+	initializePower(status);
+	return power->readUserCurrent5V(status) / 4.096f * 0.001996f - 0.002f;
+}
+
+/**
+ * Get the active state of the 5V rail
+ */
+bool getUserActive5V(int32_t *status) {
+	initializePower(status);
+	return power->readStatus_User5V(status) == 4;
+}
+
+/**
+ * Get the fault count for the 5V rail
+ */
+int getUserCurrentFaults5V(int32_t *status) {
+	initializePower(status);
+	return (int)power->readOverCurrentFaultCounts_OverCurrentFaultCount5V(status);
+}
+
+unsigned char getUserStatus5V(int32_t *status) {
+	initializePower(status);
+	return power->readStatus_User5V(status);
+}
+
+/**
+ * Get the 3.3V rail voltage
+ */
+float getUserVoltage3V3(int32_t *status) {
+	initializePower(status);
+	return power->readUserVoltage3V3(status) / 4.096f * 0.004902f - 0.01f;
+}
+
+/**
+ * Get the 3.3V rail current
+ */
+float getUserCurrent3V3(int32_t *status) {
+	initializePower(status);
+	return power->readUserCurrent3V3(status) / 4.096f * 0.002486f - 0.003f;
+}
+
+/**
+ * Get the active state of the 3.3V rail
+ */
+bool getUserActive3V3(int32_t *status) {
+	initializePower(status);
+	return power->readStatus_User3V3(status) == 4;
+}
+
+/**
+ * Get the fault count for the 3.3V rail
+ */
+int getUserCurrentFaults3V3(int32_t *status) {
+	initializePower(status);
+	return (int)power->readOverCurrentFaultCounts_OverCurrentFaultCount3V3(status);
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Semaphore.cpp b/aos/externals/allwpilib/hal/lib/Athena/Semaphore.cpp
new file mode 100644
index 0000000..df30f3c
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Semaphore.cpp
@@ -0,0 +1,150 @@
+#include "HAL/Semaphore.hpp"
+#include "HAL/cpp/Synchronized.hpp"
+
+#include "Log.hpp"
+
+// set the logging level
+TLogLevel semaphoreLogLevel = logDEBUG;
+
+#define SEMAPHORE_LOG(level) \
+    if (level > semaphoreLogLevel) ; \
+    else Log().Get(level)
+
+// See: http://www.vxdev.com/docs/vx55man/vxworks/ref/semMLib.html
+const uint32_t SEMAPHORE_Q_FIFO= 0x01; // TODO: Support
+const uint32_t SEMAPHORE_Q_PRIORITY = 0x01; // TODO: Support
+const uint32_t SEMAPHORE_DELETE_SAFE = 0x04; // TODO: Support
+const uint32_t SEMAPHORE_INVERSION_SAFE = 0x08; // TODO: Support
+
+const int32_t SEMAPHORE_NO_WAIT = 0;
+const int32_t SEMAPHORE_WAIT_FOREVER = -1;
+
+const uint32_t SEMAPHORE_EMPTY = 0;
+const uint32_t SEMAPHORE_FULL = 1;
+
+class MutexInterface {
+ public:
+  virtual void lock() = 0;
+  virtual void unlock() = 0;
+  virtual bool try_lock() = 0;
+  virtual pthread_mutex_t *native_handle() = 0;
+  virtual ~MutexInterface() {}
+};
+
+template <typename MutexType>
+class TemplatedMutexWrapper : public MutexInterface {
+ public:
+  virtual void lock() { m_.lock(); }
+  virtual void unlock() { m_.unlock(); }
+  virtual bool try_lock() { return m_.try_lock(); }
+  pthread_mutex_t *native_handle() { return m_.native_handle(); }
+
+ private:
+  MutexType m_;
+};
+
+MUTEX_ID initializeMutexRecursive()
+{
+  return new TemplatedMutexWrapper<ReentrantMutex>();
+}
+
+MUTEX_ID initializeMutexNormal()
+{
+  return new TemplatedMutexWrapper<Mutex>();
+}
+
+void deleteMutex(MUTEX_ID mutex)
+{
+	delete mutex;
+}
+
+/**
+ * Lock the semaphore, blocking until it's available.
+ * @return 0 for success, -1 for error. If -1, the error will be in errno.
+ */
+int8_t lockMutex(MUTEX_ID mutex)
+{
+    mutex->lock();
+    return 0;
+}
+
+/**
+ * Tries to lock the mutex.
+ * @return 1 if we got the lock, 0 otherwise.
+ */
+int8_t tryLockMutex(MUTEX_ID mutex)
+{
+    return mutex->try_lock();
+}
+
+/**
+ * Unlock the semaphore.
+ * @return 0 for success, -1 for error. If -1, the error will be in errno.
+ */
+int8_t unlockMutex(MUTEX_ID mutex)
+{
+	mutex->unlock();
+  return 0;
+}
+
+SEMAPHORE_ID initializeSemaphore(uint32_t initial_value) {
+  SEMAPHORE_ID sem = new sem_t;
+  sem_init(sem, 0, initial_value);
+  return sem;
+}
+
+void deleteSemaphore(SEMAPHORE_ID sem) {
+  sem_destroy(sem);
+  delete sem;
+}
+
+/**
+ * Lock the semaphore, blocking until it's available.
+ * @return 0 for success, -1 for error. If -1, the error will be in errno.
+ */
+int8_t takeSemaphore(SEMAPHORE_ID sem)
+{
+    return sem_wait(sem);
+}
+
+int8_t tryTakeSemaphore(SEMAPHORE_ID sem)
+{
+    return sem_trywait(sem);
+}
+
+/**
+ * Unlock the semaphore.
+ * @return 0 for success, -1 for error. If -1, the error will be in errno.
+ */
+int8_t giveSemaphore(SEMAPHORE_ID sem)
+{
+  return sem_post(sem);
+}
+
+
+MULTIWAIT_ID initializeMultiWait() {
+  pthread_condattr_t attr;
+  pthread_condattr_init(&attr);
+  MULTIWAIT_ID cond = new pthread_cond_t();
+  pthread_cond_init(cond, &attr);
+  pthread_condattr_destroy(&attr);
+  return cond;
+}
+
+void deleteMultiWait(MULTIWAIT_ID sem) {
+  pthread_cond_destroy(sem);
+  delete sem;
+}
+
+int8_t takeMultiWait(MULTIWAIT_ID sem, MUTEX_ID m, int32_t timeout) {
+  lockMutex(m);
+  int8_t val = pthread_cond_wait(sem, m->native_handle());
+  unlockMutex(m);
+  return val;
+}
+
+int8_t giveMultiWait(MULTIWAIT_ID sem) {
+  return pthread_cond_broadcast(sem);
+}
+
+
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Solenoid.cpp b/aos/externals/allwpilib/hal/lib/Athena/Solenoid.cpp
new file mode 100644
index 0000000..3b8bfaf
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Solenoid.cpp
@@ -0,0 +1,90 @@
+
+#include "HAL/Solenoid.hpp"
+
+#include "Port.h"
+#include "HAL/Errors.hpp"
+#include "ChipObject.h"
+#include "HAL/cpp/Synchronized.hpp"
+#include "NetworkCommunication/LoadOut.h"
+#include "ctre/PCM.h"
+
+static const int NUM_MODULE_NUMBERS = 63;
+
+PCM *modules[NUM_MODULE_NUMBERS] = { NULL };
+
+struct solenoid_port_t {
+	PCM *module;
+	uint32_t pin;
+};
+
+void initializePCM(int module) {
+	if(!modules[module]) {
+		modules[module] = new PCM(module);
+	}
+}
+
+void* initializeSolenoidPort(void *port_pointer, int32_t *status) {
+	Port* port = (Port*) port_pointer;
+	initializePCM(port->module);
+	
+	solenoid_port_t *solenoid_port = new solenoid_port_t;
+	solenoid_port->module = modules[port->module];
+	solenoid_port->pin = port->pin;
+
+	return solenoid_port;
+}
+
+bool checkSolenoidModule(uint8_t module) {
+	return module < NUM_MODULE_NUMBERS;
+}
+
+bool getSolenoid(void* solenoid_port_pointer, int32_t *status) {
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+	bool value;
+
+	*status = port->module->GetSolenoid(port->pin, value);
+
+	return value;
+}
+
+void setSolenoid(void* solenoid_port_pointer, bool value, int32_t *status) {
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+
+	port->module->SetSolenoids(1 << port->pin, value ? 0xFF : 0x00);
+}
+
+void setSolenoids(void* solenoid_port_pointer, uint8_t value, uint8_t mask, int32_t *status) {
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+
+	port->module->SetSolenoids(value, mask);
+}
+
+int getPCMSolenoidBlackList(void* solenoid_port_pointer, int32_t *status){
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+	UINT8 value;
+	
+	*status = port->module->GetSolenoidBlackList(value);
+
+	return value;
+}
+bool getPCMSolenoidVoltageStickyFault(void* solenoid_port_pointer, int32_t *status){
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+	bool value;
+
+	*status = port->module->GetSolenoidStickyFault(value);
+
+	return value;
+}
+bool getPCMSolenoidVoltageFault(void* solenoid_port_pointer, int32_t *status){
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+	bool value;
+
+	*status = port->module->GetSolenoidFault(value);
+
+	return value;
+}
+void clearAllPCMStickyFaults_sol(void *solenoid_port_pointer, int32_t *status){
+	solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+	
+	*status = port->module->ClearStickyFaults();
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Task.cpp b/aos/externals/allwpilib/hal/lib/Athena/Task.cpp
new file mode 100644
index 0000000..2be66f5
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Task.cpp
@@ -0,0 +1,104 @@
+
+#include "HAL/Task.hpp"
+
+#include <stdio.h>
+#include <signal.h>
+
+#ifndef OK
+#define OK		0
+#endif /* OK */
+#ifndef ERROR
+#define ERROR		(-1)
+#endif /* ERROR */
+
+const uint32_t VXWORKS_FP_TASK = 0x01000000;
+const int32_t HAL_objLib_OBJ_ID_ERROR = -1; // TODO: update to relevant TaskIDError
+const int32_t HAL_objLib_OBJ_DELETED = -1; // TODO: update to relevant TaskDeletedError
+const int32_t HAL_taskLib_ILLEGAL_OPTIONS = -1; // TODO: update to relevant TaskOptionsError
+const int32_t HAL_memLib_NOT_ENOUGH_MEMORY = -1; // TODO: update to relevant TaskMemoryError
+const int32_t HAL_taskLib_ILLEGAL_PRIORITY = -1; // TODO: update to relevant TaskPriorityError
+
+struct TaskArgs {
+	FUNCPTR fun;
+	char* name;
+	pthread_t** task;
+	uint32_t arg0, arg1, arg2, arg3, arg4,
+	         arg5, arg6, arg7, arg8, arg9;
+};
+
+void* startRoutine(void* data) {
+	TaskArgs* args = (TaskArgs*) data;
+	printf("[HAL] Starting task %s...\n", args->name);
+	int val = args->fun(args->arg0, args->arg1, args->arg2, args->arg3, args->arg4,
+			         args->arg5, args->arg6, args->arg7, args->arg8, args->arg9);
+	printf("[HAL] Exited task %s with code %i\n", args->name, val);
+	*args->task = NULL;
+	int* ret = new int(); *ret = val;
+	return ret;
+}
+
+TASK spawnTask(char * name, int priority, int options, int stackSize, 
+		       FUNCPTR entryPt, uint32_t arg0, uint32_t arg1, uint32_t arg2,
+		       uint32_t arg3, uint32_t arg4, uint32_t arg5, uint32_t arg6,
+		       uint32_t arg7, uint32_t arg8, uint32_t arg9) {
+  printf("[HAL] Spawning task %s...\n", name);
+  pthread_t* task = new pthread_t;
+  pthread_attr_t* attr = new pthread_attr_t;
+  pthread_attr_init(attr);
+  TaskArgs* args = new TaskArgs();
+  args->fun = entryPt;
+  args->name = name;
+  args->task = new pthread_t*;
+  *args->task = task;
+  args->arg0 = arg0; args->arg1 = arg1; args->arg2 = arg2; args->arg3 = arg3; args->arg4 = arg4;
+  args->arg5 = arg5; args->arg6 = arg6; args->arg7 = arg7; args->arg8 = arg8; args->arg9 = arg9;
+  if (pthread_create(task, attr, startRoutine, args) == 0) {
+	  printf("[HAL] Success\n");
+	  pthread_detach(*task);
+  } else {
+	  printf("[HAL] Failure\n");
+	  task = NULL;
+  }
+  pthread_attr_destroy(attr);
+  return task;
+}
+
+STATUS restartTask(TASK task) {
+  return ERROR; // TODO: implement;
+}
+
+STATUS deleteTask(TASK task) {
+  return ERROR; // TODO: implement
+}
+
+STATUS isTaskReady(TASK task) {
+  return ERROR; // TODO: implement
+}
+
+STATUS isTaskSuspended(TASK task) {
+  return ERROR; // TODO: implement
+}
+
+STATUS suspendTask(TASK task) {
+  return ERROR; // TODO: implement
+}
+
+STATUS resumeTask(TASK task) {
+  return ERROR; // TODO: implement
+}
+
+STATUS verifyTaskID(TASK task) {
+  if (task != NULL && pthread_kill(*task, 0) == 0) {
+	return OK;
+  } else {
+	return ERROR;
+  }
+}
+
+STATUS setTaskPriority(TASK task, int priority) {
+  return ERROR; // TODO: implement
+}
+
+STATUS getTaskPriority(TASK task, int* priority) {
+  return ERROR; // TODO: implement
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/Utilities.cpp b/aos/externals/allwpilib/hal/lib/Athena/Utilities.cpp
new file mode 100644
index 0000000..b34677f
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/Utilities.cpp
@@ -0,0 +1,44 @@
+#include "HAL/Utilities.hpp"
+#include <time.h>
+
+const int32_t HAL_NO_WAIT = 0;
+const int32_t HAL_WAIT_FOREVER = -1;
+
+void delayTicks(int32_t ticks)
+{
+	struct timespec test, remaining;
+	test.tv_sec = 0;
+	test.tv_nsec = ticks * 3;
+
+	/* Sleep until the requested number of ticks has passed, with additional
+		time added if nanosleep is interrupted. */
+	while(nanosleep(&test, &remaining) == -1) {
+		test = remaining;
+	}
+}
+
+void delayMillis(double ms)
+{
+	struct timespec test, remaining;
+	test.tv_sec = ms / 1000;
+	test.tv_nsec = 1000 * (((uint64_t)ms) % 1000000);
+
+	/* Sleep until the requested number of milliseconds has passed, with
+		additional time added if nanosleep is interrupted. */
+	while(nanosleep(&test, &remaining) == -1) {
+		test = remaining;
+	}
+}
+
+void delaySeconds(double s)
+{
+	struct timespec test, remaining;
+	test.tv_sec = (int)s;
+	test.tv_nsec = (s - (int)s) * 1000000000.0;
+
+	/* Sleep until the requested number of seconds has passed, with additional
+		time added if nanosleep is interrupted. */
+	while(nanosleep(&test, &remaining) == -1) {
+		test = remaining;
+	}
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/cpp/Resource.cpp b/aos/externals/allwpilib/hal/lib/Athena/cpp/Resource.cpp
new file mode 100644
index 0000000..ceed1b1
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/cpp/Resource.cpp
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HAL/cpp/Resource.hpp"
+#include "HAL/Errors.hpp"
+#include <cstddef>
+
+ReentrantMutex Resource::m_createLock;
+
+/**
+ * Allocate storage for a new instance of Resource.
+ * Allocate a bool array of values that will get initialized to indicate that no resources
+ * have been allocated yet. The indicies of the resources are [0 .. elements - 1].
+ */
+Resource::Resource(uint32_t elements)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_createLock);
+	m_size = elements;
+	m_isAllocated = new bool[m_size];
+	for (uint32_t i=0; i < m_size; i++)
+	{
+		m_isAllocated[i] = false;
+	}
+}
+
+/**
+ * Factory method to create a Resource allocation-tracker *if* needed.
+ *
+ * @param r -- address of the caller's Resource pointer. If *r == NULL, this
+ *    will construct a Resource and make *r point to it. If *r != NULL, i.e.
+ *    the caller already has a Resource instance, this won't do anything.
+ * @param elements -- the number of elements for this Resource allocator to
+ *    track, that is, it will allocate resource numbers in the range
+ *    [0 .. elements - 1].
+ */
+/*static*/ void Resource::CreateResourceObject(Resource **r, uint32_t elements)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_createLock);
+	if (*r == NULL)
+	{
+		*r = new Resource(elements);
+	}
+}
+
+/**
+ * Delete the allocated array or resources.
+ * This happens when the module is unloaded (provided it was statically allocated).
+ */
+Resource::~Resource()
+{
+	delete[] m_isAllocated;
+}
+
+/**
+ * Allocate a resource.
+ * When a resource is requested, mark it allocated. In this case, a free resource value
+ * within the range is located and returned after it is marked allocated.
+ */
+uint32_t Resource::Allocate(const char *resourceDesc)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_allocateLock);
+	for (uint32_t i=0; i < m_size; i++)
+	{
+		if (!m_isAllocated[i])
+		{
+			m_isAllocated[i] = true;
+			return i;
+		}
+	}
+	// TODO: wpi_setWPIErrorWithContext(NoAvailableResources, resourceDesc);
+	return ~0ul;
+}
+
+/**
+ * Allocate a specific resource value.
+ * The user requests a specific resource value, i.e. channel number and it is verified
+ * unallocated, then returned.
+ */
+uint32_t Resource::Allocate(uint32_t index, const char *resourceDesc)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_allocateLock);
+	if (index >= m_size)
+	{
+		// TODO: wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc);
+		return ~0ul;
+	}
+	if ( m_isAllocated[index] )
+	{
+		// TODO: wpi_setWPIErrorWithContext(ResourceAlreadyAllocated, resourceDesc);
+		return ~0ul;
+	}
+	m_isAllocated[index] = true;
+	return index;
+}
+
+
+/**
+ * Free an allocated resource.
+ * After a resource is no longer needed, for example a destructor is called for a channel assignment
+ * class, Free will release the resource value so it can be reused somewhere else in the program.
+ */
+void Resource::Free(uint32_t index)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_allocateLock);
+	if (index == ~0ul) return;
+	if (index >= m_size)
+	{
+		// TODO: wpi_setWPIError(NotAllocated);
+		return;
+	}
+	if (!m_isAllocated[index])
+	{
+		// TODO: wpi_setWPIError(NotAllocated);
+		return;
+	}
+	m_isAllocated[index] = false;
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/cpp/Synchronized.cpp b/aos/externals/allwpilib/hal/lib/Athena/cpp/Synchronized.cpp
new file mode 100644
index 0000000..cfc2ad5
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/cpp/Synchronized.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HAL/cpp/Synchronized.hpp"
+#include "HAL/Semaphore.hpp"
+
+/**
+ * Synchronized class deals with critical regions.
+ * Declare a Synchronized object at the beginning of a block. That will take the semaphore.
+ * When the code exits from the block it will call the destructor which will give the semaphore.
+ * This ensures that no matter how the block is exited, the semaphore will always be released.
+ * @param semaphore The semaphore controlling this critical region.
+ */
+Synchronized::Synchronized(SEMAPHORE_ID semaphore)
+    : m_semaphore(semaphore) {
+  takeSemaphore(m_semaphore);
+}
+
+/**
+ * This destructor unlocks the semaphore.
+ */
+Synchronized::~Synchronized()
+{
+	giveSemaphore(m_semaphore);
+}
diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/CanTalonSRX.cpp b/aos/externals/allwpilib/hal/lib/Athena/ctre/CanTalonSRX.cpp
new file mode 100644
index 0000000..43e6aaa
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/CanTalonSRX.cpp
@@ -0,0 +1,1242 @@
+/**

+ * @brief CAN TALON SRX driver.

+ *

+ * The TALON SRX is designed to instrument all runtime signals periodically.  The default periods are chosen to support 16 TALONs

+ * with 10ms update rate for control (throttle or setpoint).  However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate

+ * The getters for these unsolicited signals are auto generated at the bottom of this module.

+ *

+ * Likewise most control signals are sent periodically using the fire-and-forget CAN API.

+ * The setters for these unsolicited signals are auto generated at the bottom of this module.

+ *

+ * Signals that are not available in an unsolicited fashion are the Close Loop gains.

+ * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once

+ * 	or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application.  These parameters are saved to flash so once they are

+ * 	loaded in the TALON, they will persist through power cycles and mode changes.

+ *

+ * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from

+ * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.

+ *

+ * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters.  Most likely

+ * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.

+ * If this API is used, be mindful of the CAN utilization reported in the driver station.

+ *

+ * Encoder position is measured in encoder edges.  Every edge is counted (similar to roboRIO 4X mode).

+ * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).

+ * Use SetFeedbackDeviceSelect to select which sensor type you need.  Once you do that you can use GetSensorPosition()

+ * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by default).

+ * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.

+ *

+ * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.

+ * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms.  This allows easy instrumentation

+ * for "in the pits" checking of all sensors regardless of modeselect.  The 100ms rate is overridable for teams who want to acquire sensor

+ * data for processing, not just instrumentation.  Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.

+ *

+ * Velocity is in position ticks / 100ms.

+ *

+ * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).

+ *  This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).

+ *

+ * Pos and velocity close loops are calc'd as

+ * 		err = target - posOrVel.

+ * 		iErr += err;

+ * 		if(   (IZone!=0)  and  abs(err) > IZone)

+ * 			ClearIaccum()

+ * 		output = P X err + I X iErr + D X dErr + F X target

+ * 		dErr = err - lastErr

+ *	P, I,and D gains are always positive. F can be negative.

+ *	Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.

+ *	Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.

+ *

+ * P gain is specified in throttle per error tick.  For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1

+ * 		ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

+ *

+ * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)

+ *  	for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

+ *  	Close loop and integral accumulator runs every 1ms.

+ *

+ * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)

+ * 	per change of 1 unit (ADC or encoder) per ms.

+ *

+ * I Zone is specified in the same units as sensor position (ADC units or quadrature edges).  If pos/vel error is outside of

+ * 		this value, the integrated error will auto-clear...

+ * 		if(   (IZone!=0)  and  abs(err) > IZone)

+ * 			ClearIaccum()

+ * 		...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.

+ *

+ * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable ramping.

+ * 		Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.

+ *

+ * auto generated using spreadsheet and WpiClassGen.csproj

+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967

+ */

+#include "CanTalonSRX.h"

+#include "NetworkCommunication/CANSessionMux.h"	//CAN Comm

+#include <string.h> // memset

+#include <unistd.h> // usleep

+

+#define STATUS_1  		0x02041400

+#define STATUS_2  		0x02041440

+#define STATUS_3  		0x02041480

+#define STATUS_4  		0x020414C0

+#define STATUS_5  		0x02041500

+#define STATUS_6  		0x02041540

+#define STATUS_7  		0x02041580

+

+#define CONTROL_1 			0x02040000

+#define CONTROL_2 			0x02040040

+#define CONTROL_3 			0x02040080

+

+#define EXPECTED_RESPONSE_TIMEOUT_MS	(200)

+#define GET_STATUS1() CtreCanNode::recMsg<TALON_Status_1_General_10ms_t		> rx = GetRx<TALON_Status_1_General_10ms_t>(STATUS_1	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS2() CtreCanNode::recMsg<TALON_Status_2_Feedback_20ms_t	> rx = GetRx<TALON_Status_2_Feedback_20ms_t>(STATUS_2	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS3() CtreCanNode::recMsg<TALON_Status_3_Enc_100ms_t		> rx = GetRx<TALON_Status_3_Enc_100ms_t>(STATUS_3		  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS4() CtreCanNode::recMsg<TALON_Status_4_AinTempVbat_100ms_t> rx = GetRx<TALON_Status_4_AinTempVbat_100ms_t>(STATUS_4 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS5() CtreCanNode::recMsg<TALON_Status_5_Startup_OneShot_t	> rx = GetRx<TALON_Status_5_Startup_OneShot_t>(STATUS_5	  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS6() CtreCanNode::recMsg<TALON_Status_6_Eol_t				> rx = GetRx<TALON_Status_6_Eol_t>(STATUS_6				  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS7() CtreCanNode::recMsg<TALON_Status_7_Debug_200ms_t		> rx = GetRx<TALON_Status_7_Debug_200ms_t>(STATUS_7		  | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)

+

+#define PARAM_REQUEST 		0x02041800

+#define PARAM_RESPONSE 		0x02041840

+#define PARAM_SET			0x02041880

+

+const int kParamArbIdValue = 	PARAM_RESPONSE;

+const int kParamArbIdMask = 	0xFFFFFFFF;

+

+const double FLOAT_TO_FXP = (double)0x400000;

+const double FXP_TO_FLOAT = 0.0000002384185791015625;

+

+/* encoder/decoders */

+/** control */

+typedef struct _TALON_Control_1_General_10ms_t {

+	unsigned TokenH:8;

+	unsigned TokenL:8;

+	unsigned DemandH:8;

+	unsigned DemandM:8;

+	unsigned DemandL:8;

+	unsigned ProfileSlotSelect:1;

+	unsigned FeedbackDeviceSelect:4;

+	unsigned OverrideLimitSwitchEn:3;

+	unsigned RevFeedbackSensor:1;

+	unsigned RevMotDuringCloseLoopEn:1;

+	unsigned OverrideBrakeType:2;

+	unsigned ModeSelect:4;

+	unsigned RampThrottle:8;

+} TALON_Control_1_General_10ms_t ;

+typedef struct _TALON_Control_2_Rates_OneShot_t {

+	unsigned Status1Ms:8;

+	unsigned Status2Ms:8;

+	unsigned Status3Ms:8;

+	unsigned Status4Ms:8;

+} TALON_Control_2_Rates_OneShot_t ;

+typedef struct _TALON_Control_3_ClearFlags_OneShot_t {

+	unsigned ZeroFeedbackSensor:1;

+	unsigned ClearStickyFaults:1;

+} TALON_Control_3_ClearFlags_OneShot_t ;

+

+/** status */

+typedef struct _TALON_Status_1_General_10ms_t {

+	unsigned CloseLoopErrH:8;

+	unsigned CloseLoopErrM:8;

+	unsigned CloseLoopErrL:8;

+	unsigned AppliedThrottle_h3:3;

+	unsigned Fault_RevSoftLim:1;

+	unsigned Fault_ForSoftLim:1;

+	unsigned TokLocked:1;

+	unsigned LimitSwitchClosedRev:1;

+	unsigned LimitSwitchClosedFor:1;

+	unsigned AppliedThrottle_l8:8;

+	unsigned ModeSelect_h1:1;

+	unsigned FeedbackDeviceSelect:4;

+	unsigned LimitSwitchEn:3;

+	unsigned Fault_HardwareFailure:1;

+	unsigned Fault_RevLim:1;

+	unsigned Fault_ForLim:1;

+	unsigned Fault_UnderVoltage:1;

+	unsigned Fault_OverTemp:1;

+	unsigned ModeSelect_b3:3;

+	unsigned TokenSeed:8;

+} TALON_Status_1_General_10ms_t ;

+typedef struct _TALON_Status_2_Feedback_20ms_t {

+	unsigned SensorPositionH:8;

+	unsigned SensorPositionM:8;

+	unsigned SensorPositionL:8;

+	unsigned SensorVelocityH:8;

+	unsigned SensorVelocityL:8;

+	unsigned Current_h8:8;

+	unsigned StckyFault_RevSoftLim:1;

+	unsigned StckyFault_ForSoftLim:1;

+	unsigned StckyFault_RevLim:1;

+	unsigned StckyFault_ForLim:1;

+	unsigned StckyFault_UnderVoltage:1;

+	unsigned StckyFault_OverTemp:1;

+	unsigned Current_l2:2;

+	unsigned reserved:6;

+	unsigned ProfileSlotSelect:1;

+	unsigned BrakeIsEnabled:1;

+} TALON_Status_2_Feedback_20ms_t ;

+typedef struct _TALON_Status_3_Enc_100ms_t {

+	unsigned EncPositionH:8;

+	unsigned EncPositionM:8;

+	unsigned EncPositionL:8;

+	unsigned EncVelH:8;

+	unsigned EncVelL:8;

+	unsigned EncIndexRiseEventsH:8;

+	unsigned EncIndexRiseEventsL:8;

+	unsigned reserved:5;

+	unsigned QuadIdxpin:1;

+	unsigned QuadBpin:1;

+	unsigned QuadApin:1;

+} TALON_Status_3_Enc_100ms_t ;

+typedef struct _TALON_Status_4_AinTempVbat_100ms_t {

+	unsigned AnalogInWithOvH:8;

+	unsigned AnalogInWithOvM:8;

+	unsigned AnalogInWithOvL:8;

+	unsigned AnalogInVelH:8;

+	unsigned AnalogInVelL:8;

+	unsigned Temp:8;

+	unsigned BatteryV:8;

+	unsigned reserved:8;

+} TALON_Status_4_AinTempVbat_100ms_t ;

+typedef struct _TALON_Status_5_Startup_OneShot_t {

+	unsigned ResetCountH:8;

+	unsigned ResetCountL:8;

+	unsigned ResetFlagsH:8;

+	unsigned ResetFlagsL:8;

+	unsigned FirmVersH:8;

+	unsigned FirmVersL:8;

+} TALON_Status_5_Startup_OneShot_t ;

+typedef struct _TALON_Status_6_Eol_t {

+	unsigned currentAdcUncal_h2:2;

+	unsigned reserved1:5;

+	unsigned SpiCsPin_GadgeteerPin6:1;

+	unsigned currentAdcUncal_l8:8;

+	unsigned tempAdcUncal_h2:2;

+	unsigned reserved2:6;

+	unsigned tempAdcUncal_l8:8;

+	unsigned vbatAdcUncal_h2:2;

+	unsigned reserved3:6;

+	unsigned vbatAdcUncal_l8:8;

+	unsigned analogAdcUncal_h2:2;

+	unsigned reserved4:6;

+	unsigned analogAdcUncal_l8:8;

+} TALON_Status_6_Eol_t ;

+typedef struct _TALON_Status_7_Debug_200ms_t {

+	unsigned TokenizationFails_h8:8;

+	unsigned TokenizationFails_l8:8;

+	unsigned LastFailedToken_h8:8;

+	unsigned LastFailedToken_l8:8;

+	unsigned TokenizationSucceses_h8:8;

+	unsigned TokenizationSucceses_l8:8;

+} TALON_Status_7_Debug_200ms_t ;

+typedef struct _TALON_Param_Request_t {

+	unsigned ParamEnum:8;

+} TALON_Param_Request_t ;

+typedef struct _TALON_Param_Response_t {

+	unsigned ParamEnum:8;

+	unsigned ParamValueL:8;

+	unsigned ParamValueML:8;

+	unsigned ParamValueMH:8;

+	unsigned ParamValueH:8;

+} TALON_Param_Response_t ;

+

+

+CanTalonSRX::CanTalonSRX(int deviceNumber,int controlPeriodMs): CtreCanNode(deviceNumber), _can_h(0), _can_stat(0)

+{

+	/* bound period to be within [1 ms,95 ms] */

+	if(controlPeriodMs < 1)

+		controlPeriodMs = 1;

+	else if(controlPeriodMs > 95)

+		controlPeriodMs = 95;

+	RegisterRx(STATUS_1 | (UINT8)deviceNumber );

+	RegisterRx(STATUS_2 | (UINT8)deviceNumber );

+	RegisterRx(STATUS_3 | (UINT8)deviceNumber );

+	RegisterRx(STATUS_4 | (UINT8)deviceNumber );

+	RegisterRx(STATUS_5 | (UINT8)deviceNumber );

+	RegisterRx(STATUS_6 | (UINT8)deviceNumber );

+	RegisterRx(STATUS_7 | (UINT8)deviceNumber );

+	RegisterTx(CONTROL_1 | (UINT8)deviceNumber, (UINT8)controlPeriodMs);

+	/* default our frame rate table to what firmware defaults to. */

+	_statusRateMs[0] = 10;	/* 	TALON_Status_1_General_10ms_t 		*/

+	_statusRateMs[1] = 20;	/* 	TALON_Status_2_Feedback_20ms_t 		*/

+	_statusRateMs[2] = 100;	/* 	TALON_Status_3_Enc_100ms_t 			*/

+	_statusRateMs[3] = 100;	/* 	TALON_Status_4_AinTempVbat_100ms_t 	*/

+	/* the only default param that is nonzero is limit switch.

+	 * Default to using the flash settings. */

+	SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash);

+}

+/* CanTalonSRX D'tor

+ */

+CanTalonSRX::~CanTalonSRX()

+{

+	if(_can_h){

+		FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h);

+		_can_h = 0;

+	}

+}

+void CanTalonSRX::OpenSessionIfNeedBe()

+{

+	_can_stat = 0;

+	if (_can_h == 0) {

+		/* bit30 - bit8 must match $000002XX.  Top bit is not masked to get remote frames */

+		FRC_NetworkCommunication_CANSessionMux_openStreamSession(&_can_h,kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask, kMsgCapacity, &_can_stat);

+		if (_can_stat == 0) {

+			/* success */

+		} else {

+			/* something went wrong, try again later */

+			_can_h = 0;

+		}

+	}

+}

+void CanTalonSRX::ProcessStreamMessages()

+{

+	if(0 == _can_h)

+		OpenSessionIfNeedBe();

+	/* process receive messages */

+	uint32_t i;

+	uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]);

+	uint32_t messagesRead = 0;

+	/* read out latest bunch of messages */

+	_can_stat = 0;

+	if (_can_h){

+		FRC_NetworkCommunication_CANSessionMux_readStreamSession(_can_h,_msgBuff, messagesToRead, &messagesRead, &_can_stat);

+	}

+	/* loop thru each message of interest */

+	for (i = 0; i < messagesRead; ++i) {

+		tCANStreamMessage * msg = _msgBuff + i;

+		if(msg->messageID == (PARAM_RESPONSE | GetDeviceNumber()) ){

+			TALON_Param_Response_t paramResp;
+      memcpy(&paramResp, msg->data, sizeof(paramResp));
+			/* decode value */

+			int32_t val = paramResp.ParamValueH;

+			val <<= 8;

+			val |=  paramResp.ParamValueMH;

+			val <<= 8;

+			val |=  paramResp.ParamValueML;

+			val <<= 8;

+			val |=  paramResp.ParamValueL;

+			/* save latest signal */

+			_sigs[paramResp.ParamEnum] = val;

+		}else{

+			int brkpthere = 42;

+			++brkpthere;

+		}

+	}

+}

+void CanTalonSRX::Set(double value)

+{

+	if(value > 1)

+		value = 1;

+	else if(value < -1)

+		value = -1;

+	SetDemand(1023*value); /* must be within [-1023,1023] */

+}

+/*---------------------setters and getters that use the param request/response-------------*/

+/**

+ * Send a one shot frame to set an arbitrary signal.

+ * Most signals are in the control frame so avoid using this API unless you have to.

+ * Use this api for...

+ * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

+ * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

+ * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

+ */

+CTR_Code CanTalonSRX::SetParamRaw(unsigned paramEnum, int rawBits)

+{

+	/* caller is using param API.  Open session if it hasn'T been done. */

+	if(0 == _can_h)

+		OpenSessionIfNeedBe();

+	TALON_Param_Response_t frame;

+	memset(&frame,0,sizeof(frame));

+	frame.ParamEnum = paramEnum;

+	frame.ParamValueH = rawBits >> 0x18;

+	frame.ParamValueMH = rawBits >> 0x10;

+	frame.ParamValueML = rawBits >> 0x08;

+	frame.ParamValueL = rawBits;

+	int32_t status = 0;

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_SET | GetDeviceNumber(), (const uint8_t*)&frame, 5, 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+/**

+ * Checks cached CAN frames and updating solicited signals.

+ */

+CTR_Code CanTalonSRX::GetParamResponseRaw(unsigned paramEnum, int & rawBits)

+{

+	CTR_Code retval = CTR_OKAY;

+	/* process received param events. We don't expect many since this API is not used often. */

+	ProcessStreamMessages();

+	/* grab the solicited signal value */

+	sigs_t::iterator i = _sigs.find(paramEnum);

+	if(i == _sigs.end()){

+		retval = CTR_SigNotUpdated;

+	}else{

+		rawBits = i->second;

+	}

+	return retval;

+}

+/**

+ * Asks TALON to immedietely respond with signal value.  This API is only used for signals that are not sent periodically.

+ * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.

+  * @param param to request.

+ */

+CTR_Code CanTalonSRX::RequestParam(param_t paramEnum)

+{

+	/* process received param events. We don't expect many since this API is not used often. */

+	ProcessStreamMessages();

+	TALON_Param_Request_t frame;

+	memset(&frame,0,sizeof(frame));

+	frame.ParamEnum = paramEnum;

+	int32_t status = 0;

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_REQUEST | GetDeviceNumber(), (const uint8_t*)&frame, 1, 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+

+CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value)

+{

+	int32_t rawbits = 0;

+	switch(paramEnum){

+		case eProfileParamSlot0_P:/* unsigned 10.22 fixed pt value */

+		case eProfileParamSlot0_I:

+		case eProfileParamSlot0_D:

+		case eProfileParamSlot1_P:

+		case eProfileParamSlot1_I:

+		case eProfileParamSlot1_D:

+		{

+			uint32_t urawbits;

+			value = std::min(value,1023.0); /* bounds check doubles that are outside u10.22 */

+			value = std::max(value,0.0);

+			urawbits = value * FLOAT_TO_FXP; /* perform unsign arithmetic */

+			rawbits = urawbits; /* copy bits over.  SetParamRaw just stuffs into CAN frame with no sense of signedness */

+		}	break;

+		case eProfileParamSlot1_F:	/* signed 10.22 fixed pt value */

+		case eProfileParamSlot0_F:

+			value = std::min(value, 512.0); /* bounds check doubles that are outside s10.22 */

+			value = std::max(value,-512.0);

+			rawbits = value * FLOAT_TO_FXP;

+			break;

+		default: /* everything else is integral */

+			rawbits = (int32_t)value;

+			break;

+	}

+	return SetParamRaw(paramEnum,rawbits);

+}

+CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double & value)

+{

+	int32_t rawbits = 0;

+	CTR_Code retval = GetParamResponseRaw(paramEnum,rawbits);

+	switch(paramEnum){

+		case eProfileParamSlot0_P:/* 10.22 fixed pt value */

+		case eProfileParamSlot0_I:

+		case eProfileParamSlot0_D:

+		case eProfileParamSlot0_F:

+		case eProfileParamSlot1_P:

+		case eProfileParamSlot1_I:

+		case eProfileParamSlot1_D:

+		case eProfileParamSlot1_F:

+		case eCurrent:

+		case eTemp:

+		case eBatteryV:

+			value = ((double)rawbits) * FXP_TO_FLOAT;

+			break;

+		default: /* everything else is integral */

+			value = (double)rawbits;

+			break;

+	}

+	return retval;

+}

+CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int & value)

+{

+	double dvalue = 0;

+	CTR_Code retval = GetParamResponse(paramEnum, dvalue);

+	value = (int32_t)dvalue;

+	return retval;

+}

+/*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/

+/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/

+/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/

+/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/

+CTR_Code CanTalonSRX::SetPgain(unsigned slotIdx,double gain)

+{

+	if(slotIdx == 0)

+		return SetParam(eProfileParamSlot0_P, gain);

+	return SetParam(eProfileParamSlot1_P, gain);

+}

+CTR_Code CanTalonSRX::SetIgain(unsigned slotIdx,double gain)

+{

+	if(slotIdx == 0)

+		return SetParam(eProfileParamSlot0_I, gain);

+	return SetParam(eProfileParamSlot1_I, gain);

+}

+CTR_Code CanTalonSRX::SetDgain(unsigned slotIdx,double gain)

+{

+	if(slotIdx == 0)

+		return SetParam(eProfileParamSlot0_D, gain);

+	return SetParam(eProfileParamSlot1_D, gain);

+}

+CTR_Code CanTalonSRX::SetFgain(unsigned slotIdx,double gain)

+{

+	if(slotIdx == 0)

+		return SetParam(eProfileParamSlot0_F, gain);

+	return SetParam(eProfileParamSlot1_F, gain);

+}

+CTR_Code CanTalonSRX::SetIzone(unsigned slotIdx,int zone)

+{

+	if(slotIdx == 0)

+		return SetParam(eProfileParamSlot0_IZone, zone);

+	return SetParam(eProfileParamSlot1_IZone, zone);

+}

+CTR_Code CanTalonSRX::SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate)

+{

+	if(slotIdx == 0)

+		return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);

+	return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);

+}

+CTR_Code CanTalonSRX::GetPgain(unsigned slotIdx,double & gain)

+{

+	if(slotIdx == 0)

+		return GetParamResponse(eProfileParamSlot0_P, gain);

+	return GetParamResponse(eProfileParamSlot1_P, gain);

+}

+CTR_Code CanTalonSRX::GetIgain(unsigned slotIdx,double & gain)

+{

+	if(slotIdx == 0)

+		return GetParamResponse(eProfileParamSlot0_I, gain);

+	return GetParamResponse(eProfileParamSlot1_I, gain);

+}

+CTR_Code CanTalonSRX::GetDgain(unsigned slotIdx,double & gain)

+{

+	if(slotIdx == 0)

+		return GetParamResponse(eProfileParamSlot0_D, gain);

+	return GetParamResponse(eProfileParamSlot1_D, gain);

+}

+CTR_Code CanTalonSRX::GetFgain(unsigned slotIdx,double & gain)

+{

+	if(slotIdx == 0)

+		return GetParamResponse(eProfileParamSlot0_F, gain);

+	return GetParamResponse(eProfileParamSlot1_F, gain);

+}

+CTR_Code CanTalonSRX::GetIzone(unsigned slotIdx,int & zone)

+{

+	if(slotIdx == 0)

+		return GetParamResponseInt32(eProfileParamSlot0_IZone, zone);

+	return GetParamResponseInt32(eProfileParamSlot1_IZone, zone);

+}

+CTR_Code CanTalonSRX::GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate)

+{

+	if(slotIdx == 0)

+		return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);

+	return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);

+}

+

+CTR_Code CanTalonSRX::SetSensorPosition(int pos)

+{

+	return SetParam(eSensorPosition, pos);

+}

+CTR_Code CanTalonSRX::SetForwardSoftLimit(int forwardLimit)

+{

+	return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit);

+}

+CTR_Code CanTalonSRX::SetReverseSoftLimit(int reverseLimit)

+{

+	return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit);

+}

+CTR_Code CanTalonSRX::SetForwardSoftEnable(int enable)

+{

+	return SetParam(eProfileParamSoftLimitForEnable, enable);

+}

+CTR_Code CanTalonSRX::SetReverseSoftEnable(int enable)

+{

+	return SetParam(eProfileParamSoftLimitRevEnable, enable);

+}

+CTR_Code CanTalonSRX::GetForwardSoftLimit(int & forwardLimit)

+{

+	return GetParamResponseInt32(eProfileParamSoftLimitForThreshold, forwardLimit);

+}

+CTR_Code CanTalonSRX::GetReverseSoftLimit(int & reverseLimit)

+{

+	return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold, reverseLimit);

+}

+CTR_Code CanTalonSRX::GetForwardSoftEnable(int & enable)

+{

+	return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable);

+}

+CTR_Code CanTalonSRX::GetReverseSoftEnable(int & enable)

+{

+	return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable);

+}

+/**

+ * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for what's available.

+ */

+CTR_Code CanTalonSRX::SetStatusFrameRate(unsigned frameEnum, unsigned periodMs)

+{

+	int32_t status = 0;

+	/* bounds check the period */

+	if(periodMs < 1)

+		periodMs = 1;

+	else if (periodMs > 255)

+		periodMs = 255;

+  uint8_t period = (uint8_t)periodMs;

+	/* tweak just the status messsage rate the caller cares about */

+	switch(frameEnum){

+		case kStatusFrame_General:

+			_statusRateMs[0] = period;

+			break;

+		case kStatusFrame_Feedback:

+			_statusRateMs[1] = period;

+			break;

+		case kStatusFrame_Encoder:

+			_statusRateMs[2] = period;

+			break;

+		case kStatusFrame_AnalogTempVbat:

+			_statusRateMs[3] = period;

+			break;

+	}

+	/* build our request frame */

+	TALON_Control_2_Rates_OneShot_t frame;

+	memset(&frame,0,sizeof(frame));

+	frame.Status1Ms = _statusRateMs[0];

+	frame.Status2Ms = _statusRateMs[1];

+	frame.Status3Ms = _statusRateMs[2];

+	frame.Status4Ms = _statusRateMs[3];

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_2 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+/**

+ * Clear all sticky faults in TALON.

+ */

+CTR_Code CanTalonSRX::ClearStickyFaults()

+{

+	int32_t status = 0;

+	/* build request frame */

+	TALON_Control_3_ClearFlags_OneShot_t frame;

+	memset(&frame,0,sizeof(frame));

+	frame.ClearStickyFaults = 1;

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_3 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+/*------------------------ auto generated.  This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/

+/*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/

+CTR_Code CanTalonSRX::GetFault_OverTemp(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_OverTemp;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFault_UnderVoltage(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_UnderVoltage;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFault_ForLim(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_ForLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFault_RevLim(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_RevLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFault_HardwareFailure(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_HardwareFailure;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFault_ForSoftLim(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_ForSoftLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFault_RevSoftLim(int &param)

+{

+	GET_STATUS1();

+	param = rx->Fault_RevSoftLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetStckyFault_OverTemp(int &param)

+{

+	GET_STATUS2();

+	param = rx->StckyFault_OverTemp;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetStckyFault_UnderVoltage(int &param)

+{

+	GET_STATUS2();

+	param = rx->StckyFault_UnderVoltage;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetStckyFault_ForLim(int &param)

+{

+	GET_STATUS2();

+	param = rx->StckyFault_ForLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetStckyFault_RevLim(int &param)

+{

+	GET_STATUS2();

+	param = rx->StckyFault_RevLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetStckyFault_ForSoftLim(int &param)

+{

+	GET_STATUS2();

+	param = rx->StckyFault_ForSoftLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int &param)

+{

+	GET_STATUS2();

+	param = rx->StckyFault_RevSoftLim;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetAppliedThrottle(int &param)

+{

+	GET_STATUS1();

+	int32_t raw = 0;

+	raw |= rx->AppliedThrottle_h3;

+	raw <<= 8;

+	raw |= rx->AppliedThrottle_l8;

+	raw <<= (32-11); /* sign extend */

+	raw >>= (32-11); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetCloseLoopErr(int &param)

+{

+	GET_STATUS1();

+	int32_t raw = 0;

+	raw |= rx->CloseLoopErrH;

+	raw <<= 8;

+	raw |= rx->CloseLoopErrM;

+	raw <<= 8;

+	raw |= rx->CloseLoopErrL;

+	raw <<= (32-24); /* sign extend */

+	raw >>= (32-24); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int &param)

+{

+	GET_STATUS1();

+	param = rx->FeedbackDeviceSelect;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetModeSelect(int &param)

+{

+	GET_STATUS1();

+	uint32_t raw = 0;

+	raw |= rx->ModeSelect_h1;

+	raw <<= 3;

+	raw |= rx->ModeSelect_b3;

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetLimitSwitchEn(int &param)

+{

+	GET_STATUS1();

+	param = rx->LimitSwitchEn;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetLimitSwitchClosedFor(int &param)

+{

+	GET_STATUS1();

+	param = rx->LimitSwitchClosedFor;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int &param)

+{

+	GET_STATUS1();

+	param = rx->LimitSwitchClosedRev;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetSensorPosition(int &param)

+{

+	GET_STATUS2();

+	int32_t raw = 0;

+	raw |= rx->SensorPositionH;

+	raw <<= 8;

+	raw |= rx->SensorPositionM;

+	raw <<= 8;

+	raw |= rx->SensorPositionL;

+	raw <<= (32-24); /* sign extend */

+	raw >>= (32-24); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetSensorVelocity(int &param)

+{

+	GET_STATUS2();

+	int32_t raw = 0;

+	raw |= rx->SensorVelocityH;

+	raw <<= 8;

+	raw |= rx->SensorVelocityL;

+	raw <<= (32-16); /* sign extend */

+	raw >>= (32-16); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetCurrent(double &param)

+{

+	GET_STATUS2();

+	uint32_t raw = 0;

+	raw |= rx->Current_h8;

+	raw <<= 2;

+	raw |= rx->Current_l2;

+	param = (double)raw * 0.125 + 0;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetBrakeIsEnabled(int &param)

+{

+	GET_STATUS2();

+	param = rx->BrakeIsEnabled;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetEncPosition(int &param)

+{

+	GET_STATUS3();

+	int32_t raw = 0;

+	raw |= rx->EncPositionH;

+	raw <<= 8;

+	raw |= rx->EncPositionM;

+	raw <<= 8;

+	raw |= rx->EncPositionL;

+	raw <<= (32-24); /* sign extend */

+	raw >>= (32-24); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetEncVel(int &param)

+{

+	GET_STATUS3();

+	int32_t raw = 0;

+	raw |= rx->EncVelH;

+	raw <<= 8;

+	raw |= rx->EncVelL;

+	raw <<= (32-16); /* sign extend */

+	raw >>= (32-16); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetEncIndexRiseEvents(int &param)

+{

+	GET_STATUS3();

+	uint32_t raw = 0;

+	raw |= rx->EncIndexRiseEventsH;

+	raw <<= 8;

+	raw |= rx->EncIndexRiseEventsL;

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetQuadApin(int &param)

+{

+	GET_STATUS3();

+	param = rx->QuadApin;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetQuadBpin(int &param)

+{

+	GET_STATUS3();

+	param = rx->QuadBpin;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetQuadIdxpin(int &param)

+{

+	GET_STATUS3();

+	param = rx->QuadIdxpin;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetAnalogInWithOv(int &param)

+{

+	GET_STATUS4();

+	int32_t raw = 0;

+	raw |= rx->AnalogInWithOvH;

+	raw <<= 8;

+	raw |= rx->AnalogInWithOvM;

+	raw <<= 8;

+	raw |= rx->AnalogInWithOvL;

+	raw <<= (32-24); /* sign extend */

+	raw >>= (32-24); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetAnalogInVel(int &param)

+{

+	GET_STATUS4();

+	int32_t raw = 0;

+	raw |= rx->AnalogInVelH;

+	raw <<= 8;

+	raw |= rx->AnalogInVelL;

+	raw <<= (32-16); /* sign extend */

+	raw >>= (32-16); /* sign extend */

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetTemp(double &param)

+{

+	GET_STATUS4();

+	uint32_t raw = rx->Temp;

+	param = (double)raw * 0.6451612903 + -50;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetBatteryV(double &param)

+{

+	GET_STATUS4();

+	uint32_t raw = rx->BatteryV;

+	param = (double)raw * 0.05 + 4;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetResetCount(int &param)

+{

+	GET_STATUS5();

+	uint32_t raw = 0;

+	raw |= rx->ResetCountH;

+	raw <<= 8;

+	raw |= rx->ResetCountL;

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetResetFlags(int &param)

+{

+	GET_STATUS5();

+	uint32_t raw = 0;

+	raw |= rx->ResetFlagsH;

+	raw <<= 8;

+	raw |= rx->ResetFlagsL;

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::GetFirmVers(int &param)

+{

+	GET_STATUS5();

+	uint32_t raw = 0;

+	raw |= rx->FirmVersH;

+	raw <<= 8;

+	raw |= rx->FirmVersL;

+	param = (int)raw;

+	return rx.err;

+}

+CTR_Code CanTalonSRX::SetDemand(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->DemandH = param>>16;

+	toFill->DemandM = param>>8;

+	toFill->DemandL = param>>0;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->OverrideLimitSwitchEn = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->FeedbackDeviceSelect = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->RevMotDuringCloseLoopEn = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetOverrideBrakeType(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->OverrideBrakeType = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetModeSelect(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->ModeSelect = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+/**

+ * @param modeSelect selects which mode.

+ * @param demand setpt or throttle or masterId to follow.

+ * @return error code, 0 iff successful.

+ * This function has the advantage of atomically setting mode and demand.

+ */

+CTR_Code CanTalonSRX::SetModeSelect(int modeSelect,int demand)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->ModeSelect = modeSelect;

+	toFill->DemandH = demand>>16;

+	toFill->DemandM = demand>>8;

+	toFill->DemandL = demand>>0;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetProfileSlotSelect(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->ProfileSlotSelect = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetRampThrottle(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->RampThrottle = param;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param)

+{

+	CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());

+	if (toFill.IsEmpty()) return CTR_UnexpectedArbId;

+	toFill->RevFeedbackSensor = param ? 1 : 0;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+//------------------ C interface --------------------------------------------//

+extern "C" {

+void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs)

+{

+	return new CanTalonSRX(deviceNumber, controlPeriodMs);

+}

+void c_TalonSRX_Destroy(void *handle)

+{

+	delete (CanTalonSRX*)handle;

+}

+CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value)

+{

+	return ((CanTalonSRX*)handle)->SetParam((CanTalonSRX::param_t)paramEnum, value);

+}

+CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum)

+{

+	return ((CanTalonSRX*)handle)->RequestParam((CanTalonSRX::param_t)paramEnum);

+}

+CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value)

+{

+	return ((CanTalonSRX*)handle)->GetParamResponse((CanTalonSRX::param_t)paramEnum, *value);

+}

+CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value)

+{

+	return ((CanTalonSRX*)handle)->GetParamResponseInt32((CanTalonSRX::param_t)paramEnum, *value);

+}

+CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs)

+{

+	return ((CanTalonSRX*)handle)->SetStatusFrameRate(frameEnum, periodMs);

+}

+CTR_Code c_TalonSRX_ClearStickyFaults(void *handle)

+{

+	return ((CanTalonSRX*)handle)->ClearStickyFaults();

+}

+CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_OverTemp(*param);

+}

+CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_UnderVoltage(*param);

+}

+CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_ForLim(*param);

+}

+CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_RevLim(*param);

+}

+CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_HardwareFailure(*param);

+}

+CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_ForSoftLim(*param);

+}

+CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFault_RevSoftLim(*param);

+}

+CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetStckyFault_OverTemp(*param);

+}

+CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetStckyFault_UnderVoltage(*param);

+}

+CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetStckyFault_ForLim(*param);

+}

+CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetStckyFault_RevLim(*param);

+}

+CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetStckyFault_ForSoftLim(*param);

+}

+CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetStckyFault_RevSoftLim(*param);

+}

+CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetAppliedThrottle(*param);

+}

+CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetCloseLoopErr(*param);

+}

+CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFeedbackDeviceSelect(*param);

+}

+CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetModeSelect(*param);

+}

+CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetLimitSwitchEn(*param);

+}

+CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetLimitSwitchClosedFor(*param);

+}

+CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetLimitSwitchClosedRev(*param);

+}

+CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetSensorPosition(*param);

+}

+CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetSensorVelocity(*param);

+}

+CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param)

+{

+	return ((CanTalonSRX*)handle)->GetCurrent(*param);

+}

+CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetBrakeIsEnabled(*param);

+}

+CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetEncPosition(*param);

+}

+CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetEncVel(*param);

+}

+CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetEncIndexRiseEvents(*param);

+}

+CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetQuadApin(*param);

+}

+CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetQuadBpin(*param);

+}

+CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetQuadIdxpin(*param);

+}

+CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetAnalogInWithOv(*param);

+}

+CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetAnalogInVel(*param);

+}

+CTR_Code c_TalonSRX_GetTemp(void *handle, double *param)

+{

+	return ((CanTalonSRX*)handle)->GetTemp(*param);

+}

+CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param)

+{

+	return ((CanTalonSRX*)handle)->GetBatteryV(*param);

+}

+CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetResetCount(*param);

+}

+CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetResetFlags(*param);

+}

+CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param)

+{

+	return ((CanTalonSRX*)handle)->GetFirmVers(*param);

+}

+CTR_Code c_TalonSRX_SetDemand(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetDemand(param);

+}

+CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetOverrideLimitSwitchEn(param);

+}

+CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetFeedbackDeviceSelect(param);

+}

+CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetRevMotDuringCloseLoopEn(param);

+}

+CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetOverrideBrakeType(param);

+}

+CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetModeSelect(param);

+}

+CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand)

+{

+	return ((CanTalonSRX*)handle)->SetModeSelect(modeSelect, demand);

+}

+CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetProfileSlotSelect(param);

+}

+CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetRampThrottle(param);

+}

+CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param)

+{

+	return ((CanTalonSRX*)handle)->SetRevFeedbackSensor(param);

+}

+}

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/CanTalonSRX.h b/aos/externals/allwpilib/hal/lib/Athena/ctre/CanTalonSRX.h
new file mode 100644
index 0000000..cc2236b
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/CanTalonSRX.h
@@ -0,0 +1,375 @@
+/**

+ * @brief CAN TALON SRX driver.

+ *

+ * The TALON SRX is designed to instrument all runtime signals periodically.  The default periods are chosen to support 16 TALONs

+ * with 10ms update rate for control (throttle or setpoint).  However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate

+ * The getters for these unsolicited signals are auto generated at the bottom of this module.

+ *

+ * Likewise most control signals are sent periodically using the fire-and-forget CAN API.

+ * The setters for these unsolicited signals are auto generated at the bottom of this module.

+ *

+ * Signals that are not available in an unsolicited fashion are the Close Loop gains.

+ * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once

+ * 	or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application.  These parameters are saved to flash so once they are

+ * 	loaded in the TALON, they will persist through power cycles and mode changes.

+ *

+ * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from

+ * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.

+ *

+ * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters.  Most likely

+ * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.

+ * If this API is used, be mindful of the CAN utilization reported in the driver station.

+ *

+ * Encoder position is measured in encoder edges.  Every edge is counted (similar to roboRIO 4X mode).

+ * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).

+ * Use SetFeedbackDeviceSelect to select which sensor type you need.  Once you do that you can use GetSensorPosition()

+ * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by default).

+ * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.

+ *

+ * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.

+ * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms.  This allows easy instrumentation

+ * for "in the pits" checking of all sensors regardless of modeselect.  The 100ms rate is overridable for teams who want to acquire sensor

+ * data for processing, not just instrumentation.  Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.

+ *

+ * Velocity is in position ticks / 100ms.

+ *

+ * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).

+ *  This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).

+ *

+ * Pos and velocity close loops are calc'd as

+ * 		err = target - posOrVel.

+ * 		iErr += err;

+ * 		if(   (IZone!=0)  and  abs(err) > IZone)

+ * 			ClearIaccum()

+ * 		output = P X err + I X iErr + D X dErr + F X target

+ * 		dErr = err - lastErr

+ *	P, I,and D gains are always positive. F can be negative.

+ *	Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.

+ *	Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.

+ *

+ * P gain is specified in throttle per error tick.  For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1

+ * 		ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

+ *

+ * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)

+ *  	for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

+ *  	Close loop and integral accumulator runs every 1ms.

+ *

+ * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)

+ * 	per change of 1 unit (ADC or encoder) per ms.

+ *

+ * I Zone is specified in the same units as sensor position (ADC units or quadrature edges).  If pos/vel error is outside of

+ * 		this value, the integrated error will auto-clear...

+ * 		if(   (IZone!=0)  and  abs(err) > IZone)

+ * 			ClearIaccum()

+ * 		...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.

+ *

+ * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable ramping.

+ * 		Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.

+ *

+ * auto generated using spreadsheet and WpiClassGen.csproj

+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967

+ */

+#ifndef CanTalonSRX_H_

+#define CanTalonSRX_H_

+#include "ctre.h"				//BIT Defines + Typedefs

+#include "CtreCanNode.h"

+#include <NetworkCommunication/CANSessionMux.h>	//CAN Comm

+#include <map>

+class CanTalonSRX : public CtreCanNode

+{

+private:

+

+	/** just in case user wants to modify periods of certain status frames.

+	 * 	Default the vars to match the firmware default. */

+	uint32_t _statusRateMs[4];

+	//---------------------- Vars for opening a CAN stream if caller needs signals that require soliciting */

+	uint32_t _can_h; 	//!< Session handle for catching response params.

+	int32_t _can_stat; //!< Session handle status.

+	struct tCANStreamMessage _msgBuff[20];

+	static int const kMsgCapacity	= 20;

+	typedef std::map<uint32_t, uint32_t> sigs_t;

+	sigs_t _sigs; //!< Catches signal updates that are solicited.  Expect this to be very few.

+	void OpenSessionIfNeedBe();

+	void ProcessStreamMessages();

+	/**

+	 * Send a one shot frame to set an arbitrary signal.

+	 * Most signals are in the control frame so avoid using this API unless you have to.

+	 * Use this api for...

+	 * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

+	 * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

+	 * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

+	 */

+	CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits);

+	/**

+	 * Checks cached CAN frames and updating solicited signals.

+	 */

+	CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits);

+public:

+	static const int kDefaultControlPeriodMs = 10; //!< default control update rate is 10ms.

+	CanTalonSRX(int deviceNumber = 0,int controlPeriodMs = kDefaultControlPeriodMs);

+	~CanTalonSRX();

+	void Set(double value);

+	/* mode select enumerations */

+	static const int kMode_DutyCycle = 0; //!< Demand is 11bit signed duty cycle [-1023,1023].

+	static const int kMode_PositionCloseLoop = 1; //!< Position PIDF.

+	static const int kMode_VelocityCloseLoop = 2; //!< Velocity PIDF.

+	static const int kMode_CurrentCloseLoop = 3; //!< Current close loop - not done.

+	static const int kMode_VoltCompen = 4; //!< Voltage Compensation Mode - not done.  Demand is fixed pt target 8.8 volts.

+	static const int kMode_SlaveFollower = 5; //!< Demand is the 6 bit Device ID of the 'master' TALON SRX.

+	static const int kMode_NoDrive = 15; //!< Zero the output (honors brake/coast) regardless of demand.  Might be useful if we need to change modes but can't atomically change all the signals we want in between.

+	/* limit switch enumerations */

+	static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1;

+	static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4;

+	static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5;

+	static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6;

+	static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7;

+	/* brake override enumerations */

+	static const int kBrakeOverride_UseDefaultsFromFlash = 0;

+	static const int kBrakeOverride_OverrideCoast = 1;

+	static const int kBrakeOverride_OverrideBrake = 2;

+	/* feedback device enumerations */

+	static const int kFeedbackDev_DigitalQuadEnc=0;

+	static const int kFeedbackDev_AnalogPot=2;

+	static const int kFeedbackDev_AnalogEncoder=3;

+	static const int kFeedbackDev_CountEveryRisingEdge=4;

+	static const int kFeedbackDev_CountEveryFallingEdge=5;

+	static const int kFeedbackDev_PosIsPulseWidth=8;

+	/* ProfileSlotSelect enumerations*/

+	static const int kProfileSlotSelect_Slot0 = 0;

+	static const int kProfileSlotSelect_Slot1 = 1;

+    /* status frame rate types */

+    static const int kStatusFrame_General = 0;

+    static const int kStatusFrame_Feedback = 1;

+    static const int kStatusFrame_Encoder = 2;

+    static const int kStatusFrame_AnalogTempVbat = 3;

+	/**

+	 * Signal enumeration for generic signal access.

+	 * Although every signal is enumerated, only use this for traffic that must be solicited.

+	 * Use the auto generated getters/setters at bottom of this header as much as possible.

+	 */

+	typedef enum _param_t{

+		eProfileParamSlot0_P=1,

+		eProfileParamSlot0_I=2,

+		eProfileParamSlot0_D=3,

+		eProfileParamSlot0_F=4,

+		eProfileParamSlot0_IZone=5,

+		eProfileParamSlot0_CloseLoopRampRate=6,

+		eProfileParamSlot1_P=11,

+		eProfileParamSlot1_I=12,

+		eProfileParamSlot1_D=13,

+		eProfileParamSlot1_F=14,

+		eProfileParamSlot1_IZone=15,

+		eProfileParamSlot1_CloseLoopRampRate=16,

+		eProfileParamSoftLimitForThreshold=21,

+		eProfileParamSoftLimitRevThreshold=22,

+		eProfileParamSoftLimitForEnable=23,

+		eProfileParamSoftLimitRevEnable=24,

+		eOnBoot_BrakeMode=31,

+		eOnBoot_LimitSwitch_Forward_NormallyClosed=32,

+		eOnBoot_LimitSwitch_Reverse_NormallyClosed=33,

+		eOnBoot_LimitSwitch_Forward_Disable=34,

+		eOnBoot_LimitSwitch_Reverse_Disable=35,

+		eFault_OverTemp=41,

+		eFault_UnderVoltage=42,

+		eFault_ForLim=43,

+		eFault_RevLim=44,

+		eFault_HardwareFailure=45,

+		eFault_ForSoftLim=46,

+		eFault_RevSoftLim=47,

+		eStckyFault_OverTemp=48,

+		eStckyFault_UnderVoltage=49,

+		eStckyFault_ForLim=50,

+		eStckyFault_RevLim=51,

+		eStckyFault_ForSoftLim=52,

+		eStckyFault_RevSoftLim=53,

+		eAppliedThrottle=61,

+		eCloseLoopErr=62,

+		eFeedbackDeviceSelect=63,

+		eRevMotDuringCloseLoopEn=64,

+		eModeSelect=65,

+		eProfileSlotSelect=66,

+		eRampThrottle=67,

+		eRevFeedbackSensor=68,

+		eLimitSwitchEn=69,

+		eLimitSwitchClosedFor=70,

+		eLimitSwitchClosedRev=71,

+		eSensorPosition=73,

+		eSensorVelocity=74,

+		eCurrent=75,

+		eBrakeIsEnabled=76,

+		eEncPosition=77,

+		eEncVel=78,

+		eEncIndexRiseEvents=79,

+		eQuadApin=80,

+		eQuadBpin=81,

+		eQuadIdxpin=82,

+		eAnalogInWithOv=83,

+		eAnalogInVel=84,

+		eTemp=85,

+		eBatteryV=86,

+		eResetCount=87,

+		eResetFlags=88,

+		eFirmVers=89,

+		eSettingsChanged=90,

+		eQuadFilterEn=91,	

+		ePidIaccum=93,

+	}param_t;

+    /*---------------------setters and getters that use the solicated param request/response-------------*//**

+     * Send a one shot frame to set an arbitrary signal.

+     * Most signals are in the control frame so avoid using this API unless you have to.

+     * Use this api for...

+     * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

+     * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

+     * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

+     */

+	CTR_Code SetParam(param_t paramEnum, double value);

+	/**

+	 * Asks TALON to immedietely respond with signal value.  This API is only used for signals that are not sent periodically.

+	 * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.

+	  * @param param to request.

+	 */

+	CTR_Code RequestParam(param_t paramEnum);

+	CTR_Code GetParamResponse(param_t paramEnum, double & value);

+	CTR_Code GetParamResponseInt32(param_t paramEnum, int & value);

+    /*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/

+	/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/

+	/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/

+	/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/

+	CTR_Code SetPgain(unsigned slotIdx,double gain);

+	CTR_Code SetIgain(unsigned slotIdx,double gain);

+	CTR_Code SetDgain(unsigned slotIdx,double gain);

+	CTR_Code SetFgain(unsigned slotIdx,double gain);

+	CTR_Code SetIzone(unsigned slotIdx,int zone);

+	CTR_Code SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate);

+	CTR_Code SetSensorPosition(int pos);

+	CTR_Code SetForwardSoftLimit(int forwardLimit);

+	CTR_Code SetReverseSoftLimit(int reverseLimit);

+	CTR_Code SetForwardSoftEnable(int enable);

+	CTR_Code SetReverseSoftEnable(int enable);

+	CTR_Code GetPgain(unsigned slotIdx,double & gain);

+	CTR_Code GetIgain(unsigned slotIdx,double & gain);

+	CTR_Code GetDgain(unsigned slotIdx,double & gain);

+	CTR_Code GetFgain(unsigned slotIdx,double & gain);

+	CTR_Code GetIzone(unsigned slotIdx,int & zone);

+	CTR_Code GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate);

+	CTR_Code GetForwardSoftLimit(int & forwardLimit);

+	CTR_Code GetReverseSoftLimit(int & reverseLimit);

+	CTR_Code GetForwardSoftEnable(int & enable);

+	CTR_Code GetReverseSoftEnable(int & enable);

+	/**

+	 * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for what's available.

+	 */

+	CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs);

+	/**

+	 * Clear all sticky faults in TALON.

+	 */

+	CTR_Code ClearStickyFaults();

+    /*------------------------ auto generated.  This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/

+    /*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/

+	CTR_Code GetFault_OverTemp(int &param);

+	CTR_Code GetFault_UnderVoltage(int &param);

+	CTR_Code GetFault_ForLim(int &param);

+	CTR_Code GetFault_RevLim(int &param);

+	CTR_Code GetFault_HardwareFailure(int &param);

+	CTR_Code GetFault_ForSoftLim(int &param);

+	CTR_Code GetFault_RevSoftLim(int &param);

+	CTR_Code GetStckyFault_OverTemp(int &param);

+	CTR_Code GetStckyFault_UnderVoltage(int &param);

+	CTR_Code GetStckyFault_ForLim(int &param);

+	CTR_Code GetStckyFault_RevLim(int &param);

+	CTR_Code GetStckyFault_ForSoftLim(int &param);

+	CTR_Code GetStckyFault_RevSoftLim(int &param);

+	CTR_Code GetAppliedThrottle(int &param);

+	CTR_Code GetCloseLoopErr(int &param);

+	CTR_Code GetFeedbackDeviceSelect(int &param);

+	CTR_Code GetModeSelect(int &param);

+	CTR_Code GetLimitSwitchEn(int &param);

+	CTR_Code GetLimitSwitchClosedFor(int &param);

+	CTR_Code GetLimitSwitchClosedRev(int &param);

+	CTR_Code GetSensorPosition(int &param);

+	CTR_Code GetSensorVelocity(int &param);

+	CTR_Code GetCurrent(double &param);

+	CTR_Code GetBrakeIsEnabled(int &param);

+	CTR_Code GetEncPosition(int &param);

+	CTR_Code GetEncVel(int &param);

+	CTR_Code GetEncIndexRiseEvents(int &param);

+	CTR_Code GetQuadApin(int &param);

+	CTR_Code GetQuadBpin(int &param);

+	CTR_Code GetQuadIdxpin(int &param);

+	CTR_Code GetAnalogInWithOv(int &param);

+	CTR_Code GetAnalogInVel(int &param);

+	CTR_Code GetTemp(double &param);

+	CTR_Code GetBatteryV(double &param);

+	CTR_Code GetResetCount(int &param);

+	CTR_Code GetResetFlags(int &param);

+	CTR_Code GetFirmVers(int &param);

+	CTR_Code SetDemand(int param);

+	CTR_Code SetOverrideLimitSwitchEn(int param);

+	CTR_Code SetFeedbackDeviceSelect(int param);

+	CTR_Code SetRevMotDuringCloseLoopEn(int param);

+	CTR_Code SetOverrideBrakeType(int param);

+	CTR_Code SetModeSelect(int param);

+	CTR_Code SetModeSelect(int modeSelect,int demand);

+	CTR_Code SetProfileSlotSelect(int param);

+	CTR_Code SetRampThrottle(int param);

+	CTR_Code SetRevFeedbackSensor(int param);

+};

+extern "C" {

+	void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs);

+	void c_TalonSRX_Destroy(void *handle);

+	CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value);

+	CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum);

+	CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value);

+	CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value);

+	CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs);

+	CTR_Code c_TalonSRX_ClearStickyFaults(void *handle);

+	CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param);

+	CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetTemp(void *handle, double *param);

+	CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param);

+	CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param);

+	CTR_Code c_TalonSRX_SetDemand(void *handle, int param);

+	CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param);

+	CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param);

+	CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param);

+	CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param);

+	CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param);

+	CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand);

+	CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param);

+	CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param);

+	CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param);

+}

+#endif

+

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/CtreCanNode.cpp b/aos/externals/allwpilib/hal/lib/Athena/ctre/CtreCanNode.cpp
new file mode 100644
index 0000000..b2e3620
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/CtreCanNode.cpp
@@ -0,0 +1,101 @@
+#pragma GCC diagnostic ignored "-Wmissing-field-initializers"

+

+#include "CtreCanNode.h"

+#include "NetworkCommunication/CANSessionMux.h"

+#include <string.h> // memset

+#include <unistd.h> // usleep

+

+static const UINT32 kFullMessageIDMask = 0x1fffffff;

+

+CtreCanNode::CtreCanNode(UINT8 deviceNumber)

+{

+	_deviceNumber = deviceNumber;

+}

+CtreCanNode::~CtreCanNode()

+{

+}

+void CtreCanNode::RegisterRx(uint32_t arbId)

+{

+	/* no need to do anything, we just use new API to poll last received message */

+}

+void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs)

+{

+	int32_t status = 0;

+

+	txJob_t job = {0};

+	job.arbId = arbId;

+	job.periodMs = periodMs;

+	_txJobs[arbId] = job;

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(	job.arbId,

+														job.toSend,

+														8,

+														job.periodMs,

+														&status);

+}

+timespec diff(const timespec & start, const timespec & end)

+{

+	timespec temp;

+	if ((end.tv_nsec-start.tv_nsec)<0) {

+		temp.tv_sec = end.tv_sec-start.tv_sec-1;

+		temp.tv_nsec = 1000000000+end.tv_nsec-start.tv_nsec;

+	} else {

+		temp.tv_sec = end.tv_sec-start.tv_sec;

+		temp.tv_nsec = end.tv_nsec-start.tv_nsec;

+	}

+	return temp;

+}

+CTR_Code CtreCanNode::GetRx(uint32_t arbId,uint8_t * dataBytes, uint32_t timeoutMs)

+{

+	CTR_Code retval = CTR_OKAY;

+	int32_t status = 0;

+	uint8_t len = 0;

+	uint32_t timeStamp;

+	/* cap timeout at 999ms */

+	if(timeoutMs > 999)

+		timeoutMs = 999;

+	FRC_NetworkCommunication_CANSessionMux_receiveMessage(&arbId,kFullMessageIDMask,dataBytes,&len,&timeStamp,&status);

+	if(status == 0){

+		/* fresh update */

+		rxEvent_t & r = _rxRxEvents[arbId]; /* lookup entry or make a default new one with all zeroes */

+		clock_gettime(2,&r.time); 			/* fill in time */

+		memcpy(r.bytes,  dataBytes,  8);	/* fill in databytes */

+	}else{

+		/* did not get the message */

+		rxRxEvents_t::iterator i = _rxRxEvents.find(arbId);

+		if(i == _rxRxEvents.end()){

+			/* we've never gotten this mesage */

+			retval = CTR_RxTimeout;

+			/* fill caller's buffer with zeros */

+			memset(dataBytes,0,8);

+		}else{

+			/* we've gotten this message before but not recently */

+			memcpy(dataBytes,i->second.bytes,8);

+			/* get the time now */

+			struct timespec temp;

+			clock_gettime(2,&temp); /* get now */

+			/* how long has it been? */

+			temp = diff(i->second.time,temp); /* temp = now - last */

+			if(temp.tv_sec > 0){

+				retval = CTR_RxTimeout;

+			}else if(temp.tv_nsec > ((int32_t)timeoutMs*1000*1000)){

+				retval = CTR_RxTimeout;

+			}else {

+				/* our last update was recent enough */

+			}

+		}

+	}

+

+	return retval;

+}

+void CtreCanNode::FlushTx(uint32_t arbId)

+{

+	int32_t status = 0;

+	txJobs_t::iterator iter = _txJobs.find(arbId);

+	if(iter != _txJobs.end())

+		FRC_NetworkCommunication_CANSessionMux_sendMessage(	iter->second.arbId,

+															iter->second.toSend,

+															8,

+															iter->second.periodMs,

+															&status);

+}

+

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/CtreCanNode.h b/aos/externals/allwpilib/hal/lib/Athena/ctre/CtreCanNode.h
new file mode 100644
index 0000000..65fa948
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/CtreCanNode.h
@@ -0,0 +1,120 @@
+#ifndef CtreCanNode_H_

+#define CtreCanNode_H_

+#include "ctre.h"				//BIT Defines + Typedefs

+#include <NetworkCommunication/CANSessionMux.h>	//CAN Comm

+#include <pthread.h>

+#include <map>

+#include <string.h> // memcpy

+#include <sys/time.h>

+class CtreCanNode

+{

+public:

+	CtreCanNode(UINT8 deviceNumber);

+    ~CtreCanNode();

+

+	UINT8 GetDeviceNumber()

+	{

+		return _deviceNumber;

+	}

+protected:

+

+

+	template <typename T> class txTask{

+		public:

+			uint32_t arbId;

+			T * toSend;

+			T * operator -> ()

+			{

+				return toSend;

+			}

+			T & operator*()

+			{

+				return *toSend;

+			}

+			bool IsEmpty()

+			{

+				if(toSend == 0)

+					return true;

+				return false;

+			}

+	};

+	template <typename T> class recMsg{

+		public:

+			uint32_t arbId;

+			uint8_t bytes[8];

+			CTR_Code err;

+			T * operator -> ()

+			{

+        T *r;
+        memcpy(&r, &bytes, sizeof(r));
+        return r;
+			}

+			T & operator*()

+			{

+        T *r;
+        memcpy(&r, &bytes, sizeof(r));
+        return *r;
+			}

+	};

+	UINT8 _deviceNumber;

+	void RegisterRx(uint32_t arbId);

+	void RegisterTx(uint32_t arbId, uint32_t periodMs);

+

+	CTR_Code GetRx(uint32_t arbId,uint8_t * dataBytes,uint32_t timeoutMs);

+	void FlushTx(uint32_t arbId);

+

+	template<typename T> txTask<T> GetTx(uint32_t arbId)

+	{

+		txTask<T> retval = {0, nullptr};

+		txJobs_t::iterator i = _txJobs.find(arbId);

+		if(i != _txJobs.end()){

+			retval.arbId = i->second.arbId;

+      memcpy(&retval.toSend, &i->second.toSend, sizeof(retval.toSend));
+		}

+		return retval;

+	}

+	template<class T> void FlushTx(T & par)

+	{

+		FlushTx(par.arbId);

+	}

+

+	template<class T> recMsg<T> GetRx(uint32_t arbId, uint32_t timeoutMs)

+	{

+		recMsg<T> retval;

+		retval.err = GetRx(arbId,retval.bytes, timeoutMs);

+		return retval;

+	}

+

+private:

+

+	class txJob_t {

+		public:

+			uint32_t arbId;

+			uint8_t toSend[8];

+			uint32_t periodMs;

+	};

+

+	class rxEvent_t{

+		public:

+			uint8_t bytes[8];

+			struct timespec time;

+			rxEvent_t()

+			{

+				bytes[0] = 0;

+				bytes[1] = 0;

+				bytes[2] = 0;

+				bytes[3] = 0;

+				bytes[4] = 0;

+				bytes[5] = 0;

+				bytes[6] = 0;

+				bytes[7] = 0;

+			}

+	};

+

+	typedef std::map<uint32_t,txJob_t> txJobs_t;

+	txJobs_t _txJobs;

+

+	typedef std::map<uint32_t,rxEvent_t> rxRxEvents_t;

+	rxRxEvents_t _rxRxEvents;

+};

+#endif

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/PCM.cpp b/aos/externals/allwpilib/hal/lib/Athena/ctre/PCM.cpp
new file mode 100644
index 0000000..fbf6555
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/PCM.cpp
@@ -0,0 +1,541 @@
+#pragma GCC diagnostic ignored "-Wmissing-field-initializers"

+

+#include "PCM.h"

+#include "NetworkCommunication/CANSessionMux.h"

+#include <string.h> // memset

+#include <unistd.h> // usleep

+/* This can be a constant, as long as nobody needs to updatie solenoids within

+    1/50 of a second. */

+static const INT32 kCANPeriod = 20;

+

+#define STATUS_1  			0x9041400

+#define STATUS_SOL_FAULTS  	0x9041440

+#define STATUS_DEBUG  		0x9041480

+

+#define EXPECTED_RESPONSE_TIMEOUT_MS	(50)

+#define GET_PCM_STATUS()			CtreCanNode::recMsg<PcmStatus_t> 		rx = GetRx<PcmStatus_t>			(STATUS_1,EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_PCM_SOL_FAULTS()		CtreCanNode::recMsg<PcmStatusFault_t> 	rx = GetRx<PcmStatusFault_t>	(STATUS_SOL_FAULTS,EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_PCM_DEBUG()				CtreCanNode::recMsg<PcmDebug_t> 		rx = GetRx<PcmDebug_t>			(STATUS_DEBUG,EXPECTED_RESPONSE_TIMEOUT_MS)

+

+#define CONTROL_1 			0x09041C00	/* PCM_Control */

+#define CONTROL_2 			0x09041C40	/* PCM_SupplemControl */

+#define CONTROL_3 			0x09041C80	/* PcmControlSetOneShotDur_t */

+

+/* encoder/decoders */

+typedef struct _PcmStatus_t{

+	/* Byte 0 */

+	unsigned SolenoidBits:8;

+	/* Byte 1 */

+	unsigned compressorOn:1;

+	unsigned stickyFaultFuseTripped:1;

+	unsigned stickyFaultCompCurrentTooHigh:1;

+	unsigned faultFuseTripped:1;

+	unsigned faultCompCurrentTooHigh:1;

+	unsigned faultHardwareFailure:1;

+	unsigned isCloseloopEnabled:1;

+	unsigned pressureSwitchEn:1;

+	/* Byte 2*/

+	unsigned battVoltage:8;

+	/* Byte 3 */

+	unsigned solenoidVoltageTop8:8;

+	/* Byte 4 */

+	unsigned compressorCurrentTop6:6;

+	unsigned solenoidVoltageBtm2:2;

+	/* Byte 5 */

+	unsigned StickyFault_dItooHigh :1;

+	unsigned Fault_dItooHigh :1;

+	unsigned moduleEnabled:1;

+	unsigned closedLoopOutput:1;

+	unsigned compressorCurrentBtm4:4;

+	/* Byte 6 */

+	unsigned tokenSeedTop8:8;

+	/* Byte 7 */

+	unsigned tokenSeedBtm8:8;

+}PcmStatus_t;

+

+typedef struct _PcmControl_t{

+	/* Byte 0 */

+	unsigned tokenTop8:8;

+	/* Byte 1 */

+	unsigned tokenBtm8:8;

+	/* Byte 2 */

+	unsigned solenoidBits:8;

+	/* Byte 3*/

+	unsigned reserved:4;

+	unsigned closeLoopOutput:1;

+	unsigned compressorOn:1;

+	unsigned closedLoopEnable:1;

+	unsigned clearStickyFaults:1;

+	/* Byte 4 */

+	unsigned OneShotField_h8:8;

+	/* Byte 5 */

+	unsigned OneShotField_l8:8;

+}PcmControl_t;

+

+typedef struct _PcmControlSetOneShotDur_t{

+	uint8_t sol10MsPerUnit[8];

+}PcmControlSetOneShotDur_t;

+

+typedef struct _PcmStatusFault_t{

+	/* Byte 0 */

+	unsigned SolenoidBlacklist:8;

+	/* Byte 1 */

+	unsigned reserved_bit0 :1;

+	unsigned reserved_bit1 :1;

+	unsigned reserved_bit2 :1;

+	unsigned reserved_bit3 :1;

+	unsigned StickyFault_CompNoCurrent :1;

+	unsigned Fault_CompNoCurrent :1;

+	unsigned StickyFault_SolenoidJumper :1;

+	unsigned Fault_SolenoidJumper :1;

+}PcmStatusFault_t;

+

+typedef struct _PcmDebug_t{

+	unsigned tokFailsTop8:8;

+	unsigned tokFailsBtm8:8;

+	unsigned lastFailedTokTop8:8;

+	unsigned lastFailedTokBtm8:8;

+	unsigned tokSuccessTop8:8;

+	unsigned tokSuccessBtm8:8;

+}PcmDebug_t;

+

+

+/* PCM Constructor - Clears all vars, establishes default settings, starts PCM background process

+ *

+ * @Return	-	void

+ *

+ * @Param 	-	deviceNumber	- 	Device ID of PCM to be controlled

+ */

+PCM::PCM(UINT8 deviceNumber): CtreCanNode(deviceNumber)

+{

+	RegisterRx(STATUS_1 | deviceNumber );

+	RegisterRx(STATUS_SOL_FAULTS | deviceNumber );

+	RegisterRx(STATUS_DEBUG | deviceNumber );

+	RegisterTx(CONTROL_1 | deviceNumber, kCANPeriod);

+	/* enable close loop */

+	SetClosedLoopControl(1);

+}

+/* PCM D'tor

+ */

+PCM::~PCM()

+{

+

+}

+

+/* Set PCM solenoid state

+ *

+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid

+ *

+ * @Param 	-	idx			- 	ID of solenoid (0-7)

+ * @Param 	-	en			- 	Enable / Disable identified solenoid

+ */

+CTR_Code PCM::SetSolenoids(uint8_t value, uint8_t mask)

+{

+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());

+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;

+	toFill->solenoidBits |= mask & value;

+	toFill->solenoidBits &= ~(mask & ~value);

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+

+/* Clears PCM sticky faults (indicators of past faults

+ *

+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid

+ *

+ * @Param 	-	clr		- 	Clear / do not clear faults

+ */

+CTR_Code PCM::ClearStickyFaults()

+{

+	int32_t status = 0;

+	uint8_t pcmSupplemControl[] = { 0, 0, 0, 0x80 }; /* only bit set is ClearStickyFaults */

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_2  | GetDeviceNumber(), pcmSupplemControl, sizeof(pcmSupplemControl), 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+

+/* Enables PCM Closed Loop Control of Compressor via pressure switch

+ *

+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid

+ *

+ * @Param 	-	en		- 	Enable / Disable Closed Loop Control

+ */

+CTR_Code PCM::SetClosedLoopControl(bool en)

+{

+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());

+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;

+	toFill->closedLoopEnable = en;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+/* Get solenoid Blacklist status

+ * @Return	-	CTR_Code	-	Error code (if any)

+ * @Param	-	idx			-	ID of solenoid [0,7] to fire one shot pulse.

+ */

+CTR_Code PCM::FireOneShotSolenoid(UINT8 idx)

+{

+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());

+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;

+	/* grab field as it is now */

+	uint16_t oneShotField;

+	oneShotField = toFill->OneShotField_h8;

+	oneShotField <<= 8;

+	oneShotField |= toFill->OneShotField_l8;

+	/* get the caller's channel */

+	uint16_t shift = 2*idx;

+	uint16_t mask = 3; /* two bits wide */

+	uint8_t chBits = (oneShotField >> shift) & mask;

+	/* flip it */

+	chBits = (chBits)%3 + 1;

+	/* clear out 2bits for this channel*/

+	oneShotField &= ~(mask << shift);

+	/* put new field in */

+	oneShotField |= chBits << shift;

+	/* apply field as it is now */

+	toFill->OneShotField_h8 = oneShotField >> 8;

+	toFill->OneShotField_l8 = oneShotField;

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+/* Configure the pulse width of a solenoid channel for one-shot pulse.

+ * Preprogrammed pulsewidth is 10ms resolute and can be between 20ms and 5.1s.

+ * @Return	-	CTR_Code	-	Error code (if any)

+ * @Param	-	idx			-	ID of solenoid [0,7] to configure.

+ * @Param	-	durMs		-	pulse width in ms.

+ */

+CTR_Code PCM::SetOneShotDurationMs(UINT8 idx,uint32_t durMs)

+{

+	/* sanity check caller's param */

+	if(idx > 8)

+		return CTR_InvalidParamValue;

+	/* get latest tx frame */

+	CtreCanNode::txTask<PcmControlSetOneShotDur_t> toFill = GetTx<PcmControlSetOneShotDur_t>(CONTROL_3 | GetDeviceNumber());

+	if(toFill.IsEmpty()){

+		/* only send this out if caller wants to do one-shots */

+		RegisterTx(CONTROL_3 | _deviceNumber, kCANPeriod);

+		/* grab it */

+		toFill = GetTx<PcmControlSetOneShotDur_t>(CONTROL_3 | GetDeviceNumber());

+	}

+	toFill->sol10MsPerUnit[idx] = std::min(durMs/10,(uint32_t)0xFF);

+	/* apply the new data bytes */

+	FlushTx(toFill);

+	return CTR_OKAY;

+}

+

+/* Get solenoid state

+ *

+ * @Return	-	True/False	-	True if solenoid enabled, false otherwise

+ *

+ * @Param 	-	idx		- 	ID of solenoid (0-7) to return status of

+ */

+CTR_Code PCM::GetSolenoid(UINT8 idx, bool &status)

+{

+	GET_PCM_STATUS();

+	status = (rx->SolenoidBits & (1ul<<(idx)) ) ? 1 : 0;

+	return rx.err;

+}

+

+/* Get pressure switch state

+ *

+ * @Return	-	True/False	-	True if pressure adequate, false if low

+ */

+CTR_Code PCM::GetPressure(bool &status)

+{

+	GET_PCM_STATUS();

+	status = (rx->pressureSwitchEn ) ? 1 : 0;

+	return rx.err;

+}

+

+/* Get compressor state

+ *

+ * @Return	-	True/False	-	True if enabled, false if otherwise

+ */

+CTR_Code PCM::GetCompressor(bool &status)

+{

+	GET_PCM_STATUS();

+	status = (rx->compressorOn);

+	return rx.err;

+}

+

+/* Get closed loop control state

+ *

+ * @Return	-	True/False	-	True if closed loop enabled, false if otherwise

+ */

+CTR_Code PCM::GetClosedLoopControl(bool &status)

+{

+	GET_PCM_STATUS();

+	status = (rx->isCloseloopEnabled);

+	return rx.err;

+}

+

+/* Get compressor current draw

+ *

+ * @Return	-	Amperes	-	Compressor current

+ */

+CTR_Code PCM::GetCompressorCurrent(float &status)

+{

+	GET_PCM_STATUS();

+	uint32_t temp =(rx->compressorCurrentTop6);

+	temp <<= 4;

+	temp |=  rx->compressorCurrentBtm4;

+	status = temp * 0.03125; /* 5.5 fixed pt value in Amps */

+	return rx.err;

+}

+

+/* Get voltage across solenoid rail

+ *

+ * @Return	-	Volts	-	Voltage across solenoid rail

+ */

+CTR_Code PCM::GetSolenoidVoltage(float &status)

+{

+	GET_PCM_STATUS();

+	uint32_t raw =(rx->solenoidVoltageTop8);

+	raw <<= 2;

+	raw |=  rx->solenoidVoltageBtm2;

+	status = (double) raw * 0.03125; /* 5.5 fixed pt value in Volts */

+	return rx.err;

+}

+

+/* Get hardware fault value

+ *

+ * @Return	-	True/False	-	True if hardware failure detected, false if otherwise

+ */

+CTR_Code PCM::GetHardwareFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->faultHardwareFailure;

+	return rx.err;

+}

+

+/* Get compressor fault value

+ *

+ * @Return	-	True/False	-	True if shorted compressor detected, false if otherwise

+ */

+CTR_Code PCM::GetCompressorCurrentTooHighFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->faultCompCurrentTooHigh;

+	return rx.err;

+}

+CTR_Code PCM::GetCompressorShortedStickyFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->StickyFault_dItooHigh;

+	return rx.err;

+}

+CTR_Code PCM::GetCompressorShortedFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->Fault_dItooHigh;

+	return rx.err;

+}

+CTR_Code PCM::GetCompressorNotConnectedStickyFault(bool &status)

+{

+	GET_PCM_SOL_FAULTS();

+	status = rx->StickyFault_CompNoCurrent;

+	return rx.err;

+}

+CTR_Code PCM::GetCompressorNotConnectedFault(bool &status)

+{

+	GET_PCM_SOL_FAULTS();

+	status = rx->Fault_CompNoCurrent;

+	return rx.err;

+}

+

+/* Get solenoid fault value

+ *

+ * @Return	-	True/False	-	True if shorted solenoid detected, false if otherwise

+ */

+CTR_Code PCM::GetSolenoidFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->faultFuseTripped;

+	return rx.err;

+}

+

+/* Get compressor sticky fault value

+ *

+ * @Return	-	True/False	-	True if solenoid had previously been shorted

+ * 								(and sticky fault was not cleared), false if otherwise

+ */

+CTR_Code PCM::GetCompressorCurrentTooHighStickyFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->stickyFaultCompCurrentTooHigh;

+	return rx.err;

+}

+

+/* Get solenoid sticky fault value

+ *

+ * @Return	-	True/False	-	True if compressor had previously been shorted

+ * 								(and sticky fault was not cleared), false if otherwise

+ */

+CTR_Code PCM::GetSolenoidStickyFault(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->stickyFaultFuseTripped;

+	return rx.err;

+}

+/* Get battery voltage

+ *

+ * @Return	-	Volts	-	Voltage across PCM power ports

+ */

+CTR_Code PCM::GetBatteryVoltage(float &status)

+{

+	GET_PCM_STATUS();

+	status = (float)rx->battVoltage * 0.05 + 4.0; /* 50mV per unit plus 4V. */

+	return rx.err;

+}

+/* Return status of module enable/disable

+ *

+ * @Return	-	bool		-	Returns TRUE if PCM is enabled, FALSE if disabled

+ */

+CTR_Code PCM::isModuleEnabled(bool &status)

+{

+	GET_PCM_STATUS();

+	status = rx->moduleEnabled;

+	return rx.err;

+}

+/* Get number of total failed PCM Control Frame

+ *

+ * @Return	-	Failed Control Frames	-	Number of failed control frames (tokenization fails)

+ *

+ * @WARNING	-	Return only valid if [SeekDebugFrames] is enabled

+ * 				See function SeekDebugFrames

+ * 				See function EnableSeekDebugFrames

+ */

+CTR_Code PCM::GetNumberOfFailedControlFrames(UINT16 &status)

+{

+	GET_PCM_DEBUG();

+	status = rx->tokFailsTop8;

+	status <<= 8;

+	status |= rx->tokFailsBtm8;

+	return rx.err;

+}

+/* Get raw Solenoid Blacklist

+ *

+ * @Return	-	BINARY	-	Raw binary breakdown of Solenoid Blacklist

+ * 							BIT7 = Solenoid 1, BIT6 = Solenoid 2, etc.

+ *

+ * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled

+ * 				See function SeekStatusFaultFrames

+ * 				See function EnableSeekStatusFaultFrames

+ */

+CTR_Code PCM::GetSolenoidBlackList(UINT8 &status)

+{

+	GET_PCM_SOL_FAULTS();

+	status = rx->SolenoidBlacklist;

+	return rx.err;

+}

+/* Get solenoid Blacklist status

+ * - Blacklisted solenoids cannot be enabled until PCM is power cycled

+ *

+ * @Return	-	True/False	-	True if Solenoid is blacklisted, false if otherwise

+ *

+ * @Param	-	idx			-	ID of solenoid [0,7]

+ *

+ * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled

+ * 				See function SeekStatusFaultFrames

+ * 				See function EnableSeekStatusFaultFrames

+ */

+CTR_Code PCM::IsSolenoidBlacklisted(UINT8 idx, bool &status)

+{

+	GET_PCM_SOL_FAULTS();

+	status = (rx->SolenoidBlacklist & (1ul<<(idx)) )? 1 : 0;

+	return rx.err;

+}

+//------------------ C interface --------------------------------------------//

+extern "C" {

+	void * c_PCM_Init(void) {

+		return new PCM();

+	}

+	CTR_Code c_SetSolenoid(void * handle, uint8_t value, uint8_t mask) {

+		return ((PCM*) handle)->SetSolenoids(value, mask);

+	}

+	CTR_Code c_SetClosedLoopControl(void * handle, INT8 param) {

+		return ((PCM*) handle)->SetClosedLoopControl(param);

+	}

+	CTR_Code c_ClearStickyFaults(void * handle, INT8 param) {

+		return ((PCM*) handle)->ClearStickyFaults();

+	}

+	CTR_Code c_GetSolenoid(void * handle, UINT8 idx, INT8 * status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetSolenoid(idx, bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetPressure(void * handle, INT8 * status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetPressure(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetCompressor(void * handle, INT8 * status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetCompressor(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetClosedLoopControl(void * handle, INT8 * status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetClosedLoopControl(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetCompressorCurrent(void * handle, float * status) {

+		CTR_Code retval = ((PCM*) handle)->GetCompressorCurrent(*status);

+		return retval;

+	}

+	CTR_Code c_GetSolenoidVoltage(void * handle, float*status) {

+		return ((PCM*) handle)->GetSolenoidVoltage(*status);

+	}

+	CTR_Code c_GetHardwareFault(void * handle, INT8*status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetHardwareFault(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetCompressorFault(void * handle, INT8*status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetCompressorCurrentTooHighFault(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetSolenoidFault(void * handle, INT8*status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetSolenoidFault(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetCompressorStickyFault(void * handle, INT8*status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetCompressorCurrentTooHighStickyFault(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetSolenoidStickyFault(void * handle, INT8*status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->GetSolenoidStickyFault(bstatus);

+		*status = bstatus;

+		return retval;

+	}

+	CTR_Code c_GetBatteryVoltage(void * handle, float*status) {

+		CTR_Code retval = ((PCM*) handle)->GetBatteryVoltage(*status);

+		return retval;

+	}

+	void c_SetDeviceNumber_PCM(void * handle, UINT8 deviceNumber) {

+	}

+	CTR_Code c_GetNumberOfFailedControlFrames(void * handle, UINT16*status) {

+		return ((PCM*) handle)->GetNumberOfFailedControlFrames(*status);

+	}

+	CTR_Code c_GetSolenoidBlackList(void * handle, UINT8 *status) {

+		return ((PCM*) handle)->GetSolenoidBlackList(*status);

+	}

+	CTR_Code c_IsSolenoidBlacklisted(void * handle, UINT8 idx, INT8*status) {

+		bool bstatus;

+		CTR_Code retval = ((PCM*) handle)->IsSolenoidBlacklisted(idx, bstatus);

+		*status = bstatus;

+		return retval;

+	}

+}

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/PCM.h b/aos/externals/allwpilib/hal/lib/Athena/ctre/PCM.h
new file mode 100644
index 0000000..19dfc54
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/PCM.h
@@ -0,0 +1,212 @@
+#ifndef PCM_H_

+#define PCM_H_

+#include "ctre.h"				//BIT Defines + Typedefs

+#include <NetworkCommunication/CANSessionMux.h>	//CAN Comm

+#include "CtreCanNode.h"

+#include <pthread.h>

+class PCM : public CtreCanNode

+{

+public:

+    PCM(UINT8 deviceNumber=0);

+    ~PCM();

+    

+    /* Set PCM solenoids state

+     *

+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoids

+     * @Param 	-	value		- 	Values for specified solenoids

+     * @Param 	-	mask		- 	Mask of solenoids to set

+     */

+    CTR_Code 	SetSolenoids(uint8_t value, uint8_t mask);

+

+    /* Enables PCM Closed Loop Control of Compressor via pressure switch

+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid

+     * @Param 	-	en		- 	Enable / Disable Closed Loop Control

+     */

+    CTR_Code 	SetClosedLoopControl(bool en);

+

+    /* Clears PCM sticky faults (indicators of past faults

+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid

+     */

+    CTR_Code 	ClearStickyFaults();

+    

+    /* Get solenoid state

+     *

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param 	-	idx		- 	ID of solenoid (0-7) to return if solenoid is on.

+     * @Param	-	status	-	OK if solenoid enabled, false otherwise

+     */

+    CTR_Code 	GetSolenoid(UINT8 idx, bool &status);

+

+    /* Get pressure switch state

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if pressure adequate, false if low

+     */

+    CTR_Code 	GetPressure(bool &status);

+

+    /* Get compressor state

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if compress ouput is on, false if otherwise

+     */

+    CTR_Code	GetCompressor(bool &status);

+

+    /* Get closed loop control state

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status	-	True if closed loop enabled, false if otherwise

+     */

+    CTR_Code 	GetClosedLoopControl(bool &status);

+

+    /* Get compressor current draw

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	Compressor current returned in Amperes (A)

+     */

+    CTR_Code 	GetCompressorCurrent(float &status);

+

+    /* Get voltage across solenoid rail

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	Voltage across solenoid rail in Volts (V)

+     */

+    CTR_Code 	GetSolenoidVoltage(float &status);

+

+    /* Get hardware fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if hardware failure detected, false if otherwise

+     */

+    CTR_Code 	GetHardwareFault(bool &status);

+

+    /* Get compressor fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if abnormally high compressor current detected, false if otherwise

+     */

+    CTR_Code 	GetCompressorCurrentTooHighFault(bool &status);

+

+    /* Get solenoid fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if shorted solenoid detected, false if otherwise

+     */

+    CTR_Code 	GetSolenoidFault(bool &status);

+

+    /* Get compressor sticky fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if solenoid had previously been shorted

+     * 								(and sticky fault was not cleared), false if otherwise

+     */

+    CTR_Code 	GetCompressorCurrentTooHighStickyFault(bool &status);

+    /* Get compressor shorted sticky fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if compressor output is shorted, false if otherwise

+     */

+    CTR_Code 	GetCompressorShortedStickyFault(bool &status);

+    /* Get compressor shorted fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if compressor output is shorted, false if otherwise

+     */

+    CTR_Code 	GetCompressorShortedFault(bool &status);

+    /* Get compressor is not connected sticky fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if compressor current is too low, 

+     * 					indicating compressor is not connected, false if otherwise

+     */

+    CTR_Code 	GetCompressorNotConnectedStickyFault(bool &status);

+    /* Get compressor is not connected fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if compressor current is too low, 

+     * 					indicating compressor is not connected, false if otherwise

+     */

+    CTR_Code 	GetCompressorNotConnectedFault(bool &status);

+

+    /* Get solenoid sticky fault value

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	True if compressor had previously been shorted

+     * 								(and sticky fault was not cleared), false if otherwise

+     */

+    CTR_Code 	GetSolenoidStickyFault(bool &status);

+

+    /* Get battery voltage

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	Voltage across PCM power ports in Volts (V)

+     */

+    CTR_Code 	GetBatteryVoltage(float &status);

+    

+    /* Set PCM Device Number and according CAN frame IDs

+     * @Return	-	void

+     * @Param	-	deviceNumber	-	Device number of PCM to control

+     */

+    void	SetDeviceNumber(UINT8 deviceNumber);

+    /* Get number of total failed PCM Control Frame

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	Number of failed control frames (tokenization fails)

+     * @WARNING	-	Return only valid if [SeekDebugFrames] is enabled

+     * 				See function SeekDebugFrames

+     * 				See function EnableSeekDebugFrames

+     */

+	CTR_Code GetNumberOfFailedControlFrames(UINT16 &status);

+    

+    /* Get raw Solenoid Blacklist

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	Raw binary breakdown of Solenoid Blacklist

+     * 								BIT7 = Solenoid 1, BIT6 = Solenoid 2, etc.

+     * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled

+     * 				See function SeekStatusFaultFrames

+     * 				See function EnableSeekStatusFaultFrames

+     */

+    CTR_Code 	GetSolenoidBlackList(UINT8 &status);

+

+    /* Get solenoid Blacklist status

+     * - Blacklisted solenoids cannot be enabled until PCM is power cycled

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	idx			-	ID of solenoid [0,7]

+     * @Param	-	status		-	True if Solenoid is blacklisted, false if otherwise

+     * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled

+     * 				See function SeekStatusFaultFrames

+     * 				See function EnableSeekStatusFaultFrames

+     */

+    CTR_Code 	IsSolenoidBlacklisted(UINT8 idx, bool &status);

+

+    /* Return status of module enable/disable

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	status		-	Returns TRUE if PCM is enabled, FALSE if disabled

+     */

+    CTR_Code	isModuleEnabled(bool &status);

+

+    /* Get solenoid Blacklist status

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	idx			-	ID of solenoid [0,7] to fire one shot pulse.

+     */

+    CTR_Code FireOneShotSolenoid(UINT8 idx);

+

+    /* Configure the pulse width of a solenoid channel for one-shot pulse.

+	 * Preprogrammed pulsewidth is 10ms resolute and can be between 20ms and 5.1s.

+     * @Return	-	CTR_Code	-	Error code (if any)

+     * @Param	-	idx			-	ID of solenoid [0,7] to configure.

+     * @Param	-	durMs		-	pulse width in ms.

+     */

+    CTR_Code SetOneShotDurationMs(UINT8 idx,uint32_t durMs);

+

+};

+//------------------ C interface --------------------------------------------//

+extern "C" {

+	void * c_PCM_Init(void);

+	CTR_Code c_SetSolenoids(void * handle,uint8_t value,uint8_t mask);

+	CTR_Code c_SetClosedLoopControl(void * handle,INT8 param);

+	CTR_Code c_ClearStickyFaults(void * handle,INT8 param);

+	CTR_Code c_GetSolenoid(void * handle,UINT8 idx,INT8 * status);

+	CTR_Code c_GetPressure(void * handle,INT8 * status);

+	CTR_Code c_GetCompressor(void * handle,INT8 * status);

+	CTR_Code c_GetClosedLoopControl(void * handle,INT8 * status);

+	CTR_Code c_GetCompressorCurrent(void * handle,float * status);

+	CTR_Code c_GetSolenoidVoltage(void * handle,float*status);

+	CTR_Code c_GetHardwareFault(void * handle,INT8*status);

+	CTR_Code c_GetCompressorFault(void * handle,INT8*status);

+	CTR_Code c_GetSolenoidFault(void * handle,INT8*status);

+	CTR_Code c_GetCompressorStickyFault(void * handle,INT8*status);

+	CTR_Code c_GetSolenoidStickyFault(void * handle,INT8*status);

+	CTR_Code c_GetBatteryVoltage(void * handle,float*status);

+	void c_SetDeviceNumber_PCM(void * handle,UINT8 deviceNumber);

+	void c_EnableSeekStatusFrames(void * handle,INT8 enable);

+	void c_EnableSeekStatusFaultFrames(void * handle,INT8 enable);

+	void c_EnableSeekDebugFrames(void * handle,INT8 enable);

+	CTR_Code c_GetNumberOfFailedControlFrames(void * handle,UINT16*status);

+	CTR_Code c_GetSolenoidBlackList(void * handle,UINT8 *status);

+	CTR_Code c_IsSolenoidBlacklisted(void * handle,UINT8 idx,INT8*status);

+}

+#endif

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/PDP.cpp b/aos/externals/allwpilib/hal/lib/Athena/ctre/PDP.cpp
new file mode 100644
index 0000000..2fb4c8f
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/PDP.cpp
@@ -0,0 +1,230 @@
+#include "PDP.h"

+#include "NetworkCommunication/CANSessionMux.h"	//CAN Comm

+#include <string.h> // memset

+#include <unistd.h> // usleep

+

+#define STATUS_1  		0x8041400

+#define STATUS_2  		0x8041440

+#define STATUS_3  		0x8041480

+#define STATUS_ENERGY	0x8041740

+

+#define CONTROL_1		0x08041C00	/* PDP_Control_ClearStats */

+

+#define EXPECTED_RESPONSE_TIMEOUT_MS	(50)

+#define GET_STATUS1()		CtreCanNode::recMsg<PdpStatus1_t> rx = GetRx<PdpStatus1_t>(STATUS_1,EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS2()		CtreCanNode::recMsg<PdpStatus2_t> rx = GetRx<PdpStatus2_t>(STATUS_2,EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS3()		CtreCanNode::recMsg<PdpStatus3_t> rx = GetRx<PdpStatus3_t>(STATUS_3,EXPECTED_RESPONSE_TIMEOUT_MS)

+#define GET_STATUS_ENERGY()	CtreCanNode::recMsg<PDP_Status_Energy_t> rx = GetRx<PDP_Status_Energy_t>(STATUS_ENERGY,EXPECTED_RESPONSE_TIMEOUT_MS)

+

+/* encoder/decoders */

+typedef struct _PdpStatus1_t{

+	unsigned chan1_h8:8;

+	unsigned chan2_h6:6;

+	unsigned chan1_l2:2;

+	unsigned chan3_h4:4;

+	unsigned chan2_l4:4;

+	unsigned chan4_h2:2;

+	unsigned chan3_l6:6;

+	unsigned chan4_l8:8;

+	unsigned chan5_h8:8;

+	unsigned chan6_h6:6;

+	unsigned chan5_l2:2;

+	unsigned reserved4:4;

+	unsigned chan6_l4:4;

+}PdpStatus1_t;

+typedef struct _PdpStatus2_t{

+	unsigned chan7_h8:8;

+	unsigned chan8_h6:6;

+	unsigned chan7_l2:2;

+	unsigned chan9_h4:4;

+	unsigned chan8_l4:4;

+	unsigned chan10_h2:2;

+	unsigned chan9_l6:6;

+	unsigned chan10_l8:8;

+	unsigned chan11_h8:8;

+	unsigned chan12_h6:6;

+	unsigned chan11_l2:2;

+	unsigned reserved4:4;

+	unsigned chan12_l4:4;

+}PdpStatus2_t;

+typedef struct _PdpStatus3_t{

+	unsigned chan13_h8:8;

+	unsigned chan14_h6:6;

+	unsigned chan13_l2:2;

+	unsigned chan15_h4:4;

+	unsigned chan14_l4:4;

+	unsigned chan16_h2:2;

+	unsigned chan15_l6:6;

+	unsigned chan16_l8:8;

+	unsigned internalResBattery_mOhms:8;

+	unsigned busVoltage:8;

+	unsigned temp:8;

+}PdpStatus3_t;

+typedef struct _PDP_Status_Energy_t {

+	unsigned TmeasMs_likelywillbe20ms_:8;

+	unsigned TotalCurrent_125mAperunit_h8:8;

+	unsigned Power_125mWperunit_h4:4;

+	unsigned TotalCurrent_125mAperunit_l4:4;

+	unsigned Power_125mWperunit_m8:8;

+	unsigned Energy_125mWPerUnitXTmeas_h4:4;

+	unsigned Power_125mWperunit_l4:4;

+	unsigned Energy_125mWPerUnitXTmeas_mh8:8;

+	unsigned Energy_125mWPerUnitXTmeas_ml8:8;

+	unsigned Energy_125mWPerUnitXTmeas_l8:8;

+} PDP_Status_Energy_t ;

+

+PDP::PDP(UINT8 deviceNumber): CtreCanNode(deviceNumber)

+{

+	RegisterRx(STATUS_1 | deviceNumber );

+	RegisterRx(STATUS_2 | deviceNumber );

+	RegisterRx(STATUS_3 | deviceNumber );

+}

+/* PDP D'tor

+ */

+PDP::~PDP()

+{

+}

+

+CTR_Code PDP::GetChannelCurrent(UINT8 idx, double &current)

+{

+	CTR_Code retval = CTR_InvalidParamValue;

+	uint32_t raw = 0;

+

+	if(idx <= 5){

+		GET_STATUS1();

+	    retval = rx.err;

+		switch(idx){

+			case 0:	raw = ((uint32_t)rx->chan1_h8 << 2) | rx->chan1_l2;	break;

+			case 1:	raw = ((uint32_t)rx->chan2_h6 << 4) | rx->chan2_l4;	break;

+			case 2:	raw = ((uint32_t)rx->chan3_h4 << 6) | rx->chan3_l6;	break;

+			case 3:	raw = ((uint32_t)rx->chan4_h2 << 8) | rx->chan4_l8;	break;

+			case 4:	raw = ((uint32_t)rx->chan5_h8 << 2) | rx->chan5_l2;	break;

+			case 5:	raw = ((uint32_t)rx->chan6_h6 << 4) | rx->chan6_l4;	break;

+			default:	retval = CTR_InvalidParamValue;	break;

+		}

+	}else if(idx <= 11){

+		GET_STATUS2();

+	    retval = rx.err;

+		switch(idx){

+			case  6:	raw = ((uint32_t)rx->chan7_h8  << 2) | rx->chan7_l2;	break;

+			case  7:	raw = ((uint32_t)rx->chan8_h6  << 4) | rx->chan8_l4;	break;

+			case  8:	raw = ((uint32_t)rx->chan9_h4  << 6) | rx->chan9_l6;	break;

+			case  9:	raw = ((uint32_t)rx->chan10_h2 << 8) | rx->chan10_l8;	break;

+			case 10:	raw = ((uint32_t)rx->chan11_h8 << 2) | rx->chan11_l2;	break;

+			case 11:	raw = ((uint32_t)rx->chan12_h6 << 4) | rx->chan12_l4;	break;

+			default:	retval = CTR_InvalidParamValue;	break;

+		}

+	}else if(idx <= 15){

+		GET_STATUS3();

+	    retval = rx.err;

+		switch(idx){

+			case 12:	raw = ((uint32_t)rx->chan13_h8  << 2) | rx->chan13_l2;	break;

+			case 13:	raw = ((uint32_t)rx->chan14_h6  << 4) | rx->chan14_l4;	break;

+			case 14:	raw = ((uint32_t)rx->chan15_h4  << 6) | rx->chan15_l6;	break;

+			case 15:	raw = ((uint32_t)rx->chan16_h2  << 8) | rx->chan16_l8;	break;

+			default:	retval = CTR_InvalidParamValue;	break;

+		}

+	}

+	/* convert to amps */

+	current = (double)raw * 0.125;  /* 7.3 fixed pt value in Amps */

+	/* signal caller with success */

+	return retval;

+}

+CTR_Code PDP::GetVoltage(double &voltage)

+{

+	GET_STATUS3();

+	uint32_t raw = rx->busVoltage;

+	voltage = (double)raw * 0.05 + 4.0; /* 50mV per unit plus 4V. */;

+	return rx.err;

+}

+CTR_Code PDP::GetTemperature(double &tempC)

+{

+	GET_STATUS3();

+	uint32_t raw = rx->temp;

+	tempC =	(double)raw * 1.03250836957542 - 67.8564500484966;

+	return rx.err;

+}

+CTR_Code PDP::GetTotalCurrent(double &currentAmps)

+{

+	GET_STATUS_ENERGY();

+	uint32_t raw;

+	raw = rx->TotalCurrent_125mAperunit_h8;

+	raw <<= 4;

+	raw |=  rx->TotalCurrent_125mAperunit_l4;

+	currentAmps = 0.125 * raw;

+	return rx.err;

+}

+CTR_Code PDP::GetTotalPower(double &powerWatts)

+{

+	GET_STATUS_ENERGY();

+	uint32_t raw;

+	raw = rx->Power_125mWperunit_h4;

+	raw <<= 8;

+	raw |=  rx->Power_125mWperunit_m8;

+	raw <<= 4;

+	raw |=  rx->Power_125mWperunit_l4;

+	powerWatts = 0.125 * raw;

+	return rx.err;

+}

+CTR_Code PDP::GetTotalEnergy(double &energyJoules)

+{

+	GET_STATUS_ENERGY();

+	uint32_t raw;

+	raw = rx->Energy_125mWPerUnitXTmeas_h4;

+	raw <<= 8;

+	raw |=  rx->Energy_125mWPerUnitXTmeas_mh8;

+	raw <<= 8;

+	raw |=  rx->Energy_125mWPerUnitXTmeas_ml8;

+	raw <<= 8;

+	raw |=  rx->Energy_125mWPerUnitXTmeas_l8;

+	energyJoules = 0.125 * raw; 						/* mW integrated every TmeasMs */

+	energyJoules *= rx->TmeasMs_likelywillbe20ms_;	/* multiplied by TmeasMs = joules */

+	return rx.err;

+}

+/* Clear sticky faults.

+ * @Return	-	CTR_Code	-	Error code (if any)

+ */

+CTR_Code PDP::ClearStickyFaults()

+{

+	int32_t status = 0;

+	uint8_t pdpControl[] = { 0x80 }; /* only bit set is ClearStickyFaults */

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_1  | GetDeviceNumber(), pdpControl, sizeof(pdpControl), 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+

+/* Reset Energy Signals

+ * @Return	-	CTR_Code	-	Error code (if any)

+ */

+CTR_Code PDP::ResetEnergy()

+{

+	int32_t status = 0;

+	uint8_t pdpControl[] = { 0x40 }; /* only bit set is ResetEnergy */

+	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_1  | GetDeviceNumber(), pdpControl, sizeof(pdpControl), 0, &status);

+	if(status)

+		return CTR_TxFailed;

+	return CTR_OKAY;

+}

+//------------------ C interface --------------------------------------------//

+extern "C" {

+	void * c_PDP_Init(void)

+	{

+		return new PDP();

+	}

+	CTR_Code c_GetChannelCurrent(void * handle,UINT8 idx, double *status)

+	{

+		return ((PDP*)handle)-> GetChannelCurrent(idx,*status);

+	}

+	CTR_Code c_GetVoltage(void * handle,double *status)

+	{

+		return ((PDP*)handle)-> GetVoltage(*status);

+	}

+	CTR_Code c_GetTemperature(void * handle,double *status)

+	{

+		return ((PDP*)handle)-> GetTemperature(*status);

+	}

+	void c_SetDeviceNumber_PDP(void * handle,UINT8 deviceNumber)

+	{

+	}

+}

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/PDP.h b/aos/externals/allwpilib/hal/lib/Athena/ctre/PDP.h
new file mode 100644
index 0000000..a289d1a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/PDP.h
@@ -0,0 +1,64 @@
+#ifndef PDP_H_

+#define PDP_H_

+#include "ctre.h"				//BIT Defines + Typedefs

+#include <NetworkCommunication/CANSessionMux.h>	//CAN Comm

+#include "CtreCanNode.h"

+#include <pthread.h>

+class PDP : public CtreCanNode

+{

+public:

+    /* Get PDP Channel Current

+     *

+     * @Param	-	deviceNumber	-	Device ID for PDP. Factory default is 60. Function defaults to 60.

+     */

+    PDP(UINT8 deviceNumber=0);

+    ~PDP();

+    /* Get PDP Channel Current

+     *

+     * @Return	-	CTR_Code	-	Error code (if any)

+     *

+     * @Param	-	idx			-	ID of channel to return current for (channels 1-16)

+     *

+     * @Param	-	status		-	Current of channel 'idx' in Amps (A)

+     */

+    CTR_Code GetChannelCurrent(UINT8 idx, double &status);

+

+    /* Get Bus Voltage of PDP

+     *

+     * @Return	-	CTR_Code	- 	Error code (if any)

+     *

+     * @Param	-	status		- 	Voltage (V) across PDP

+     */

+    CTR_Code GetVoltage(double &status);

+

+    /* Get Temperature of PDP

+     *

+     * @Return	-	CTR_Code	-	Error code (if any)

+     *

+     * @Param	-	status		-	Temperature of PDP in Centigrade / Celcius (C)

+     */

+    CTR_Code GetTemperature(double &status);

+

+	CTR_Code GetTotalCurrent(double &currentAmps);

+	CTR_Code GetTotalPower(double &powerWatts);

+	CTR_Code GetTotalEnergy(double &energyJoules);

+    /* Clear sticky faults.

+     * @Return	-	CTR_Code	-	Error code (if any)

+     */

+	CTR_Code ClearStickyFaults();

+

+	/* Reset Energy Signals

+	 * @Return	-	CTR_Code	-	Error code (if any)

+	 */

+	CTR_Code ResetEnergy();

+private:

+    uint64_t ReadCurrents(uint8_t api);

+};

+extern "C" {

+	void * c_PDP_Init();

+	CTR_Code c_GetChannelCurrent(void * handle,UINT8 idx, double *status);

+	CTR_Code c_GetVoltage(void * handle,double *status);

+	CTR_Code c_GetTemperature(void * handle,double *status);

+	void c_SetDeviceNumber_PDP(void * handle,UINT8 deviceNumber);

+}

+#endif /* PDP_H_ */

diff --git a/aos/externals/allwpilib/hal/lib/Athena/ctre/ctre.h b/aos/externals/allwpilib/hal/lib/Athena/ctre/ctre.h
new file mode 100644
index 0000000..c2d3f69
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/ctre/ctre.h
@@ -0,0 +1,50 @@
+#ifndef GLOBAL_H

+#define GLOBAL_H

+

+//Bit Defines

+#define BIT0 0x01

+#define BIT1 0x02

+#define BIT2 0x04

+#define BIT3 0x08

+#define BIT4 0x10

+#define BIT5 0x20

+#define BIT6 0x40

+#define BIT7 0x80

+#define BIT8  0x0100

+#define BIT9  0x0200

+#define BIT10 0x0400

+#define BIT11 0x0800

+#define BIT12 0x1000

+#define BIT13 0x2000

+#define BIT14 0x4000

+#define BIT15 0x8000

+

+//Signed

+typedef	signed char	INT8;

+typedef	signed short	INT16;

+typedef	signed int	INT32;

+typedef	signed long long INT64;

+

+//Unsigned

+typedef	unsigned char	UINT8;

+typedef	unsigned short	UINT16;

+typedef	unsigned int	UINT32;

+typedef	unsigned long long UINT64;

+

+//Other

+typedef	unsigned char	UCHAR;

+typedef unsigned short	USHORT;

+typedef	unsigned int	UINT;

+typedef unsigned long	ULONG;

+

+typedef enum {

+		CTR_OKAY,				//!< No Error - Function executed as expected

+		CTR_RxTimeout,			//!< CAN frame has not been received within specified period of time.

+		CTR_TxTimeout,			//!< Not used.

+		CTR_InvalidParamValue, 	//!< Caller passed an invalid param

+		CTR_UnexpectedArbId,	//!< Specified CAN Id is invalid.

+		CTR_TxFailed,			//!< Could not transmit the CAN frame.

+		CTR_SigNotUpdated,		//!< Have not received an value response for signal.

+}CTR_Code;

+

+#endif

diff --git a/aos/externals/allwpilib/hal/lib/Athena/i2clib/i2c-lib.h b/aos/externals/allwpilib/hal/lib/Athena/i2clib/i2c-lib.h
new file mode 100644
index 0000000..b34cb33
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/i2clib/i2c-lib.h
@@ -0,0 +1,16 @@
+#ifndef __I2C_LIB_H__

+#define __I2C_LIB_H__

+

+#ifdef __cplusplus

+extern "C" {

+#endif

+int i2clib_open(const char *device);

+void i2clib_close(int handle);

+int i2clib_read(int handle, uint8_t dev_addr, char *recv_buf, int32_t recv_size);

+int i2clib_write(int handle, uint8_t dev_addr, const char *send_buf, int32_t send_size);

+int i2clib_writeread(int handle, uint8_t dev_addr, const char *send_buf, int32_t send_size, char *recv_buf, int32_t recv_size);

+#ifdef __cplusplus

+}

+#endif

+

+#endif /* __I2C_LIB_H__ */
\ No newline at end of file
diff --git a/aos/externals/allwpilib/hal/lib/Athena/i2clib/i2clib/environs.h b/aos/externals/allwpilib/hal/lib/Athena/i2clib/i2clib/environs.h
new file mode 100644
index 0000000..d250585
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/i2clib/i2clib/environs.h
@@ -0,0 +1,66 @@
+/*!

+   \file environs.h

+   \brief Defines export symbols and namespace aliases

+*/

+/*

+   Copyright (c) 2014,

+   National Instruments Corporation.

+   All rights reserved.

+

+   File:        $Id: //lvaddon/FIRST/FRC/trunk/2015/tools/frcrti/export/1.0/1.0.0a6/includes/wpilib/i2clib/i2clib/environs.h#1 $

+   Author:      nipg.pl

+   Originated:  Mon Feb 10 10:39:42 2014

+*/

+

+#ifndef ___i2clib_environs_h___

+#define ___i2clib_environs_h___

+

+#include <nibuild/platform.h>

+

+/*

+ * kI2CLIBExportSymbols directs the build to export symbols modified by

+ * the kI2CLIBExport keyword. kI2CLIBNoExportSymbols directs the build to not

+ * import or export symbols modified by the kI2CLIBExport keyword. If

+ * neither of these are defined, the symbols modified by kI2CLIBExport are

+ * imported. These should be defined only when building the component,

+ * so clients do not need to trouble themselves with it.

+ */

+#if defined(kI2CLIBExportSymbols)

+   #define kI2CLIBExport kNIExport

+   #define kI2CLIBExportPre kNIExportPre

+   #define kI2CLIBExportPost kNIExportPost

+   #define kI2CLIBExportInline kNIExportInline

+   #define kI2CLIBExportData kNIExportData

+#elif defined(kI2CLIBNoExportSymbols)

+   #define kI2CLIBExport

+   #define kI2CLIBExportPre

+   #define kI2CLIBExportPost

+   #define kI2CLIBExportInline

+   #define kI2CLIBExportData

+#else

+   #define kI2CLIBExport kNIImport

+   #define kI2CLIBExportPre kNIImportPre

+   #define kI2CLIBExportPost kNIImportPost

+   #define kI2CLIBExportInline kNIImportInline

+   #define kI2CLIBExportData kNIImportData

+#endif

+

+// namespace declarations for aliasing ...

+

+#ifdef __cplusplus

+

+

+/*!

+   \namespace nI2CLIB_1_0

+   \brief i2c user-mode library Release 1.0

+*/

+namespace nI2CLIB_1_0

+{

+   // current versioned namespace aliases used by this package

+

+}

+

+#endif // __cplusplus

+

+#endif // ___i2clib_environs_h___

+

diff --git a/aos/externals/allwpilib/hal/lib/Athena/spilib/spi-lib.h b/aos/externals/allwpilib/hal/lib/Athena/spilib/spi-lib.h
new file mode 100644
index 0000000..b5c2a7a
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/spilib/spi-lib.h
@@ -0,0 +1,19 @@
+#ifndef __SPI_LIB_H__

+#define __SPI_LIB_H__

+

+#ifdef __cplusplus

+extern "C" {

+#endif

+int spilib_open(const char *device);

+void spilib_close(int handle);

+int spilib_setspeed(int handle, uint32_t speed);

+int spilib_setbitsperword(int handle, uint8_t bpw);

+int spilib_setopts(int handle, int msb_first, int sample_on_trailing, int clk_idle_high);

+int spilib_read(int handle, char *recv_buf, int32_t size);

+int spilib_write(int handle, const char *send_buf, int32_t size);

+int spilib_writeread(int handle, const char *send_buf, char *recv_buf, int32_t size);

+#ifdef __cplusplus

+}

+#endif

+

+#endif /* __SPI_LIB_H__ */
\ No newline at end of file
diff --git a/aos/externals/allwpilib/hal/lib/Athena/visa/visa.h b/aos/externals/allwpilib/hal/lib/Athena/visa/visa.h
new file mode 100644
index 0000000..3c6ad30
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/visa/visa.h
@@ -0,0 +1,1064 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc.                                        */
+/* Contains National Instruments extensions.                                 */
+/* Do not modify the contents of this file.                                  */
+/*---------------------------------------------------------------------------*/
+/*                                                                           */
+/* Title   : VISA.H                                                          */
+/* Date    : 10-09-2006                                                      */
+/* Purpose : Include file for the VISA Library 4.0 specification             */
+/*                                                                           */
+/*---------------------------------------------------------------------------*/
+/* When using NI-VISA extensions, you must link with the VISA library that   */
+/* comes with NI-VISA.  Currently, the extensions provided by NI-VISA are:   */
+/*                                                                           */
+/* PXI (Compact PCI eXtensions for Instrumentation) and PCI support.  To use */
+/* this, you must define the macro NIVISA_PXI before including this header.  */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/*                                                                           */
+/* A fast set of macros for viPeekXX/viPokeXX that guarantees binary         */
+/* compatibility with other implementations of VISA.  To use this, you must  */
+/* define the macro NIVISA_PEEKPOKE before including this header.            */
+/*                                                                           */
+/* Support for USB devices that do not conform to a specific class.  To use  */
+/* this, you must define the macro NIVISA_USB before including this header.  */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISA_HEADER__
+#define __VISA_HEADER__
+
+#include <stdarg.h>
+
+#if !defined(__VISATYPE_HEADER__)
+#include "visatype.h"
+#endif
+
+#define VI_SPEC_VERSION     (0x00400000UL)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+   extern "C" {
+#endif
+
+#if defined(_CVI_)
+#pragma EnableLibraryRuntimeChecking
+#endif
+
+/*- VISA Types --------------------------------------------------------------*/
+
+typedef ViObject             ViEvent;
+typedef ViEvent      _VI_PTR ViPEvent;
+typedef ViObject             ViFindList;
+typedef ViFindList   _VI_PTR ViPFindList;
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+typedef ViUInt64             ViBusAddress;
+typedef ViUInt64             ViBusSize;
+typedef ViUInt64             ViAttrState;
+#else
+typedef ViUInt32             ViBusAddress;
+typedef ViUInt32             ViBusSize;
+typedef ViUInt32             ViAttrState;
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64             ViBusAddress64;
+typedef ViBusAddress64 _VI_PTR ViPBusAddress64;
+#endif
+
+typedef ViUInt32             ViEventType;
+typedef ViEventType  _VI_PTR ViPEventType;
+typedef ViEventType  _VI_PTR ViAEventType;
+typedef void         _VI_PTR ViPAttrState;
+typedef ViAttr       _VI_PTR ViPAttr;
+typedef ViAttr       _VI_PTR ViAAttr;
+
+typedef ViString             ViKeyId;
+typedef ViPString            ViPKeyId;
+typedef ViUInt32             ViJobId;
+typedef ViJobId      _VI_PTR ViPJobId;
+typedef ViUInt32             ViAccessMode;
+typedef ViAccessMode _VI_PTR ViPAccessMode;
+typedef ViBusAddress _VI_PTR ViPBusAddress;
+typedef ViUInt32             ViEventFilter;
+
+typedef va_list              ViVAList;
+
+typedef ViStatus (_VI_FUNCH _VI_PTR ViHndlr)
+   (ViSession vi, ViEventType eventType, ViEvent event, ViAddr userHandle);
+
+/*- Resource Manager Functions and Operations -------------------------------*/
+
+ViStatus _VI_FUNC  viOpenDefaultRM (ViPSession vi);
+ViStatus _VI_FUNC  viFindRsrc      (ViSession sesn, ViString expr, ViPFindList vi,
+                                    ViPUInt32 retCnt, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC  viFindNext      (ViFindList vi, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC  viParseRsrc     (ViSession rmSesn, ViRsrc rsrcName,
+                                    ViPUInt16 intfType, ViPUInt16 intfNum);
+ViStatus _VI_FUNC  viParseRsrcEx   (ViSession rmSesn, ViRsrc rsrcName, ViPUInt16 intfType,
+                                    ViPUInt16 intfNum, ViChar _VI_FAR rsrcClass[],
+                                    ViChar _VI_FAR expandedUnaliasedName[],
+                                    ViChar _VI_FAR aliasIfExists[]);
+ViStatus _VI_FUNC  viOpen          (ViSession sesn, ViRsrc name, ViAccessMode mode,
+                                    ViUInt32 timeout, ViPSession vi);
+
+/*- Resource Template Operations --------------------------------------------*/
+
+ViStatus _VI_FUNC  viClose         (ViObject vi);
+ViStatus _VI_FUNC  viSetAttribute  (ViObject vi, ViAttr attrName, ViAttrState attrValue);
+ViStatus _VI_FUNC  viGetAttribute  (ViObject vi, ViAttr attrName, void _VI_PTR attrValue);
+ViStatus _VI_FUNC  viStatusDesc    (ViObject vi, ViStatus status, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC  viTerminate     (ViObject vi, ViUInt16 degree, ViJobId jobId);
+
+ViStatus _VI_FUNC  viLock          (ViSession vi, ViAccessMode lockType, ViUInt32 timeout,
+                                    ViKeyId requestedKey, ViChar _VI_FAR accessKey[]);
+ViStatus _VI_FUNC  viUnlock        (ViSession vi);
+ViStatus _VI_FUNC  viEnableEvent   (ViSession vi, ViEventType eventType, ViUInt16 mechanism,
+                                    ViEventFilter context);
+ViStatus _VI_FUNC  viDisableEvent  (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC  viDiscardEvents (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC  viWaitOnEvent   (ViSession vi, ViEventType inEventType, ViUInt32 timeout,
+                                    ViPEventType outEventType, ViPEvent outContext);
+ViStatus _VI_FUNC  viInstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+                                    ViAddr userHandle);
+ViStatus _VI_FUNC  viUninstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+                                      ViAddr userHandle);
+
+/*- Basic I/O Operations ----------------------------------------------------*/
+
+ViStatus _VI_FUNC  viRead          (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viReadAsync     (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPJobId  jobId);
+ViStatus _VI_FUNC  viReadToFile    (ViSession vi, ViConstString filename, ViUInt32 cnt,
+                                    ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viWrite         (ViSession vi, ViBuf  buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viWriteAsync    (ViSession vi, ViBuf  buf, ViUInt32 cnt, ViPJobId  jobId);
+ViStatus _VI_FUNC  viWriteFromFile (ViSession vi, ViConstString filename, ViUInt32 cnt,
+                                    ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viAssertTrigger (ViSession vi, ViUInt16 protocol);
+ViStatus _VI_FUNC  viReadSTB       (ViSession vi, ViPUInt16 status);
+ViStatus _VI_FUNC  viClear         (ViSession vi);
+
+/*- Formatted and Buffered I/O Operations -----------------------------------*/
+
+ViStatus _VI_FUNC  viSetBuf        (ViSession vi, ViUInt16 mask, ViUInt32 size);
+ViStatus _VI_FUNC  viFlush         (ViSession vi, ViUInt16 mask);
+
+ViStatus _VI_FUNC  viBufWrite      (ViSession vi, ViBuf  buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viBufRead       (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+
+ViStatus _VI_FUNCC viPrintf        (ViSession vi, ViString writeFmt, ...);
+ViStatus _VI_FUNC  viVPrintf       (ViSession vi, ViString writeFmt, ViVAList params);
+ViStatus _VI_FUNCC viSPrintf       (ViSession vi, ViPBuf buf, ViString writeFmt, ...);
+ViStatus _VI_FUNC  viVSPrintf      (ViSession vi, ViPBuf buf, ViString writeFmt,
+                                    ViVAList parms);
+
+ViStatus _VI_FUNCC viScanf         (ViSession vi, ViString readFmt, ...);
+ViStatus _VI_FUNC  viVScanf        (ViSession vi, ViString readFmt, ViVAList params);
+ViStatus _VI_FUNCC viSScanf        (ViSession vi, ViBuf buf, ViString readFmt, ...);
+ViStatus _VI_FUNC  viVSScanf       (ViSession vi, ViBuf buf, ViString readFmt,
+                                    ViVAList parms);
+
+ViStatus _VI_FUNCC viQueryf        (ViSession vi, ViString writeFmt, ViString readFmt, ...);
+ViStatus _VI_FUNC  viVQueryf       (ViSession vi, ViString writeFmt, ViString readFmt, 
+                                    ViVAList params);
+
+/*- Memory I/O Operations ---------------------------------------------------*/
+
+ViStatus _VI_FUNC  viIn8           (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt8  val8);
+ViStatus _VI_FUNC  viOut8          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt8   val8);
+ViStatus _VI_FUNC  viIn16          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt16 val16);
+ViStatus _VI_FUNC  viOut16         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt16  val16);
+ViStatus _VI_FUNC  viIn32          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt32 val32);
+ViStatus _VI_FUNC  viOut32         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt32  val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viIn64          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt64 val64);
+ViStatus _VI_FUNC  viOut64         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt64  val64);
+
+ViStatus _VI_FUNC  viIn8Ex         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt8  val8);
+ViStatus _VI_FUNC  viOut8Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt8   val8);
+ViStatus _VI_FUNC  viIn16Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt16 val16);
+ViStatus _VI_FUNC  viOut16Ex       (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt16  val16);
+ViStatus _VI_FUNC  viIn32Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt32 val32);
+ViStatus _VI_FUNC  viOut32Ex       (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt32  val32);
+ViStatus _VI_FUNC  viIn64Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt64 val64);
+ViStatus _VI_FUNC  viOut64Ex       (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt64  val64);
+#endif
+
+ViStatus _VI_FUNC  viMoveIn8       (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveOut8      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveIn16      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveOut16     (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveIn32      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC  viMoveOut32     (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMoveIn64      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC  viMoveOut64     (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+
+ViStatus _VI_FUNC  viMoveIn8Ex     (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveOut8Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveIn16Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveOut16Ex   (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveIn32Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC  viMoveOut32Ex   (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC  viMoveIn64Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC  viMoveOut64Ex   (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+#endif
+
+ViStatus _VI_FUNC  viMove          (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength); 
+ViStatus _VI_FUNC  viMoveAsync     (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength, ViPJobId jobId);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMoveEx        (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress64 destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength); 
+ViStatus _VI_FUNC  viMoveAsyncEx   (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress64 destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength, ViPJobId jobId);
+#endif
+
+ViStatus _VI_FUNC  viMapAddress    (ViSession vi, ViUInt16 mapSpace, ViBusAddress mapOffset,
+                                    ViBusSize mapSize, ViBoolean access,
+                                    ViAddr suggested, ViPAddr address);
+ViStatus _VI_FUNC  viUnmapAddress  (ViSession vi);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMapAddressEx  (ViSession vi, ViUInt16 mapSpace, ViBusAddress64 mapOffset,
+                                    ViBusSize mapSize, ViBoolean access,
+                                    ViAddr suggested, ViPAddr address);
+#endif
+
+void     _VI_FUNC  viPeek8         (ViSession vi, ViAddr address, ViPUInt8  val8);
+void     _VI_FUNC  viPoke8         (ViSession vi, ViAddr address, ViUInt8   val8);
+void     _VI_FUNC  viPeek16        (ViSession vi, ViAddr address, ViPUInt16 val16);
+void     _VI_FUNC  viPoke16        (ViSession vi, ViAddr address, ViUInt16  val16);
+void     _VI_FUNC  viPeek32        (ViSession vi, ViAddr address, ViPUInt32 val32);
+void     _VI_FUNC  viPoke32        (ViSession vi, ViAddr address, ViUInt32  val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+void     _VI_FUNC  viPeek64        (ViSession vi, ViAddr address, ViPUInt64 val64);
+void     _VI_FUNC  viPoke64        (ViSession vi, ViAddr address, ViUInt64  val64);
+#endif
+
+/*- Shared Memory Operations ------------------------------------------------*/
+
+ViStatus _VI_FUNC  viMemAlloc      (ViSession vi, ViBusSize size, ViPBusAddress offset);
+ViStatus _VI_FUNC  viMemFree       (ViSession vi, ViBusAddress offset);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMemAllocEx    (ViSession vi, ViBusSize size, ViPBusAddress64 offset);
+ViStatus _VI_FUNC  viMemFreeEx     (ViSession vi, ViBusAddress64 offset);
+#endif
+
+/*- Interface Specific Operations -------------------------------------------*/
+
+ViStatus _VI_FUNC  viGpibControlREN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC  viGpibControlATN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC  viGpibSendIFC   (ViSession vi);
+ViStatus _VI_FUNC  viGpibCommand   (ViSession vi, ViBuf cmd, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viGpibPassControl(ViSession vi, ViUInt16 primAddr, ViUInt16 secAddr);
+
+ViStatus _VI_FUNC  viVxiCommandQuery(ViSession vi, ViUInt16 mode, ViUInt32 cmd,
+                                     ViPUInt32 response);
+ViStatus _VI_FUNC  viAssertUtilSignal(ViSession vi, ViUInt16 line);
+ViStatus _VI_FUNC  viAssertIntrSignal(ViSession vi, ViInt16 mode, ViUInt32 statusID);
+ViStatus _VI_FUNC  viMapTrigger    (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest, 
+                                    ViUInt16 mode);
+ViStatus _VI_FUNC  viUnmapTrigger  (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest);
+ViStatus _VI_FUNC  viUsbControlOut (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+                                    ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+                                    ViBuf buf);
+ViStatus _VI_FUNC  viUsbControlIn  (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+                                    ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+                                    ViPBuf buf, ViPUInt16 retCnt);
+
+/*- Attributes (platform independent size) ----------------------------------*/
+
+#define VI_ATTR_RSRC_CLASS          (0xBFFF0001UL)
+#define VI_ATTR_RSRC_NAME           (0xBFFF0002UL)
+#define VI_ATTR_RSRC_IMPL_VERSION   (0x3FFF0003UL)
+#define VI_ATTR_RSRC_LOCK_STATE     (0x3FFF0004UL)
+#define VI_ATTR_MAX_QUEUE_LENGTH    (0x3FFF0005UL)
+#define VI_ATTR_USER_DATA_32        (0x3FFF0007UL)
+#define VI_ATTR_FDC_CHNL            (0x3FFF000DUL)
+#define VI_ATTR_FDC_MODE            (0x3FFF000FUL)
+#define VI_ATTR_FDC_GEN_SIGNAL_EN   (0x3FFF0011UL)
+#define VI_ATTR_FDC_USE_PAIR        (0x3FFF0013UL)
+#define VI_ATTR_SEND_END_EN         (0x3FFF0016UL)
+#define VI_ATTR_TERMCHAR            (0x3FFF0018UL)
+#define VI_ATTR_TMO_VALUE           (0x3FFF001AUL)
+#define VI_ATTR_GPIB_READDR_EN      (0x3FFF001BUL)
+#define VI_ATTR_IO_PROT             (0x3FFF001CUL)
+#define VI_ATTR_DMA_ALLOW_EN        (0x3FFF001EUL)
+#define VI_ATTR_ASRL_BAUD           (0x3FFF0021UL)
+#define VI_ATTR_ASRL_DATA_BITS      (0x3FFF0022UL)
+#define VI_ATTR_ASRL_PARITY         (0x3FFF0023UL)
+#define VI_ATTR_ASRL_STOP_BITS      (0x3FFF0024UL)
+#define VI_ATTR_ASRL_FLOW_CNTRL     (0x3FFF0025UL)
+#define VI_ATTR_RD_BUF_OPER_MODE    (0x3FFF002AUL)
+#define VI_ATTR_RD_BUF_SIZE         (0x3FFF002BUL)
+#define VI_ATTR_WR_BUF_OPER_MODE    (0x3FFF002DUL)
+#define VI_ATTR_WR_BUF_SIZE         (0x3FFF002EUL)
+#define VI_ATTR_SUPPRESS_END_EN     (0x3FFF0036UL)
+#define VI_ATTR_TERMCHAR_EN         (0x3FFF0038UL)
+#define VI_ATTR_DEST_ACCESS_PRIV    (0x3FFF0039UL)
+#define VI_ATTR_DEST_BYTE_ORDER     (0x3FFF003AUL)
+#define VI_ATTR_SRC_ACCESS_PRIV     (0x3FFF003CUL)
+#define VI_ATTR_SRC_BYTE_ORDER      (0x3FFF003DUL)
+#define VI_ATTR_SRC_INCREMENT       (0x3FFF0040UL)
+#define VI_ATTR_DEST_INCREMENT      (0x3FFF0041UL)
+#define VI_ATTR_WIN_ACCESS_PRIV     (0x3FFF0045UL)
+#define VI_ATTR_WIN_BYTE_ORDER      (0x3FFF0047UL)
+#define VI_ATTR_GPIB_ATN_STATE      (0x3FFF0057UL)
+#define VI_ATTR_GPIB_ADDR_STATE     (0x3FFF005CUL)
+#define VI_ATTR_GPIB_CIC_STATE      (0x3FFF005EUL)
+#define VI_ATTR_GPIB_NDAC_STATE     (0x3FFF0062UL)
+#define VI_ATTR_GPIB_SRQ_STATE      (0x3FFF0067UL)
+#define VI_ATTR_GPIB_SYS_CNTRL_STATE (0x3FFF0068UL)
+#define VI_ATTR_GPIB_HS488_CBL_LEN  (0x3FFF0069UL)
+#define VI_ATTR_CMDR_LA             (0x3FFF006BUL)
+#define VI_ATTR_VXI_DEV_CLASS       (0x3FFF006CUL)
+#define VI_ATTR_MAINFRAME_LA        (0x3FFF0070UL)
+#define VI_ATTR_MANF_NAME           (0xBFFF0072UL)
+#define VI_ATTR_MODEL_NAME          (0xBFFF0077UL)
+#define VI_ATTR_VXI_VME_INTR_STATUS (0x3FFF008BUL)
+#define VI_ATTR_VXI_TRIG_STATUS     (0x3FFF008DUL)
+#define VI_ATTR_VXI_VME_SYSFAIL_STATE (0x3FFF0094UL)
+#define VI_ATTR_WIN_BASE_ADDR_32    (0x3FFF0098UL)
+#define VI_ATTR_WIN_SIZE_32         (0x3FFF009AUL)
+#define VI_ATTR_ASRL_AVAIL_NUM      (0x3FFF00ACUL)
+#define VI_ATTR_MEM_BASE_32         (0x3FFF00ADUL)
+#define VI_ATTR_ASRL_CTS_STATE      (0x3FFF00AEUL)
+#define VI_ATTR_ASRL_DCD_STATE      (0x3FFF00AFUL)
+#define VI_ATTR_ASRL_DSR_STATE      (0x3FFF00B1UL)
+#define VI_ATTR_ASRL_DTR_STATE      (0x3FFF00B2UL)
+#define VI_ATTR_ASRL_END_IN         (0x3FFF00B3UL)
+#define VI_ATTR_ASRL_END_OUT        (0x3FFF00B4UL)
+#define VI_ATTR_ASRL_REPLACE_CHAR   (0x3FFF00BEUL)
+#define VI_ATTR_ASRL_RI_STATE       (0x3FFF00BFUL)
+#define VI_ATTR_ASRL_RTS_STATE      (0x3FFF00C0UL)
+#define VI_ATTR_ASRL_XON_CHAR       (0x3FFF00C1UL)
+#define VI_ATTR_ASRL_XOFF_CHAR      (0x3FFF00C2UL)
+#define VI_ATTR_WIN_ACCESS          (0x3FFF00C3UL)
+#define VI_ATTR_RM_SESSION          (0x3FFF00C4UL)
+#define VI_ATTR_VXI_LA              (0x3FFF00D5UL)
+#define VI_ATTR_MANF_ID             (0x3FFF00D9UL)
+#define VI_ATTR_MEM_SIZE_32         (0x3FFF00DDUL)
+#define VI_ATTR_MEM_SPACE           (0x3FFF00DEUL)
+#define VI_ATTR_MODEL_CODE          (0x3FFF00DFUL)
+#define VI_ATTR_SLOT                (0x3FFF00E8UL)
+#define VI_ATTR_INTF_INST_NAME      (0xBFFF00E9UL)
+#define VI_ATTR_IMMEDIATE_SERV      (0x3FFF0100UL)
+#define VI_ATTR_INTF_PARENT_NUM     (0x3FFF0101UL)
+#define VI_ATTR_RSRC_SPEC_VERSION   (0x3FFF0170UL)
+#define VI_ATTR_INTF_TYPE           (0x3FFF0171UL)
+#define VI_ATTR_GPIB_PRIMARY_ADDR   (0x3FFF0172UL)
+#define VI_ATTR_GPIB_SECONDARY_ADDR (0x3FFF0173UL)
+#define VI_ATTR_RSRC_MANF_NAME      (0xBFFF0174UL)
+#define VI_ATTR_RSRC_MANF_ID        (0x3FFF0175UL)
+#define VI_ATTR_INTF_NUM            (0x3FFF0176UL)
+#define VI_ATTR_TRIG_ID             (0x3FFF0177UL)
+#define VI_ATTR_GPIB_REN_STATE      (0x3FFF0181UL)
+#define VI_ATTR_GPIB_UNADDR_EN      (0x3FFF0184UL)
+#define VI_ATTR_DEV_STATUS_BYTE     (0x3FFF0189UL)
+#define VI_ATTR_FILE_APPEND_EN      (0x3FFF0192UL)
+#define VI_ATTR_VXI_TRIG_SUPPORT    (0x3FFF0194UL)
+#define VI_ATTR_TCPIP_ADDR          (0xBFFF0195UL)
+#define VI_ATTR_TCPIP_HOSTNAME      (0xBFFF0196UL)
+#define VI_ATTR_TCPIP_PORT          (0x3FFF0197UL)
+#define VI_ATTR_TCPIP_DEVICE_NAME   (0xBFFF0199UL)
+#define VI_ATTR_TCPIP_NODELAY       (0x3FFF019AUL)
+#define VI_ATTR_TCPIP_KEEPALIVE     (0x3FFF019BUL)
+#define VI_ATTR_4882_COMPLIANT      (0x3FFF019FUL)
+#define VI_ATTR_USB_SERIAL_NUM      (0xBFFF01A0UL)
+#define VI_ATTR_USB_INTFC_NUM       (0x3FFF01A1UL)
+#define VI_ATTR_USB_PROTOCOL        (0x3FFF01A7UL)
+#define VI_ATTR_USB_MAX_INTR_SIZE   (0x3FFF01AFUL)
+#define VI_ATTR_PXI_DEV_NUM         (0x3FFF0201UL)
+#define VI_ATTR_PXI_FUNC_NUM        (0x3FFF0202UL)
+#define VI_ATTR_PXI_BUS_NUM         (0x3FFF0205UL)
+#define VI_ATTR_PXI_CHASSIS         (0x3FFF0206UL)
+#define VI_ATTR_PXI_SLOTPATH        (0xBFFF0207UL)
+#define VI_ATTR_PXI_SLOT_LBUS_LEFT  (0x3FFF0208UL)
+#define VI_ATTR_PXI_SLOT_LBUS_RIGHT (0x3FFF0209UL)
+#define VI_ATTR_PXI_TRIG_BUS        (0x3FFF020AUL)
+#define VI_ATTR_PXI_STAR_TRIG_BUS   (0x3FFF020BUL)
+#define VI_ATTR_PXI_STAR_TRIG_LINE  (0x3FFF020CUL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR0   (0x3FFF0211UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR1   (0x3FFF0212UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR2   (0x3FFF0213UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR3   (0x3FFF0214UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR4   (0x3FFF0215UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR5   (0x3FFF0216UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR0   (0x3FFF0221UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR1   (0x3FFF0222UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR2   (0x3FFF0223UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR3   (0x3FFF0224UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR4   (0x3FFF0225UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR5   (0x3FFF0226UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR0   (0x3FFF0231UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR1   (0x3FFF0232UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR2   (0x3FFF0233UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR3   (0x3FFF0234UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR4   (0x3FFF0235UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR5   (0x3FFF0236UL)
+#define VI_ATTR_PXI_IS_EXPRESS      (0x3FFF0240UL)
+#define VI_ATTR_PXI_SLOT_LWIDTH     (0x3FFF0241UL)
+#define VI_ATTR_PXI_MAX_LWIDTH      (0x3FFF0242UL)
+#define VI_ATTR_PXI_ACTUAL_LWIDTH   (0x3FFF0243UL)
+#define VI_ATTR_PXI_DSTAR_BUS       (0x3FFF0244UL)
+#define VI_ATTR_PXI_DSTAR_SET       (0x3FFF0245UL)
+
+#define VI_ATTR_JOB_ID              (0x3FFF4006UL)
+#define VI_ATTR_EVENT_TYPE          (0x3FFF4010UL)
+#define VI_ATTR_SIGP_STATUS_ID      (0x3FFF4011UL)
+#define VI_ATTR_RECV_TRIG_ID        (0x3FFF4012UL)
+#define VI_ATTR_INTR_STATUS_ID      (0x3FFF4023UL)
+#define VI_ATTR_STATUS              (0x3FFF4025UL)
+#define VI_ATTR_RET_COUNT_32        (0x3FFF4026UL)
+#define VI_ATTR_BUFFER              (0x3FFF4027UL)
+#define VI_ATTR_RECV_INTR_LEVEL     (0x3FFF4041UL)
+#define VI_ATTR_OPER_NAME           (0xBFFF4042UL)
+#define VI_ATTR_GPIB_RECV_CIC_STATE (0x3FFF4193UL)
+#define VI_ATTR_RECV_TCPIP_ADDR     (0xBFFF4198UL)
+#define VI_ATTR_USB_RECV_INTR_SIZE  (0x3FFF41B0UL)
+#define VI_ATTR_USB_RECV_INTR_DATA  (0xBFFF41B1UL)
+
+/*- Attributes (platform dependent size) ------------------------------------*/
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_USER_DATA_64        (0x3FFF000AUL)
+#define VI_ATTR_RET_COUNT_64        (0x3FFF4028UL)
+#define VI_ATTR_USER_DATA           (VI_ATTR_USER_DATA_64)
+#define VI_ATTR_RET_COUNT           (VI_ATTR_RET_COUNT_64)
+#else
+#define VI_ATTR_USER_DATA           (VI_ATTR_USER_DATA_32)
+#define VI_ATTR_RET_COUNT           (VI_ATTR_RET_COUNT_32)
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+#define VI_ATTR_WIN_BASE_ADDR_64    (0x3FFF009BUL)
+#define VI_ATTR_WIN_SIZE_64         (0x3FFF009CUL)
+#define VI_ATTR_MEM_BASE_64         (0x3FFF00D0UL)
+#define VI_ATTR_MEM_SIZE_64         (0x3FFF00D1UL)
+#endif
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_WIN_BASE_ADDR       (VI_ATTR_WIN_BASE_ADDR_64)
+#define VI_ATTR_WIN_SIZE            (VI_ATTR_WIN_SIZE_64)
+#define VI_ATTR_MEM_BASE            (VI_ATTR_MEM_BASE_64)
+#define VI_ATTR_MEM_SIZE            (VI_ATTR_MEM_SIZE_64)
+#else
+#define VI_ATTR_WIN_BASE_ADDR       (VI_ATTR_WIN_BASE_ADDR_32)
+#define VI_ATTR_WIN_SIZE            (VI_ATTR_WIN_SIZE_32)
+#define VI_ATTR_MEM_BASE            (VI_ATTR_MEM_BASE_32)
+#define VI_ATTR_MEM_SIZE            (VI_ATTR_MEM_SIZE_32)
+#endif
+
+/*- Event Types -------------------------------------------------------------*/
+
+#define VI_EVENT_IO_COMPLETION      (0x3FFF2009UL)
+#define VI_EVENT_TRIG               (0xBFFF200AUL)
+#define VI_EVENT_SERVICE_REQ        (0x3FFF200BUL)
+#define VI_EVENT_CLEAR              (0x3FFF200DUL)
+#define VI_EVENT_EXCEPTION          (0xBFFF200EUL)
+#define VI_EVENT_GPIB_CIC           (0x3FFF2012UL)
+#define VI_EVENT_GPIB_TALK          (0x3FFF2013UL)
+#define VI_EVENT_GPIB_LISTEN        (0x3FFF2014UL)
+#define VI_EVENT_VXI_VME_SYSFAIL    (0x3FFF201DUL)
+#define VI_EVENT_VXI_VME_SYSRESET   (0x3FFF201EUL)
+#define VI_EVENT_VXI_SIGP           (0x3FFF2020UL)
+#define VI_EVENT_VXI_VME_INTR       (0xBFFF2021UL)
+#define VI_EVENT_PXI_INTR           (0x3FFF2022UL)
+#define VI_EVENT_TCPIP_CONNECT      (0x3FFF2036UL)
+#define VI_EVENT_USB_INTR           (0x3FFF2037UL)
+
+#define VI_ALL_ENABLED_EVENTS       (0x3FFF7FFFUL)
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS_EVENT_EN                   (0x3FFF0002L) /* 3FFF0002,  1073676290 */
+#define VI_SUCCESS_EVENT_DIS                  (0x3FFF0003L) /* 3FFF0003,  1073676291 */
+#define VI_SUCCESS_QUEUE_EMPTY                (0x3FFF0004L) /* 3FFF0004,  1073676292 */
+#define VI_SUCCESS_TERM_CHAR                  (0x3FFF0005L) /* 3FFF0005,  1073676293 */
+#define VI_SUCCESS_MAX_CNT                    (0x3FFF0006L) /* 3FFF0006,  1073676294 */
+#define VI_SUCCESS_DEV_NPRESENT               (0x3FFF007DL) /* 3FFF007D,  1073676413 */
+#define VI_SUCCESS_TRIG_MAPPED                (0x3FFF007EL) /* 3FFF007E,  1073676414 */
+#define VI_SUCCESS_QUEUE_NEMPTY               (0x3FFF0080L) /* 3FFF0080,  1073676416 */
+#define VI_SUCCESS_NCHAIN                     (0x3FFF0098L) /* 3FFF0098,  1073676440 */
+#define VI_SUCCESS_NESTED_SHARED              (0x3FFF0099L) /* 3FFF0099,  1073676441 */
+#define VI_SUCCESS_NESTED_EXCLUSIVE           (0x3FFF009AL) /* 3FFF009A,  1073676442 */
+#define VI_SUCCESS_SYNC                       (0x3FFF009BL) /* 3FFF009B,  1073676443 */
+
+#define VI_WARN_QUEUE_OVERFLOW                (0x3FFF000CL) /* 3FFF000C,  1073676300 */
+#define VI_WARN_CONFIG_NLOADED                (0x3FFF0077L) /* 3FFF0077,  1073676407 */
+#define VI_WARN_NULL_OBJECT                   (0x3FFF0082L) /* 3FFF0082,  1073676418 */
+#define VI_WARN_NSUP_ATTR_STATE               (0x3FFF0084L) /* 3FFF0084,  1073676420 */
+#define VI_WARN_UNKNOWN_STATUS                (0x3FFF0085L) /* 3FFF0085,  1073676421 */
+#define VI_WARN_NSUP_BUF                      (0x3FFF0088L) /* 3FFF0088,  1073676424 */
+#define VI_WARN_EXT_FUNC_NIMPL                (0x3FFF00A9L) /* 3FFF00A9,  1073676457 */
+
+#define VI_ERROR_SYSTEM_ERROR       (_VI_ERROR+0x3FFF0000L) /* BFFF0000, -1073807360 */
+#define VI_ERROR_INV_OBJECT         (_VI_ERROR+0x3FFF000EL) /* BFFF000E, -1073807346 */
+#define VI_ERROR_RSRC_LOCKED        (_VI_ERROR+0x3FFF000FL) /* BFFF000F, -1073807345 */
+#define VI_ERROR_INV_EXPR           (_VI_ERROR+0x3FFF0010L) /* BFFF0010, -1073807344 */
+#define VI_ERROR_RSRC_NFOUND        (_VI_ERROR+0x3FFF0011L) /* BFFF0011, -1073807343 */
+#define VI_ERROR_INV_RSRC_NAME      (_VI_ERROR+0x3FFF0012L) /* BFFF0012, -1073807342 */
+#define VI_ERROR_INV_ACC_MODE       (_VI_ERROR+0x3FFF0013L) /* BFFF0013, -1073807341 */
+#define VI_ERROR_TMO                (_VI_ERROR+0x3FFF0015L) /* BFFF0015, -1073807339 */
+#define VI_ERROR_CLOSING_FAILED     (_VI_ERROR+0x3FFF0016L) /* BFFF0016, -1073807338 */
+#define VI_ERROR_INV_DEGREE         (_VI_ERROR+0x3FFF001BL) /* BFFF001B, -1073807333 */
+#define VI_ERROR_INV_JOB_ID         (_VI_ERROR+0x3FFF001CL) /* BFFF001C, -1073807332 */
+#define VI_ERROR_NSUP_ATTR          (_VI_ERROR+0x3FFF001DL) /* BFFF001D, -1073807331 */
+#define VI_ERROR_NSUP_ATTR_STATE    (_VI_ERROR+0x3FFF001EL) /* BFFF001E, -1073807330 */
+#define VI_ERROR_ATTR_READONLY      (_VI_ERROR+0x3FFF001FL) /* BFFF001F, -1073807329 */
+#define VI_ERROR_INV_LOCK_TYPE      (_VI_ERROR+0x3FFF0020L) /* BFFF0020, -1073807328 */
+#define VI_ERROR_INV_ACCESS_KEY     (_VI_ERROR+0x3FFF0021L) /* BFFF0021, -1073807327 */
+#define VI_ERROR_INV_EVENT          (_VI_ERROR+0x3FFF0026L) /* BFFF0026, -1073807322 */
+#define VI_ERROR_INV_MECH           (_VI_ERROR+0x3FFF0027L) /* BFFF0027, -1073807321 */
+#define VI_ERROR_HNDLR_NINSTALLED   (_VI_ERROR+0x3FFF0028L) /* BFFF0028, -1073807320 */
+#define VI_ERROR_INV_HNDLR_REF      (_VI_ERROR+0x3FFF0029L) /* BFFF0029, -1073807319 */
+#define VI_ERROR_INV_CONTEXT        (_VI_ERROR+0x3FFF002AL) /* BFFF002A, -1073807318 */
+#define VI_ERROR_QUEUE_OVERFLOW     (_VI_ERROR+0x3FFF002DL) /* BFFF002D, -1073807315 */
+#define VI_ERROR_NENABLED           (_VI_ERROR+0x3FFF002FL) /* BFFF002F, -1073807313 */
+#define VI_ERROR_ABORT              (_VI_ERROR+0x3FFF0030L) /* BFFF0030, -1073807312 */
+#define VI_ERROR_RAW_WR_PROT_VIOL   (_VI_ERROR+0x3FFF0034L) /* BFFF0034, -1073807308 */
+#define VI_ERROR_RAW_RD_PROT_VIOL   (_VI_ERROR+0x3FFF0035L) /* BFFF0035, -1073807307 */
+#define VI_ERROR_OUTP_PROT_VIOL     (_VI_ERROR+0x3FFF0036L) /* BFFF0036, -1073807306 */
+#define VI_ERROR_INP_PROT_VIOL      (_VI_ERROR+0x3FFF0037L) /* BFFF0037, -1073807305 */
+#define VI_ERROR_BERR               (_VI_ERROR+0x3FFF0038L) /* BFFF0038, -1073807304 */
+#define VI_ERROR_IN_PROGRESS        (_VI_ERROR+0x3FFF0039L) /* BFFF0039, -1073807303 */
+#define VI_ERROR_INV_SETUP          (_VI_ERROR+0x3FFF003AL) /* BFFF003A, -1073807302 */
+#define VI_ERROR_QUEUE_ERROR        (_VI_ERROR+0x3FFF003BL) /* BFFF003B, -1073807301 */
+#define VI_ERROR_ALLOC              (_VI_ERROR+0x3FFF003CL) /* BFFF003C, -1073807300 */
+#define VI_ERROR_INV_MASK           (_VI_ERROR+0x3FFF003DL) /* BFFF003D, -1073807299 */
+#define VI_ERROR_IO                 (_VI_ERROR+0x3FFF003EL) /* BFFF003E, -1073807298 */
+#define VI_ERROR_INV_FMT            (_VI_ERROR+0x3FFF003FL) /* BFFF003F, -1073807297 */
+#define VI_ERROR_NSUP_FMT           (_VI_ERROR+0x3FFF0041L) /* BFFF0041, -1073807295 */
+#define VI_ERROR_LINE_IN_USE        (_VI_ERROR+0x3FFF0042L) /* BFFF0042, -1073807294 */
+#define VI_ERROR_NSUP_MODE          (_VI_ERROR+0x3FFF0046L) /* BFFF0046, -1073807290 */
+#define VI_ERROR_SRQ_NOCCURRED      (_VI_ERROR+0x3FFF004AL) /* BFFF004A, -1073807286 */
+#define VI_ERROR_INV_SPACE          (_VI_ERROR+0x3FFF004EL) /* BFFF004E, -1073807282 */
+#define VI_ERROR_INV_OFFSET         (_VI_ERROR+0x3FFF0051L) /* BFFF0051, -1073807279 */
+#define VI_ERROR_INV_WIDTH          (_VI_ERROR+0x3FFF0052L) /* BFFF0052, -1073807278 */
+#define VI_ERROR_NSUP_OFFSET        (_VI_ERROR+0x3FFF0054L) /* BFFF0054, -1073807276 */
+#define VI_ERROR_NSUP_VAR_WIDTH     (_VI_ERROR+0x3FFF0055L) /* BFFF0055, -1073807275 */
+#define VI_ERROR_WINDOW_NMAPPED     (_VI_ERROR+0x3FFF0057L) /* BFFF0057, -1073807273 */
+#define VI_ERROR_RESP_PENDING       (_VI_ERROR+0x3FFF0059L) /* BFFF0059, -1073807271 */
+#define VI_ERROR_NLISTENERS         (_VI_ERROR+0x3FFF005FL) /* BFFF005F, -1073807265 */
+#define VI_ERROR_NCIC               (_VI_ERROR+0x3FFF0060L) /* BFFF0060, -1073807264 */
+#define VI_ERROR_NSYS_CNTLR         (_VI_ERROR+0x3FFF0061L) /* BFFF0061, -1073807263 */
+#define VI_ERROR_NSUP_OPER          (_VI_ERROR+0x3FFF0067L) /* BFFF0067, -1073807257 */
+#define VI_ERROR_INTR_PENDING       (_VI_ERROR+0x3FFF0068L) /* BFFF0068, -1073807256 */
+#define VI_ERROR_ASRL_PARITY        (_VI_ERROR+0x3FFF006AL) /* BFFF006A, -1073807254 */
+#define VI_ERROR_ASRL_FRAMING       (_VI_ERROR+0x3FFF006BL) /* BFFF006B, -1073807253 */
+#define VI_ERROR_ASRL_OVERRUN       (_VI_ERROR+0x3FFF006CL) /* BFFF006C, -1073807252 */
+#define VI_ERROR_TRIG_NMAPPED       (_VI_ERROR+0x3FFF006EL) /* BFFF006E, -1073807250 */
+#define VI_ERROR_NSUP_ALIGN_OFFSET  (_VI_ERROR+0x3FFF0070L) /* BFFF0070, -1073807248 */
+#define VI_ERROR_USER_BUF           (_VI_ERROR+0x3FFF0071L) /* BFFF0071, -1073807247 */
+#define VI_ERROR_RSRC_BUSY          (_VI_ERROR+0x3FFF0072L) /* BFFF0072, -1073807246 */
+#define VI_ERROR_NSUP_WIDTH         (_VI_ERROR+0x3FFF0076L) /* BFFF0076, -1073807242 */
+#define VI_ERROR_INV_PARAMETER      (_VI_ERROR+0x3FFF0078L) /* BFFF0078, -1073807240 */
+#define VI_ERROR_INV_PROT           (_VI_ERROR+0x3FFF0079L) /* BFFF0079, -1073807239 */
+#define VI_ERROR_INV_SIZE           (_VI_ERROR+0x3FFF007BL) /* BFFF007B, -1073807237 */
+#define VI_ERROR_WINDOW_MAPPED      (_VI_ERROR+0x3FFF0080L) /* BFFF0080, -1073807232 */
+#define VI_ERROR_NIMPL_OPER         (_VI_ERROR+0x3FFF0081L) /* BFFF0081, -1073807231 */
+#define VI_ERROR_INV_LENGTH         (_VI_ERROR+0x3FFF0083L) /* BFFF0083, -1073807229 */
+#define VI_ERROR_INV_MODE           (_VI_ERROR+0x3FFF0091L) /* BFFF0091, -1073807215 */
+#define VI_ERROR_SESN_NLOCKED       (_VI_ERROR+0x3FFF009CL) /* BFFF009C, -1073807204 */
+#define VI_ERROR_MEM_NSHARED        (_VI_ERROR+0x3FFF009DL) /* BFFF009D, -1073807203 */
+#define VI_ERROR_LIBRARY_NFOUND     (_VI_ERROR+0x3FFF009EL) /* BFFF009E, -1073807202 */
+#define VI_ERROR_NSUP_INTR          (_VI_ERROR+0x3FFF009FL) /* BFFF009F, -1073807201 */
+#define VI_ERROR_INV_LINE           (_VI_ERROR+0x3FFF00A0L) /* BFFF00A0, -1073807200 */
+#define VI_ERROR_FILE_ACCESS        (_VI_ERROR+0x3FFF00A1L) /* BFFF00A1, -1073807199 */
+#define VI_ERROR_FILE_IO            (_VI_ERROR+0x3FFF00A2L) /* BFFF00A2, -1073807198 */
+#define VI_ERROR_NSUP_LINE          (_VI_ERROR+0x3FFF00A3L) /* BFFF00A3, -1073807197 */
+#define VI_ERROR_NSUP_MECH          (_VI_ERROR+0x3FFF00A4L) /* BFFF00A4, -1073807196 */
+#define VI_ERROR_INTF_NUM_NCONFIG   (_VI_ERROR+0x3FFF00A5L) /* BFFF00A5, -1073807195 */
+#define VI_ERROR_CONN_LOST          (_VI_ERROR+0x3FFF00A6L) /* BFFF00A6, -1073807194 */
+#define VI_ERROR_MACHINE_NAVAIL     (_VI_ERROR+0x3FFF00A7L) /* BFFF00A7, -1073807193 */
+#define VI_ERROR_NPERMISSION        (_VI_ERROR+0x3FFF00A8L) /* BFFF00A8, -1073807192 */
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_VERSION_MAJOR(ver)       ((((ViVersion)ver) & 0xFFF00000UL) >> 20)
+#define VI_VERSION_MINOR(ver)       ((((ViVersion)ver) & 0x000FFF00UL) >>  8)
+#define VI_VERSION_SUBMINOR(ver)    ((((ViVersion)ver) & 0x000000FFUL)      )
+
+#define VI_FIND_BUFLEN              (256)
+
+#define VI_INTF_GPIB                (1)
+#define VI_INTF_VXI                 (2)
+#define VI_INTF_GPIB_VXI            (3)
+#define VI_INTF_ASRL                (4)
+#define VI_INTF_PXI                 (5)
+#define VI_INTF_TCPIP               (6)
+#define VI_INTF_USB                 (7)
+
+#define VI_PROT_NORMAL              (1)
+#define VI_PROT_FDC                 (2)
+#define VI_PROT_HS488               (3)
+#define VI_PROT_4882_STRS           (4)
+#define VI_PROT_USBTMC_VENDOR       (5)
+
+#define VI_FDC_NORMAL               (1)
+#define VI_FDC_STREAM               (2)
+
+#define VI_LOCAL_SPACE              (0)
+#define VI_A16_SPACE                (1)
+#define VI_A24_SPACE                (2)
+#define VI_A32_SPACE                (3)
+#define VI_A64_SPACE                (4)
+#define VI_PXI_ALLOC_SPACE          (9)
+#define VI_PXI_CFG_SPACE            (10)
+#define VI_PXI_BAR0_SPACE           (11)
+#define VI_PXI_BAR1_SPACE           (12)
+#define VI_PXI_BAR2_SPACE           (13)
+#define VI_PXI_BAR3_SPACE           (14)
+#define VI_PXI_BAR4_SPACE           (15)
+#define VI_PXI_BAR5_SPACE           (16)
+#define VI_OPAQUE_SPACE             (0xFFFF)
+
+#define VI_UNKNOWN_LA               (-1)
+#define VI_UNKNOWN_SLOT             (-1)
+#define VI_UNKNOWN_LEVEL            (-1)
+#define VI_UNKNOWN_CHASSIS          (-1)
+
+#define VI_QUEUE                    (1)
+#define VI_HNDLR                    (2)
+#define VI_SUSPEND_HNDLR            (4)
+#define VI_ALL_MECH                 (0xFFFF)
+
+#define VI_ANY_HNDLR                (0)
+
+#define VI_TRIG_ALL                 (-2)
+#define VI_TRIG_SW                  (-1)
+#define VI_TRIG_TTL0                (0)
+#define VI_TRIG_TTL1                (1)
+#define VI_TRIG_TTL2                (2)
+#define VI_TRIG_TTL3                (3)
+#define VI_TRIG_TTL4                (4)
+#define VI_TRIG_TTL5                (5)
+#define VI_TRIG_TTL6                (6)
+#define VI_TRIG_TTL7                (7)
+#define VI_TRIG_ECL0                (8)
+#define VI_TRIG_ECL1                (9)
+#define VI_TRIG_PANEL_IN            (27)
+#define VI_TRIG_PANEL_OUT           (28)
+
+#define VI_TRIG_PROT_DEFAULT        (0)
+#define VI_TRIG_PROT_ON             (1)
+#define VI_TRIG_PROT_OFF            (2)
+#define VI_TRIG_PROT_SYNC           (5)
+#define VI_TRIG_PROT_RESERVE        (6)
+#define VI_TRIG_PROT_UNRESERVE      (7)
+
+#define VI_READ_BUF                 (1)
+#define VI_WRITE_BUF                (2)
+#define VI_READ_BUF_DISCARD         (4)
+#define VI_WRITE_BUF_DISCARD        (8)
+#define VI_IO_IN_BUF                (16)
+#define VI_IO_OUT_BUF               (32)
+#define VI_IO_IN_BUF_DISCARD        (64)
+#define VI_IO_OUT_BUF_DISCARD       (128)
+
+#define VI_FLUSH_ON_ACCESS          (1)
+#define VI_FLUSH_WHEN_FULL          (2)
+#define VI_FLUSH_DISABLE            (3)
+
+#define VI_NMAPPED                  (1)
+#define VI_USE_OPERS                (2)
+#define VI_DEREF_ADDR               (3)
+#define VI_DEREF_ADDR_BYTE_SWAP     (4)
+
+#define VI_TMO_IMMEDIATE            (0L)
+#define VI_TMO_INFINITE             (0xFFFFFFFFUL)
+
+#define VI_NO_LOCK                  (0)
+#define VI_EXCLUSIVE_LOCK           (1)
+#define VI_SHARED_LOCK              (2)
+#define VI_LOAD_CONFIG              (4)
+
+#define VI_NO_SEC_ADDR              (0xFFFF)
+
+#define VI_ASRL_PAR_NONE            (0)
+#define VI_ASRL_PAR_ODD             (1)
+#define VI_ASRL_PAR_EVEN            (2)
+#define VI_ASRL_PAR_MARK            (3)
+#define VI_ASRL_PAR_SPACE           (4)
+
+#define VI_ASRL_STOP_ONE            (10)
+#define VI_ASRL_STOP_ONE5           (15)
+#define VI_ASRL_STOP_TWO            (20)
+
+#define VI_ASRL_FLOW_NONE           (0)
+#define VI_ASRL_FLOW_XON_XOFF       (1)
+#define VI_ASRL_FLOW_RTS_CTS        (2)
+#define VI_ASRL_FLOW_DTR_DSR        (4)
+
+#define VI_ASRL_END_NONE            (0)
+#define VI_ASRL_END_LAST_BIT        (1)
+#define VI_ASRL_END_TERMCHAR        (2)
+#define VI_ASRL_END_BREAK           (3)
+
+#define VI_STATE_ASSERTED           (1)
+#define VI_STATE_UNASSERTED         (0)
+#define VI_STATE_UNKNOWN            (-1)
+
+#define VI_BIG_ENDIAN               (0)
+#define VI_LITTLE_ENDIAN            (1)
+
+#define VI_DATA_PRIV                (0)
+#define VI_DATA_NPRIV               (1)
+#define VI_PROG_PRIV                (2)
+#define VI_PROG_NPRIV               (3)
+#define VI_BLCK_PRIV                (4)
+#define VI_BLCK_NPRIV               (5)
+#define VI_D64_PRIV                 (6)
+#define VI_D64_NPRIV                (7)
+
+#define VI_WIDTH_8                  (1)
+#define VI_WIDTH_16                 (2)
+#define VI_WIDTH_32                 (4)
+#define VI_WIDTH_64                 (8)
+
+#define VI_GPIB_REN_DEASSERT        (0)
+#define VI_GPIB_REN_ASSERT          (1)
+#define VI_GPIB_REN_DEASSERT_GTL    (2)
+#define VI_GPIB_REN_ASSERT_ADDRESS  (3)
+#define VI_GPIB_REN_ASSERT_LLO      (4)
+#define VI_GPIB_REN_ASSERT_ADDRESS_LLO (5)
+#define VI_GPIB_REN_ADDRESS_GTL     (6)
+
+#define VI_GPIB_ATN_DEASSERT        (0)
+#define VI_GPIB_ATN_ASSERT          (1)
+#define VI_GPIB_ATN_DEASSERT_HANDSHAKE (2)
+#define VI_GPIB_ATN_ASSERT_IMMEDIATE (3)
+
+#define VI_GPIB_HS488_DISABLED      (0)
+#define VI_GPIB_HS488_NIMPL         (-1)
+
+#define VI_GPIB_UNADDRESSED         (0)
+#define VI_GPIB_TALKER              (1)
+#define VI_GPIB_LISTENER            (2)
+
+#define VI_VXI_CMD16                (0x0200)
+#define VI_VXI_CMD16_RESP16         (0x0202)
+#define VI_VXI_RESP16               (0x0002)
+#define VI_VXI_CMD32                (0x0400)
+#define VI_VXI_CMD32_RESP16         (0x0402)
+#define VI_VXI_CMD32_RESP32         (0x0404)
+#define VI_VXI_RESP32               (0x0004)
+
+#define VI_ASSERT_SIGNAL            (-1)
+#define VI_ASSERT_USE_ASSIGNED      (0)
+#define VI_ASSERT_IRQ1              (1)
+#define VI_ASSERT_IRQ2              (2)
+#define VI_ASSERT_IRQ3              (3)
+#define VI_ASSERT_IRQ4              (4)
+#define VI_ASSERT_IRQ5              (5)
+#define VI_ASSERT_IRQ6              (6)
+#define VI_ASSERT_IRQ7              (7)
+
+#define VI_UTIL_ASSERT_SYSRESET     (1)
+#define VI_UTIL_ASSERT_SYSFAIL      (2)
+#define VI_UTIL_DEASSERT_SYSFAIL    (3)
+
+#define VI_VXI_CLASS_MEMORY         (0)
+#define VI_VXI_CLASS_EXTENDED       (1)
+#define VI_VXI_CLASS_MESSAGE        (2)
+#define VI_VXI_CLASS_REGISTER       (3)
+#define VI_VXI_CLASS_OTHER          (4)
+
+#define VI_PXI_ADDR_NONE            (0)
+#define VI_PXI_ADDR_MEM             (1)
+#define VI_PXI_ADDR_IO              (2)
+#define VI_PXI_ADDR_CFG             (3)
+
+#define VI_TRIG_UNKNOWN             (-1)
+
+#define VI_PXI_LBUS_UNKNOWN         (-1)
+#define VI_PXI_LBUS_NONE            (0)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_0 (1000)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_1 (1001)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_2 (1002)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_3 (1003)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_4 (1004)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_5 (1005)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_6 (1006)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_7 (1007)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_8 (1008)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_9 (1009)
+#define VI_PXI_STAR_TRIG_CONTROLLER (1413)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define viGetDefaultRM(vi)          viOpenDefaultRM(vi)
+#define VI_ERROR_INV_SESSION        (VI_ERROR_INV_OBJECT)
+#define VI_INFINITE                 (VI_TMO_INFINITE)
+#define VI_NORMAL                   (VI_PROT_NORMAL)
+#define VI_FDC                      (VI_PROT_FDC)
+#define VI_HS488                    (VI_PROT_HS488)
+#define VI_ASRL488                  (VI_PROT_4882_STRS)
+#define VI_ASRL_IN_BUF              (VI_IO_IN_BUF)
+#define VI_ASRL_OUT_BUF             (VI_IO_OUT_BUF)
+#define VI_ASRL_IN_BUF_DISCARD      (VI_IO_IN_BUF_DISCARD)
+#define VI_ASRL_OUT_BUF_DISCARD     (VI_IO_OUT_BUF_DISCARD)
+
+/*- National Instruments ----------------------------------------------------*/
+
+#define VI_INTF_RIO                 (8)
+#define VI_INTF_FIREWIRE            (9) 
+
+#define VI_ATTR_SYNC_MXI_ALLOW_EN   (0x3FFF0161UL) /* ViBoolean, read/write */
+
+/* This is for VXI SERVANT resources */
+
+#define VI_EVENT_VXI_DEV_CMD        (0xBFFF200FUL)
+#define VI_ATTR_VXI_DEV_CMD_TYPE    (0x3FFF4037UL) /* ViInt16, read-only */
+#define VI_ATTR_VXI_DEV_CMD_VALUE   (0x3FFF4038UL) /* ViUInt32, read-only */
+
+#define VI_VXI_DEV_CMD_TYPE_16      (16)
+#define VI_VXI_DEV_CMD_TYPE_32      (32)
+
+ViStatus _VI_FUNC viVxiServantResponse(ViSession vi, ViInt16 mode, ViUInt32 resp);
+/* mode values include VI_VXI_RESP16, VI_VXI_RESP32, and the next 2 values */
+#define VI_VXI_RESP_NONE            (0)
+#define VI_VXI_RESP_PROT_ERROR      (-1)
+
+/* This allows extended Serial support on Win32 and on NI ENET Serial products */
+
+#define VI_ATTR_ASRL_DISCARD_NULL   (0x3FFF00B0UL)
+#define VI_ATTR_ASRL_CONNECTED      (0x3FFF01BBUL)
+#define VI_ATTR_ASRL_BREAK_STATE    (0x3FFF01BCUL)
+#define VI_ATTR_ASRL_BREAK_LEN      (0x3FFF01BDUL)
+#define VI_ATTR_ASRL_ALLOW_TRANSMIT (0x3FFF01BEUL)
+#define VI_ATTR_ASRL_WIRE_MODE      (0x3FFF01BFUL)
+
+#define VI_ASRL_WIRE_485_4          (0)
+#define VI_ASRL_WIRE_485_2_DTR_ECHO (1)
+#define VI_ASRL_WIRE_485_2_DTR_CTRL (2)
+#define VI_ASRL_WIRE_485_2_AUTO     (3)
+#define VI_ASRL_WIRE_232_DTE        (128)
+#define VI_ASRL_WIRE_232_DCE        (129)
+#define VI_ASRL_WIRE_232_AUTO       (130)
+
+#define VI_EVENT_ASRL_BREAK         (0x3FFF2023UL)
+#define VI_EVENT_ASRL_CTS           (0x3FFF2029UL)
+#define VI_EVENT_ASRL_DSR           (0x3FFF202AUL)
+#define VI_EVENT_ASRL_DCD           (0x3FFF202CUL)
+#define VI_EVENT_ASRL_RI            (0x3FFF202EUL)
+#define VI_EVENT_ASRL_CHAR          (0x3FFF2035UL)
+#define VI_EVENT_ASRL_TERMCHAR      (0x3FFF2024UL)
+
+/* This is for fast viPeek/viPoke macros */
+
+#if defined(NIVISA_PEEKPOKE)
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+#undef NIVISA_PEEKPOKE_SUPP
+#endif
+
+#if (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+/* This macro is supported for all Win32 compilers, including CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_CVI_) && !defined(_NI_mswin16_)
+/* This macro is supported for Borland and Microsoft compilers on Win16, but not CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif defined(_CVI_) && defined(_NI_sparc_)
+/* This macro is supported for Solaris 1 and 2, from CVI only. */
+#define NIVISA_PEEKPOKE_SUPP
+#else
+/* This macro is not supported on other platforms. */
+#endif
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+
+extern ViBoolean NI_viImplVISA1;
+ViStatus _VI_FUNC NI_viOpenDefaultRM (ViPSession vi);
+#define viOpenDefaultRM(vi) NI_viOpenDefaultRM(vi)
+
+#define viPeek8(vi,addr,val)                                                \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((ViPUInt8)(val)) = *((volatile ViUInt8 _VI_PTR)(addr)));     \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPeek8)((vi),(addr),(val));                                      \
+      }                                                                     \
+   }
+
+#define viPoke8(vi,addr,val)                                                \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((volatile ViUInt8 _VI_PTR)(addr)) = ((ViUInt8)(val)));       \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPoke8)((vi),(addr),(val));                                      \
+      }                                                                     \
+   }
+
+#define viPeek16(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((ViPUInt16)(val)) = *((volatile ViUInt16 _VI_PTR)(addr)));   \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPeek16)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#define viPoke16(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((volatile ViUInt16 _VI_PTR)(addr)) = ((ViUInt16)(val)));     \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPoke16)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#define viPeek32(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((ViPUInt32)(val)) = *((volatile ViUInt32 _VI_PTR)(addr)));   \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPeek32)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#define viPoke32(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((volatile ViUInt32 _VI_PTR)(addr)) = ((ViUInt32)(val)));     \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPoke32)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#endif
+
+#endif
+
+#if defined(NIVISA_PXI) || defined(PXISAVISA_PXI)
+
+#if 0
+/* The following 2 attributes were incorrectly implemented in earlier
+   versions of NI-VISA.  You should now query VI_ATTR_MANF_ID or
+   VI_ATTR_MODEL_CODE.  Those attributes contain sub-vendor information
+   when it exists.  To get both the actual primary and subvendor codes
+   from the device, you should call viIn16 using VI_PXI_CFG_SPACE. */
+#define VI_ATTR_PXI_SUB_MANF_ID     (0x3FFF0203UL)
+#define VI_ATTR_PXI_SUB_MODEL_CODE  (0x3FFF0204UL)
+#endif
+
+#define VI_ATTR_PXI_SRC_TRIG_BUS    (0x3FFF020DUL)
+#define VI_ATTR_PXI_DEST_TRIG_BUS   (0x3FFF020EUL)
+
+#define VI_ATTR_PXI_RECV_INTR_SEQ   (0x3FFF4240UL)
+#define VI_ATTR_PXI_RECV_INTR_DATA  (0x3FFF4241UL)
+
+#endif
+
+#if defined(NIVISA_USB)
+
+#define VI_ATTR_USB_BULK_OUT_PIPE   (0x3FFF01A2UL)
+#define VI_ATTR_USB_BULK_IN_PIPE    (0x3FFF01A3UL)
+#define VI_ATTR_USB_INTR_IN_PIPE    (0x3FFF01A4UL)
+#define VI_ATTR_USB_CLASS           (0x3FFF01A5UL)
+#define VI_ATTR_USB_SUBCLASS        (0x3FFF01A6UL)
+#define VI_ATTR_USB_ALT_SETTING     (0x3FFF01A8UL)
+#define VI_ATTR_USB_END_IN          (0x3FFF01A9UL)
+#define VI_ATTR_USB_NUM_INTFCS      (0x3FFF01AAUL)
+#define VI_ATTR_USB_NUM_PIPES       (0x3FFF01ABUL)
+#define VI_ATTR_USB_BULK_OUT_STATUS (0x3FFF01ACUL)
+#define VI_ATTR_USB_BULK_IN_STATUS  (0x3FFF01ADUL)
+#define VI_ATTR_USB_INTR_IN_STATUS  (0x3FFF01AEUL)
+#define VI_ATTR_USB_CTRL_PIPE       (0x3FFF01B0UL)
+
+#define VI_USB_PIPE_STATE_UNKNOWN   (-1)
+#define VI_USB_PIPE_READY           (0)
+#define VI_USB_PIPE_STALLED         (1)
+
+#define VI_USB_END_NONE             (0)
+#define VI_USB_END_SHORT            (4)
+#define VI_USB_END_SHORT_OR_COUNT   (5)
+
+#endif
+
+#define VI_ATTR_FIREWIRE_DEST_UPPER_OFFSET (0x3FFF01F0UL)
+#define VI_ATTR_FIREWIRE_SRC_UPPER_OFFSET  (0x3FFF01F1UL)
+#define VI_ATTR_FIREWIRE_WIN_UPPER_OFFSET  (0x3FFF01F2UL)
+#define VI_ATTR_FIREWIRE_VENDOR_ID         (0x3FFF01F3UL)
+#define VI_ATTR_FIREWIRE_LOWER_CHIP_ID     (0x3FFF01F4UL)
+#define VI_ATTR_FIREWIRE_UPPER_CHIP_ID     (0x3FFF01F5UL)
+
+#define VI_FIREWIRE_DFLT_SPACE           (5)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+   }
+#endif
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
diff --git a/aos/externals/allwpilib/hal/lib/Athena/visa/visatype.h b/aos/externals/allwpilib/hal/lib/Athena/visa/visatype.h
new file mode 100644
index 0000000..ef089dd
--- /dev/null
+++ b/aos/externals/allwpilib/hal/lib/Athena/visa/visatype.h
@@ -0,0 +1,201 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc.                                        */
+/*                                                                           */
+/* Do not modify the contents of this file.                                  */
+/*---------------------------------------------------------------------------*/
+/*                                                                           */
+/* Title   : VISATYPE.H                                                      */
+/* Date    : 04-14-2006                                                      */
+/* Purpose : Fundamental VISA data types and macro definitions               */
+/*                                                                           */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISATYPE_HEADER__
+#define __VISATYPE_HEADER__
+
+#if defined(_WIN64)
+#define _VI_FAR
+#define _VI_FUNC            __fastcall
+#define _VI_FUNCC           __fastcall
+#define _VI_FUNCH           __fastcall
+#define _VI_SIGNED          signed
+#elif (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+#define _VI_FAR
+#define _VI_FUNC            __stdcall
+#define _VI_FUNCC           __cdecl
+#define _VI_FUNCH           __stdcall
+#define _VI_SIGNED          signed
+#elif defined(_CVI_) && defined(_NI_i386_)
+#define _VI_FAR
+#define _VI_FUNC            _pascal
+#define _VI_FUNCC
+#define _VI_FUNCH           _pascal
+#define _VI_SIGNED          signed
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_NI_mswin16_)
+#define _VI_FAR             _far
+#define _VI_FUNC            _far _pascal _export
+#define _VI_FUNCC           _far _cdecl  _export
+#define _VI_FUNCH           _far _pascal
+#define _VI_SIGNED          signed
+#elif (defined(hpux) || defined(__hpux)) && (defined(__cplusplus) || defined(__cplusplus__))
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED
+#else
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED          signed
+#endif
+
+#define _VI_ERROR           (-2147483647L-1)  /* 0x80000000 */
+#define _VI_PTR             _VI_FAR *
+
+/*- VISA Types --------------------------------------------------------------*/
+
+#ifndef _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64) || ((defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_))
+#if (defined(_MSC_VER) && (_MSC_VER >= 1200)) || (defined(_CVI_) && (_CVI_ >= 700)) || (defined(__BORLANDC__) && (__BORLANDC__ >= 0x0520))
+typedef unsigned   __int64  ViUInt64;
+typedef _VI_SIGNED __int64  ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#endif
+#elif defined(__GNUC__) && (__GNUC__ >= 3)
+#include <limits.h>
+#include <sys/types.h>
+typedef u_int64_t           ViUInt64;
+typedef int64_t             ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#else
+/* This platform does not support 64-bit types */
+#endif
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64    _VI_PTR ViPUInt64;
+typedef ViUInt64    _VI_PTR ViAUInt64;
+typedef ViInt64     _VI_PTR ViPInt64;
+typedef ViInt64     _VI_PTR ViAInt64;
+#endif
+
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+typedef unsigned int        ViUInt32;
+typedef _VI_SIGNED int      ViInt32;
+#else
+typedef unsigned long       ViUInt32;
+typedef _VI_SIGNED long     ViInt32;
+#endif
+
+typedef ViUInt32    _VI_PTR ViPUInt32;
+typedef ViUInt32    _VI_PTR ViAUInt32;
+typedef ViInt32     _VI_PTR ViPInt32;
+typedef ViInt32     _VI_PTR ViAInt32;
+
+typedef unsigned short      ViUInt16;
+typedef ViUInt16    _VI_PTR ViPUInt16;
+typedef ViUInt16    _VI_PTR ViAUInt16;
+
+typedef _VI_SIGNED short    ViInt16;
+typedef ViInt16     _VI_PTR ViPInt16;
+typedef ViInt16     _VI_PTR ViAInt16;
+
+typedef unsigned char       ViUInt8;
+typedef ViUInt8     _VI_PTR ViPUInt8;
+typedef ViUInt8     _VI_PTR ViAUInt8;
+
+typedef _VI_SIGNED char     ViInt8;
+typedef ViInt8      _VI_PTR ViPInt8;
+typedef ViInt8      _VI_PTR ViAInt8;
+
+typedef char                ViChar;
+typedef ViChar      _VI_PTR ViPChar;
+typedef ViChar      _VI_PTR ViAChar;
+
+typedef unsigned char       ViByte;
+typedef ViByte      _VI_PTR ViPByte;
+typedef ViByte      _VI_PTR ViAByte;
+
+typedef void        _VI_PTR ViAddr;
+typedef ViAddr      _VI_PTR ViPAddr;
+typedef ViAddr      _VI_PTR ViAAddr;
+
+typedef float               ViReal32;
+typedef ViReal32    _VI_PTR ViPReal32;
+typedef ViReal32    _VI_PTR ViAReal32;
+
+typedef double              ViReal64;
+typedef ViReal64    _VI_PTR ViPReal64;
+typedef ViReal64    _VI_PTR ViAReal64;
+
+typedef ViPByte             ViBuf;
+typedef ViPByte             ViPBuf;
+typedef ViPByte     _VI_PTR ViABuf;
+
+typedef ViPChar             ViString;
+typedef ViPChar             ViPString;
+typedef ViPChar     _VI_PTR ViAString;
+
+typedef ViString            ViRsrc;
+typedef ViString            ViPRsrc;
+typedef ViString    _VI_PTR ViARsrc;
+
+typedef ViUInt16            ViBoolean;
+typedef ViBoolean   _VI_PTR ViPBoolean;
+typedef ViBoolean   _VI_PTR ViABoolean;
+
+typedef ViInt32             ViStatus;
+typedef ViStatus    _VI_PTR ViPStatus;
+typedef ViStatus    _VI_PTR ViAStatus;
+
+typedef ViUInt32            ViVersion;
+typedef ViVersion   _VI_PTR ViPVersion;
+typedef ViVersion   _VI_PTR ViAVersion;
+
+typedef ViUInt32            ViObject;
+typedef ViObject    _VI_PTR ViPObject;
+typedef ViObject    _VI_PTR ViAObject;
+
+typedef ViObject            ViSession;
+typedef ViSession   _VI_PTR ViPSession;
+typedef ViSession   _VI_PTR ViASession;
+
+typedef ViUInt32             ViAttr;
+
+#ifndef _VI_CONST_STRING_DEFINED
+typedef const ViChar * ViConstString;
+#define _VI_CONST_STRING_DEFINED
+#endif  
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS          (0L)
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_NULL             (0)
+
+#define VI_TRUE             (1)
+#define VI_FALSE            (0)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define VISAFN              _VI_FUNC
+#define ViPtr               _VI_PTR
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
+
diff --git a/aos/externals/allwpilib/ni-libraries/genlinks b/aos/externals/allwpilib/ni-libraries/genlinks
new file mode 100755
index 0000000..6931dbc
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/genlinks
@@ -0,0 +1,11 @@
+#!/bin/bash
+
+# this file should generate symlinks (POSIX, TODO) or LD scripts (POSIX or windows) to enable standard version linking
+
+for lib in lib*.so.*; do
+	libout="${lib%.*}"
+	rm -rf $libout
+	echo "OUTPUT_FORMAT(elf32-littlearm)" > $libout
+	echo "GROUP ( $lib )" >> $libout
+	echo "Generated LD link $libout -> $lib"
+done
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so
new file mode 100644
index 0000000..a24218e
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libFRC_NetworkCommunication.so.1 )
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1 b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1
new file mode 100644
index 0000000..e1ec38a
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libFRC_NetworkCommunication.so.1.5 )
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1.5 b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1.5
new file mode 100644
index 0000000..845c759
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1.5
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libFRC_NetworkCommunication.so.1.5.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1.5.0 b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1.5.0
new file mode 100755
index 0000000..503911b
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunication.so.1.5.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so
new file mode 100644
index 0000000..c7c2653
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libFRC_NetworkCommunicationLV.so.1 )
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1 b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1
new file mode 100644
index 0000000..1254b6d
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libFRC_NetworkCommunicationLV.so.1.5 )
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1.5 b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1.5
new file mode 100644
index 0000000..30022db
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1.5
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libFRC_NetworkCommunicationLV.so.1.5.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1.5.0 b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1.5.0
new file mode 100755
index 0000000..f54d997
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libFRC_NetworkCommunicationLV.so.1.5.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libGCBase_gcc-4.4-arm_v2_3.so b/aos/externals/allwpilib/ni-libraries/libGCBase_gcc-4.4-arm_v2_3.so
new file mode 100755
index 0000000..3bcda8d
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libGCBase_gcc-4.4-arm_v2_3.so
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libGenApi_gcc-4.4-arm_v2_3.so b/aos/externals/allwpilib/ni-libraries/libGenApi_gcc-4.4-arm_v2_3.so
new file mode 100755
index 0000000..7e6a6df
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libGenApi_gcc-4.4-arm_v2_3.so
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libLog_gcc-4.4-arm_v2_3.so b/aos/externals/allwpilib/ni-libraries/libLog_gcc-4.4-arm_v2_3.so
new file mode 100755
index 0000000..6e8719b
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libLog_gcc-4.4-arm_v2_3.so
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libMathParser_gcc-4.4-arm_v2_3.so b/aos/externals/allwpilib/ni-libraries/libMathParser_gcc-4.4-arm_v2_3.so
new file mode 100755
index 0000000..e4d1279
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libMathParser_gcc-4.4-arm_v2_3.so
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpga.so b/aos/externals/allwpilib/ni-libraries/libNiFpga.so
new file mode 100644
index 0000000..c506470
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpga.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiFpga.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14 b/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14
new file mode 100644
index 0000000..3b66e3e
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiFpga.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14.0 b/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14.0
new file mode 100644
index 0000000..aa4e287
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiFpga.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14.0.0
new file mode 100755
index 0000000..1f3a237
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpga.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so
new file mode 100644
index 0000000..88b5a24
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiFpgaLv.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14 b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14
new file mode 100644
index 0000000..3adae09
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiFpgaLv.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14.0 b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14.0
new file mode 100644
index 0000000..db0b28c
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiFpgaLv.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14.0.0
new file mode 100755
index 0000000..3efee8f
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiFpgaLv.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so
new file mode 100644
index 0000000..98b55b1
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiRioSrv.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14 b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14
new file mode 100644
index 0000000..ef98d56
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiRioSrv.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14.0 b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14.0
new file mode 100644
index 0000000..7ee207d
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libNiRioSrv.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14.0.0
new file mode 100755
index 0000000..4917af8
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libNiRioSrv.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so
new file mode 100644
index 0000000..b44dc03
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libRoboRIO_FRC_ChipObject.so.1 )
diff --git a/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1 b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1
new file mode 100644
index 0000000..fff4f97
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libRoboRIO_FRC_ChipObject.so.1.2 )
diff --git a/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1.2 b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1.2
new file mode 100644
index 0000000..467fa0e
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1.2
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libRoboRIO_FRC_ChipObject.so.1.2.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1.2.0 b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1.2.0
new file mode 100755
index 0000000..316bdce
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libRoboRIO_FRC_ChipObject.so.1.2.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libi2c.so b/aos/externals/allwpilib/ni-libraries/libi2c.so
new file mode 100644
index 0000000..673ca37
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libi2c.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libi2c.so.1 )
diff --git a/aos/externals/allwpilib/ni-libraries/libi2c.so.1 b/aos/externals/allwpilib/ni-libraries/libi2c.so.1
new file mode 100644
index 0000000..e10758b
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libi2c.so.1
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libi2c.so.1.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libi2c.so.1.0 b/aos/externals/allwpilib/ni-libraries/libi2c.so.1.0
new file mode 100644
index 0000000..68c5890
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libi2c.so.1.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libi2c.so.1.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libi2c.so.1.0.0 b/aos/externals/allwpilib/ni-libraries/libi2c.so.1.0.0
new file mode 100755
index 0000000..34740ca
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libi2c.so.1.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/liblog4cpp_gcc-4.4-arm_v2_3.so b/aos/externals/allwpilib/ni-libraries/liblog4cpp_gcc-4.4-arm_v2_3.so
new file mode 100755
index 0000000..46f6780
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/liblog4cpp_gcc-4.4-arm_v2_3.so
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libni_emb.so b/aos/externals/allwpilib/ni-libraries/libni_emb.so
new file mode 100644
index 0000000..93678d5
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_emb.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libni_emb.so.7 )
diff --git a/aos/externals/allwpilib/ni-libraries/libni_emb.so.7 b/aos/externals/allwpilib/ni-libraries/libni_emb.so.7
new file mode 100644
index 0000000..aa703b7
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_emb.so.7
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libni_emb.so.7.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libni_emb.so.7.0 b/aos/externals/allwpilib/ni-libraries/libni_emb.so.7.0
new file mode 100644
index 0000000..da52c36
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_emb.so.7.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libni_emb.so.7.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libni_emb.so.7.0.0 b/aos/externals/allwpilib/ni-libraries/libni_emb.so.7.0.0
new file mode 100755
index 0000000..363b852
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_emb.so.7.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libni_rtlog.so b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so
new file mode 100644
index 0000000..3045681
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libni_rtlog.so.2 )
diff --git a/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2 b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2
new file mode 100644
index 0000000..f7fc193
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libni_rtlog.so.2.3 )
diff --git a/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2.3 b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2.3
new file mode 100644
index 0000000..f673867
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2.3
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libni_rtlog.so.2.3.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2.3.0 b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2.3.0
new file mode 100755
index 0000000..2d6d6ae
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libni_rtlog.so.2.3.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libniimaqdx.so b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so
new file mode 100644
index 0000000..ed97ce7
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libniimaqdx.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14 b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14
new file mode 100644
index 0000000..6edea92
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libniimaqdx.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14.0 b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14.0
new file mode 100644
index 0000000..12b642e
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libniimaqdx.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14.0.0
new file mode 100755
index 0000000..27cd188
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libniimaqdx.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so
new file mode 100644
index 0000000..eeb8133
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnirio_emb_can.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14 b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14
new file mode 100644
index 0000000..c0548d7
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnirio_emb_can.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14.0 b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14.0
new file mode 100644
index 0000000..b4e836f
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnirio_emb_can.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14.0.0
new file mode 100755
index 0000000..3e04ea8
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnirio_emb_can.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libnivision.so b/aos/externals/allwpilib/ni-libraries/libnivision.so
new file mode 100644
index 0000000..67c0c57
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivision.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnivision.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnivision.so.14 b/aos/externals/allwpilib/ni-libraries/libnivision.so.14
new file mode 100644
index 0000000..4306944
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivision.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnivision.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnivision.so.14.0 b/aos/externals/allwpilib/ni-libraries/libnivision.so.14.0
new file mode 100644
index 0000000..3a4d263
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivision.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnivision.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnivision.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libnivision.so.14.0.0
new file mode 100755
index 0000000..a0a4810
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivision.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libnivissvc.so b/aos/externals/allwpilib/ni-libraries/libnivissvc.so
new file mode 100644
index 0000000..e0bbd48
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivissvc.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnivissvc.so.14 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14 b/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14
new file mode 100644
index 0000000..205cc35
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnivissvc.so.14.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14.0 b/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14.0
new file mode 100644
index 0000000..26ffd42
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libnivissvc.so.14.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14.0.0 b/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14.0.0
new file mode 100755
index 0000000..480578d
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libnivissvc.so.14.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libspi.so b/aos/externals/allwpilib/ni-libraries/libspi.so
new file mode 100644
index 0000000..e77606f
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libspi.so
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libspi.so.1 )
diff --git a/aos/externals/allwpilib/ni-libraries/libspi.so.1 b/aos/externals/allwpilib/ni-libraries/libspi.so.1
new file mode 100644
index 0000000..5aa0632
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libspi.so.1
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libspi.so.1.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libspi.so.1.0 b/aos/externals/allwpilib/ni-libraries/libspi.so.1.0
new file mode 100644
index 0000000..9f016df
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libspi.so.1.0
@@ -0,0 +1,2 @@
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( libspi.so.1.0.0 )
diff --git a/aos/externals/allwpilib/ni-libraries/libspi.so.1.0.0 b/aos/externals/allwpilib/ni-libraries/libspi.so.1.0.0
new file mode 100755
index 0000000..5f69f31
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libspi.so.1.0.0
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libvisa.so b/aos/externals/allwpilib/ni-libraries/libvisa.so
new file mode 100755
index 0000000..4ca711c
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libvisa.so
Binary files differ
diff --git a/aos/externals/allwpilib/ni-libraries/libwpi.so b/aos/externals/allwpilib/ni-libraries/libwpi.so
new file mode 100644
index 0000000..429ff80
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libwpi.so
@@ -0,0 +1,3 @@
+/* GNU ld script */
+OUTPUT_FORMAT(elf32-littlearm)
+INPUT ( -lwpi_2015 )
diff --git a/aos/externals/allwpilib/ni-libraries/libwpi_2015.so b/aos/externals/allwpilib/ni-libraries/libwpi_2015.so
new file mode 100644
index 0000000..3589af2
--- /dev/null
+++ b/aos/externals/allwpilib/ni-libraries/libwpi_2015.so
@@ -0,0 +1,3 @@
+/* GNU ld script */
+OUTPUT_FORMAT(elf32-littlearm)
+GROUP ( AS_NEEDED ( -lwpilib_nonshared -lHALAthena -lNetworkTables -lFRC_NetworkCommunication -li2c -lni_emb -lNiFpgaLv -lNiFpga -lnirio_emb_can -lNiRioSrv -lni_rtlog -lRoboRIO_FRC_ChipObject -lspi -lvisa -ldl -lpthread -lrt -lGCBase_gcc-4.4-arm_v2_3 -lGenApi_gcc-4.4-arm_v2_3 -lLog_gcc-4.4-arm_v2_3 -lMathParser_gcc-4.4-arm_v2_3 -llog4cpp_gcc-4.4-arm_v2_3 -lniimaqdx -lnivision -lnivissvc ) )
diff --git a/aos/externals/allwpilib/sync.sh b/aos/externals/allwpilib/sync.sh
new file mode 100755
index 0000000..8e05233
--- /dev/null
+++ b/aos/externals/allwpilib/sync.sh
@@ -0,0 +1,20 @@
+#!/bin/bash -e
+
+# This script copies the correct directories over from an allwpilib git
+# repository (which needs to have a working tree).
+# THIS WILL ERASE ANY LOCAL CHANGES TO THE WPILIB SOURCES!
+
+# Takes 1 argument: the folder to copy from.
+
+cd $(dirname $0)
+
+SOURCE=$1
+DIRS="wpilibc hal ni-libraries"
+
+[ -n "${SOURCE}" ] || ( echo "Need a directory to sync from!" ; exit 1 )
+[ -d "${SOURCE}" ] || ( echo "${SOURCE} is not a directory. Aborting!" ; exit 1 )
+
+for dir in ${DIRS}; do
+	[ -d ${dir} ] && rm -r ${dir}
+	cp -r ${SOURCE}/${dir} ./
+done
diff --git a/aos/externals/allwpilib/wpilibc/CMakeLists.txt b/aos/externals/allwpilib/wpilibc/CMakeLists.txt
new file mode 100644
index 0000000..de4a7ef
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/CMakeLists.txt
@@ -0,0 +1,5 @@
+cmake_minimum_required(VERSION 2.8)
+project(WPILibC)
+
+add_subdirectory(wpilibC++)
+add_subdirectory(wpilibC++Devices)
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/CMakeLists.txt b/aos/externals/allwpilib/wpilibc/wpilibC++/CMakeLists.txt
new file mode 100644
index 0000000..4af3fc9
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/CMakeLists.txt
@@ -0,0 +1,5 @@
+cmake_minimum_required(VERSION 2.8)
+project(WPILibC++)
+
+INSTALL(DIRECTORY include DESTINATION ${CMAKE_INSTALL_PREFIX} COMPONENT headers)
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Base.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Base.h
new file mode 100644
index 0000000..74073e8
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Base.h
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+// A macro to disallow the copy constructor and operator= functions
+// This should be used in the private: declarations for a class
+#define DISALLOW_COPY_AND_ASSIGN(TypeName) \
+  TypeName(const TypeName&) = delete;      \
+  void operator=(const TypeName&) = delete
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Controller.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Controller.h
new file mode 100644
index 0000000..99eba88
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Controller.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 <stdint.h>
+#include <cmath>
+#include <pthread.h>
+#include <semaphore.h>
+
+/**
+ * Interface for Controllers
+ * Common interface for controllers. Controllers run control loops, the most common
+ * are PID controllers and their variants, but this includes anything that is controlling
+ * an actuator in a separate thread.
+ */
+class Controller
+{
+public:
+	virtual ~Controller() {};
+	
+	/**
+	 * Allows the control loop to run
+	 */
+	virtual void Enable() = 0;
+	
+	/** 
+	 * Stops the control loop from running until explicitly re-enabled by calling enable()
+	 */
+	virtual void Disable() = 0;
+};
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Error.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Error.h
new file mode 100644
index 0000000..4fbe0f0
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Error.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+#include <stdint.h>
+
+//  Forward declarations
+class ErrorBase;
+
+/**
+ * Error object represents a library error.
+ */
+class Error
+{
+public:
+	typedef int32_t Code;
+
+	Error();
+	~Error();
+	void Clone(Error &error);
+	Code GetCode() const;
+	const char *GetMessage() const;
+	const char *GetFilename() const;
+	const char *GetFunction() const;
+	uint32_t GetLineNumber() const;
+	const ErrorBase* GetOriginatingObject() const;
+	double GetTimestamp() const;
+	void Clear();
+	void Set(Code code, const char* contextMessage, const char* filename, const char *function,
+			uint32_t lineNumber, const ErrorBase* originatingObject);
+	static void EnableSuspendOnError(bool enable)
+	{
+		m_suspendOnErrorEnabled = enable;
+	}
+
+private:
+	void Report();
+
+	Code m_code;
+	std::string m_message;
+	std::string m_filename;
+	std::string m_function;
+	uint32_t m_lineNumber;
+	const ErrorBase* m_originatingObject;
+	double m_timestamp;
+
+	static bool m_suspendOnErrorEnabled;
+    DISALLOW_COPY_AND_ASSIGN(Error);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/ErrorBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/ErrorBase.h
new file mode 100644
index 0000000..94e9164
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/ErrorBase.h
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "Base.h"
+#include "Error.h"
+#include "HAL/cpp/Synchronized.hpp"
+
+#define wpi_setErrnoErrorWithContext(context)   (this->SetErrnoError((context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setErrnoError()   (wpi_setErrnoErrorWithContext(""))
+#define wpi_setImaqErrorWithContext(code, context)   (this->SetImaqError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setErrorWithContext(code, context)   (this->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setError(code)   (wpi_setErrorWithContext(code, ""))
+#define wpi_setStaticErrorWithContext(object, code, context)   (object->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setStaticError(object, code)   (wpi_setStaticErrorWithContext(object, code, ""))
+#define wpi_setGlobalErrorWithContext(code, context)   (ErrorBase::SetGlobalError((code), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setGlobalError(code)   (wpi_setGlobalErrorWithContext(code, ""))
+#define wpi_setWPIErrorWithContext(error, context)   (this->SetWPIError((wpi_error_s_##error), (wpi_error_value_##error), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setWPIError(error)   (wpi_setWPIErrorWithContext(error, ""))
+#define wpi_setStaticWPIErrorWithContext(object, error, context)   (object->SetWPIError((wpi_error_s_##error), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setStaticWPIError(object, error)   (wpi_setStaticWPIErrorWithContext(object, error, ""))
+#define wpi_setGlobalWPIErrorWithContext(error, context)   (ErrorBase::SetGlobalWPIError((wpi_error_s_##error), (context), __FILE__, __FUNCTION__, __LINE__))
+#define wpi_setGlobalWPIError(error)   (wpi_setGlobalWPIErrorWithContext(error, ""))
+
+/**
+ * Base class for most objects.
+ * ErrorBase is the base class for most objects since it holds the generated error
+ * for that object. In addition, there is a single instance of a global error object
+ */
+class ErrorBase
+{
+//TODO: Consider initializing instance variables and cleanup in destructor
+public:
+	virtual ~ErrorBase();
+	virtual Error& GetError();
+	virtual const Error& GetError() const;
+	virtual void SetErrnoError(const char *contextMessage, const char* filename,
+			const char* function, uint32_t lineNumber) const;
+	virtual void SetImaqError(int success, const char *contextMessage, const char* filename,
+			const char* function, uint32_t lineNumber) const;
+	virtual void SetError(Error::Code code, const char *contextMessage, const char* filename,
+			const char* function, uint32_t lineNumber) const;
+	virtual void SetWPIError(const char *errorMessage, Error::Code code, const char *contextMessage,
+			const char* filename, const char* function, uint32_t lineNumber) const;
+	virtual void CloneError(ErrorBase *rhs) const;
+	virtual void ClearError() const;
+	virtual bool StatusIsFatal() const;
+	static void SetGlobalError(Error::Code code, const char *contextMessage, const char* filename,
+			const char* function, uint32_t lineNumber);
+	static void SetGlobalWPIError(const char *errorMessage, const char *contextMessage,
+			const char* filename, const char* function, uint32_t lineNumber);
+	static Error& GetGlobalError();
+protected:
+	mutable Error m_error;
+	// TODO: Replace globalError with a global list of all errors.
+	static Mutex _globalErrorMutex;
+	static Error _globalError;
+	ErrorBase();
+private:
+	DISALLOW_COPY_AND_ASSIGN(ErrorBase);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/GenericHID.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/GenericHID.h
new file mode 100644
index 0000000..cb8dfde
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/GenericHID.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* 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>
+
+/** GenericHID Interface
+ */
+class GenericHID
+{
+public:
+	enum JoystickHand
+	{
+		kLeftHand = 0,
+		kRightHand = 1
+	};
+
+	virtual ~GenericHID()
+	{
+	}
+
+	virtual float GetX(JoystickHand hand = kRightHand) = 0;
+	virtual float GetY(JoystickHand hand = kRightHand) = 0;
+	virtual float GetZ() = 0;
+	virtual float GetTwist() = 0;
+	virtual float GetThrottle() = 0;
+	virtual float GetRawAxis(uint32_t axis) = 0;
+
+	virtual bool GetTrigger(JoystickHand hand = kRightHand) = 0;
+	virtual bool GetTop(JoystickHand hand = kRightHand) = 0;
+	virtual bool GetBumper(JoystickHand hand = kRightHand) = 0;
+	virtual bool GetRawButton(uint32_t button) = 0;
+
+	virtual int GetPOV(uint32_t pov = 0) = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/HLUsageReporting.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/HLUsageReporting.h
new file mode 100644
index 0000000..359b149
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/HLUsageReporting.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
+
+class HLUsageReportingInterface
+{
+public:
+	virtual ~HLUsageReportingInterface() {};
+	virtual void ReportScheduler() = 0;
+    virtual void ReportSmartDashboard() = 0;
+};
+
+class HLUsageReporting
+{
+private:
+	static HLUsageReportingInterface* impl;
+	
+public:
+	static void SetImplementation(HLUsageReportingInterface* i);
+	static void ReportScheduler();
+    static void ReportSmartDashboard();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Notifier.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Notifier.h
new file mode 100644
index 0000000..9579e67
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Notifier.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 "ErrorBase.h"
+#include "Task.h"
+#include "HAL/cpp/Synchronized.hpp"
+
+typedef void (*TimerEventHandler)(void *param);
+
+class Notifier : public ErrorBase
+{
+public:
+	Notifier(TimerEventHandler handler, void *param = NULL);
+	virtual ~Notifier();
+	void StartSingle(double delay);
+	void StartPeriodic(double period);
+	void Stop();
+private:
+	static Notifier *timerQueueHead;
+	static ReentrantMutex queueSemaphore;
+	static void* m_notifier;
+	static int refcount;
+
+	static void ProcessQueue(uint32_t mask, void *params); // process the timer queue on a timer event
+	static void UpdateAlarm();			// update the FPGA alarm since the queue has changed
+	void InsertInQueue(bool reschedule);	// insert this Notifier in the timer queue
+	void DeleteFromQueue();				// delete this Notifier from the timer queue
+	TimerEventHandler m_handler;			// address of the handler
+	void *m_param;							// a parameter to pass to the handler
+	double m_period;						// the relative time (either periodic or single)
+	double m_expirationTime;				// absolute expiration time for the current event
+	Notifier *m_nextEvent;					// next Nofifier event
+	bool m_periodic;						// true if this is a periodic event
+	bool m_queued;							// indicates if this entry is queued
+	SEMAPHORE_ID m_handlerSemaphore;		// held by interrupt manager task while handler call is in progress
+
+	DISALLOW_COPY_AND_ASSIGN(Notifier);
+
+	static Task *task;
+	static void Run();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/PIDOutput.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/PIDOutput.h
new file mode 100644
index 0000000..a2e2c95
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/PIDOutput.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * PIDOutput interface is a generic output for the PID class.
+ * PWMs use this class.
+ * Users implement this interface to allow for a PIDController to 
+ * read directly from the inputs
+ */
+class PIDOutput
+{
+public:
+	virtual void PIDWrite(float output) = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/PIDSource.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/PIDSource.h
new file mode 100644
index 0000000..e81bd28
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/PIDSource.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+/**
+ * PIDSource interface is a generic sensor source for the PID class.
+ * All sensors that can be used with the PID class will implement the PIDSource that
+ * returns a standard value that will be used in the PID code.
+ */
+class PIDSource
+{	
+public:
+	enum PIDSourceParameter {kDistance, kRate, kAngle};
+	virtual double PIDGet() = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Resource.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Resource.h
new file mode 100644
index 0000000..4eb9427
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Resource.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/Synchronized.hpp"
+#include <stdint.h>
+
+/**
+ * The Resource class is a convenient way to track allocated resources.
+ * It tracks them as indicies in the range [0 .. elements - 1].
+ * E.g. the library uses this to track hardware channel allocation.
+ *
+ * The Resource class does not allocate the hardware channels or other
+ * resources; it just tracks which indices were marked in use by
+ * Allocate and not yet freed by Free.
+ */
+class Resource : public ErrorBase
+{
+public:
+	virtual ~Resource();
+	static void CreateResourceObject(Resource **r, uint32_t elements);
+	uint32_t Allocate(const char *resourceDesc);
+	uint32_t Allocate(uint32_t index, const char *resourceDesc);
+	void Free(uint32_t index);
+
+private:
+	explicit Resource(uint32_t size);
+
+	bool *m_isAllocated;
+	ReentrantMutex m_allocateLock;
+	uint32_t m_size;
+
+	static ReentrantMutex m_createLock;
+
+	DISALLOW_COPY_AND_ASSIGN(Resource);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/RobotState.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/RobotState.h
new file mode 100644
index 0000000..ee25493
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/RobotState.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+class RobotStateInterface
+{
+public:
+	virtual ~RobotStateInterface() {};
+    virtual bool IsDisabled() = 0;
+	virtual bool IsEnabled() = 0;
+	virtual bool IsOperatorControl() = 0;
+	virtual bool IsAutonomous() = 0;
+	virtual bool IsTest() = 0;
+};
+
+class RobotState
+{
+private:
+	static RobotStateInterface* impl;
+	
+public:
+	static void SetImplementation(RobotStateInterface* i);
+    static bool IsDisabled();
+	static bool IsEnabled();
+	static bool IsOperatorControl();
+	static bool IsAutonomous();
+	static bool IsTest();
+};
+
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/SensorBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/SensorBase.h
new file mode 100644
index 0000000..a629e18
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/SensorBase.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <stdio.h>
+#include "Base.h"
+
+/**
+ * Base class for all sensors.
+ * Stores most recent status information as well as containing utility functions for checking
+ * channels and error processing.
+ */
+class SensorBase : public ErrorBase
+{
+public:
+	SensorBase();
+	virtual ~SensorBase();
+	static void DeleteSingletons();
+
+	static uint32_t GetDefaultSolenoidModule()
+	{
+		return 0;
+	}
+
+	static bool CheckSolenoidModule(uint8_t moduleNumber);
+	static bool CheckDigitalChannel(uint32_t channel);
+	static bool CheckRelayChannel(uint32_t channel);
+	static bool CheckPWMChannel(uint32_t channel);
+	static bool CheckAnalogInput(uint32_t channel);
+	static bool CheckAnalogOutput(uint32_t channel);
+	static bool CheckSolenoidChannel(uint32_t channel);
+	static bool CheckPDPChannel(uint32_t channel);
+
+	static const uint32_t kDigitalChannels = 26;
+	static const uint32_t kAnalogInputs = 8;
+	static const uint32_t kAnalogOutputs = 2;
+	static const uint32_t kSolenoidChannels = 8;
+	static const uint32_t kSolenoidModules = 2;
+	static const uint32_t kPwmChannels = 20;
+	static const uint32_t kRelayChannels = 8;
+	static const uint32_t kPDPChannels = 16;
+	static const uint32_t kChassisSlots = 8;
+
+protected:
+	void AddToSingletonList();
+
+	static void* m_digital_ports[kDigitalChannels];
+	static void* m_relay_ports[kRelayChannels];
+	static void* m_pwm_ports[kPwmChannels];
+
+private:
+	DISALLOW_COPY_AND_ASSIGN(SensorBase);
+	static SensorBase *m_singletonList;
+	SensorBase *m_nextSingleton;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Task.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Task.h
new file mode 100644
index 0000000..ca1754a
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Task.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 "ErrorBase.h"
+#include "HAL/Task.hpp"
+
+/**
+ * WPI task is a wrapper for the native Task object.
+ * All WPILib tasks are managed by a static task manager for simplified cleanup.
+ **/
+class Task : public ErrorBase
+{
+public:
+	static const uint32_t kDefaultPriority = 101;
+
+	Task(const char* name, FUNCPTR function, int32_t priority = kDefaultPriority,
+			uint32_t stackSize = 20000);
+	virtual ~Task();
+
+	bool Start(uint32_t arg0 = 0, uint32_t arg1 = 0, uint32_t arg2 = 0, uint32_t arg3 = 0,
+			uint32_t arg4 = 0, uint32_t arg5 = 0, uint32_t arg6 = 0, uint32_t arg7 = 0,
+			uint32_t arg8 = 0, uint32_t arg9 = 0);
+	bool Restart();
+	bool Stop();
+
+	bool IsReady();
+	bool IsSuspended();
+
+	bool Suspend();
+	bool Resume();
+
+	bool Verify();
+
+	int32_t GetPriority();
+	bool SetPriority(int32_t priority);
+	const char* GetName();
+	TASK GetID();
+
+private:
+	FUNCPTR m_function;
+	char* m_taskName;
+	TASK m_taskID;
+	uint32_t m_stackSize;
+	int m_priority;
+	bool HandleError(STATUS results);
+	DISALLOW_COPY_AND_ASSIGN(Task);
+};
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Timer.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Timer.h
new file mode 100644
index 0000000..fc3f9af
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Timer.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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/cpp/Synchronized.hpp"
+#include "Base.h"
+
+typedef void (*TimerInterruptHandler)(void *param);
+
+void Wait(double seconds);
+double GetClock();
+double GetTime();
+
+/**
+ * Timer objects measure accumulated time in seconds.
+ * The timer object functions like a stopwatch. It can be started, stopped, and cleared. When the
+ * timer is running its value counts up in seconds. When stopped, the timer holds the current
+ * value. The implementation simply records the time when started and subtracts the current time
+ * whenever the value is requested.
+ */
+class Timer
+{
+public:
+	Timer();
+	virtual ~Timer();
+	double Get();
+	void Reset();
+	void Start();
+	void Stop();
+	bool HasPeriodPassed(double period);
+
+	static double GetFPGATimestamp();
+	static double GetPPCTimestamp();
+    static double GetMatchTime();
+	
+	// The time, in seconds, at which the 32-bit FPGA timestamp rolls over to 0
+	static constexpr double kRolloverTime = (1ll << 32) / 1e6;
+
+private:
+	double m_startTime;
+	double m_accumulatedTime;
+	bool m_running;
+	Mutex m_lock;
+	DISALLOW_COPY_AND_ASSIGN(Timer);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/Utility.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Utility.h
new file mode 100644
index 0000000..4fe325f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/Utility.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>
+#include <string>
+
+#define wpi_assert(condition) wpi_assert_impl(condition, #condition, NULL, __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertWithMessage(condition, message) wpi_assert_impl(condition, #condition, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertEqual(a, b) wpi_assertEqual_impl(a, b, #a, #b, NULL, __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertEqualWithMessage(a, b, message) wpi_assertEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertNotEqual(a, b) wpi_assertNotEqual_impl(a, b, #a, #b, NULL, __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertNotEqualWithMessage(a, b, message) wpi_assertNotEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, __FUNCTION__)
+
+bool wpi_assert_impl(bool conditionValue, const char *conditionText, const char *message, const char *fileName, uint32_t lineNumber, const char *funcName);
+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);
+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);
+
+void wpi_suspendOnAssertEnabled(bool enabled);
+
+uint16_t GetFPGAVersion();
+uint32_t GetFPGARevision();
+uint32_t GetFPGATime();
+bool GetUserButton();
+std::string GetStackTrace(uint32_t offset);
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/WPIErrors.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/WPIErrors.h
new file mode 100644
index 0000000..9e37715
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/WPIErrors.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
+
+#ifdef WPI_ERRORS_DEFINE_STRINGS
+#define S(label, offset, message) const char *wpi_error_s_##label = message ; \
+	const int32_t wpi_error_value_##label = offset
+#else
+#define S(label, offset, message) extern const char *wpi_error_s_##label ; \
+	const int32_t wpi_error_value_##label = offset
+#endif
+
+/*
+ * Fatal errors
+ */
+S(ModuleIndexOutOfRange, -1, "Allocating module that is out of range or not found");
+S(ChannelIndexOutOfRange, -1, "Allocating channel that is out of range");
+S(NotAllocated, -2, "Attempting to free unallocated resource");
+S(ResourceAlreadyAllocated, -3, "Attempted to reuse an allocated resource");
+S(NoAvailableResources, -4, "No available resources to allocate");
+S(NullParameter, -5, "A pointer parameter to a method is NULL");
+S(Timeout, -6, "A timeout has been exceeded");
+S(CompassManufacturerError, -7, "Compass manufacturer doesn't match HiTechnic");
+S(CompassTypeError, -8, "Compass type doesn't match expected type for HiTechnic compass");
+S(IncompatibleMode, -9, "The object is in an incompatible mode");
+S(AnalogTriggerLimitOrderError, -10, "AnalogTrigger limits error.  Lower limit > Upper Limit");
+S(AnalogTriggerPulseOutputError, -11, "Attempted to read AnalogTrigger pulse output.");
+S(TaskError, -12, "Task can't be started");
+S(TaskIDError, -13, "Task error: Invalid ID.");
+S(TaskDeletedError, -14, "Task error: Task already deleted.");
+S(TaskOptionsError, -15, "Task error: Invalid options.");
+S(TaskMemoryError, -16, "Task can't be started due to insufficient memory.");
+S(TaskPriorityError, -17, "Task error: Invalid priority [1-255].");
+S(DriveUninitialized, -18, "RobotDrive not initialized for the C interface");
+S(CompressorNonMatching, -19, "Compressor slot/channel doesn't match previous instance");
+S(CompressorAlreadyDefined, -20, "Creating a second compressor instance");
+S(CompressorUndefined, -21, "Using compressor functions without defining compressor");
+S(InconsistentArrayValueAdded, -22, "When packing data into an array to the dashboard, not all values added were of the same type.");
+S(MismatchedComplexTypeClose, -23, "When packing data to the dashboard, a Close for a complex type was called without a matching Open.");
+S(DashboardDataOverflow, -24, "When packing data to the dashboard, too much data was packed and the buffer overflowed.");
+S(DashboardDataCollision, -25, "The same buffer was used for packing data and for printing.");
+S(EnhancedIOMissing, -26, "IO is not attached or Enhanced IO is not enabled.");
+S(LineNotOutput, -27, "Cannot SetDigitalOutput for a line not configured for output.");
+S(ParameterOutOfRange, -28, "A parameter is out of range.");
+S(SPIClockRateTooLow, -29, "SPI clock rate was below the minimum supported");
+S(JaguarVersionError, -30, "Jaguar firmware version error");
+S(JaguarMessageNotFound, -31, "Jaguar message not found");
+S(NetworkTablesReadError, -40, "Error reading NetworkTables socket");
+S(NetworkTablesBufferFull, -41, "Buffer full writing to NetworkTables socket");
+S(NetworkTablesWrongType, -42, "The wrong type was read from the NetworkTables entry");
+S(NetworkTablesCorrupt, -43, "NetworkTables data stream is corrupt");
+S(SmartDashboardMissingKey, -43, "SmartDashboard data does not exist");
+S(CommandIllegalUse, -50, "Illegal use of Command");
+S(UnsupportedInSimulation, -80, "Unsupported in simulation");
+
+/*
+ * Warnings
+ */
+S(SampleRateTooHigh, 1, "Analog module sample rate is too high");
+S(VoltageOutOfRange, 2, "Voltage to convert to raw value is out of range [-10; 10]");
+S(CompressorTaskError, 3, "Compressor task won't start");
+S(LoopTimingError, 4, "Digital module loop timing is not the expected value");
+S(NonBinaryDigitalValue, 5, "Digital output value is not 0 or 1");
+S(IncorrectBatteryChannel, 6, "Battery measurement channel is not correct value");
+S(BadJoystickIndex, 7, "Joystick index is out of range, should be 0-3");
+S(BadJoystickAxis, 8, "Joystick axis or POV is out of range");
+S(InvalidMotorIndex, 9, "Motor index is out of range, should be 0-3");
+S(DriverStationTaskError, 10, "Driver Station task won't start");
+S(EnhancedIOPWMPeriodOutOfRange, 11, "Driver Station Enhanced IO PWM Output period out of range.");
+S(SPIWriteNoMOSI, 12, "Cannot write to SPI port with no MOSI output");
+S(SPIReadNoMISO, 13, "Cannot read from SPI port with no MISO input");
+S(SPIReadNoData, 14, "No data available to read from SPI");
+S(IncompatibleState, 15, "Incompatible State: The operation cannot be completed");
+
+#undef S
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/interfaces/Accelerometer.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/interfaces/Accelerometer.h
new file mode 100644
index 0000000..609e9bc
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/interfaces/Accelerometer.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+/**
+ * Interface for 3-axis accelerometers
+ */
+class Accelerometer
+{
+public:
+	virtual ~Accelerometer() {};
+
+	enum Range
+	{
+		kRange_2G = 0,
+		kRange_4G = 1,
+		kRange_8G = 2,
+		kRange_16G = 3
+	};
+
+	/**
+	 * Common interface for setting the measuring range of an accelerometer.
+	 *
+	 * @param range The maximum acceleration, positive or negative, that the
+	 * accelerometer will measure.  Not all accelerometers support all ranges.
+	 */
+	virtual void SetRange(Range range) = 0;
+
+	/**
+	 * Common interface for getting the x axis acceleration
+	 *
+	 * @return The acceleration along the x axis in g-forces
+	 */
+	virtual double GetX() = 0;
+
+	/**
+	 * Common interface for getting the y axis acceleration
+	 *
+	 * @return The acceleration along the y axis in g-forces
+	 */
+	virtual double GetY() = 0;
+
+	/**
+	 * Common interface for getting the z axis acceleration
+	 *
+	 * @return The acceleration along the z axis in g-forces
+	 */
+	virtual double GetZ() = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/include/interfaces/Potentiometer.h b/aos/externals/allwpilib/wpilibc/wpilibC++/include/interfaces/Potentiometer.h
new file mode 100644
index 0000000..f5f4567
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/include/interfaces/Potentiometer.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.  */
+/*----------------------------------------------------------------------------*/
+
+#ifndef INTERFACES_POTENTIOMETER_H
+#define INTERFACES_POTENTIOMETER_H
+
+#include "PIDSource.h"
+
+/**
+ * Interface for potentiometers.
+ */
+class Potentiometer : public PIDSource
+{
+public:
+	virtual ~Potentiometer() {};
+	/**
+	 * Common interface for getting the current value of a potentiometer.
+	 * 
+	 * @return The current set speed.  Value is between -1.0 and 1.0.
+	 */
+	virtual double Get() = 0;
+};
+
+#endif
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/src/Error.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++/src/Error.cpp
new file mode 100644
index 0000000..f64c4fe
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/src/Error.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Error.h"
+
+#include <iostream>
+#include <sstream>
+#include <cstring>
+#include <cstdlib>
+#include <stdint.h>
+#include "HAL/Task.hpp"
+
+#include "DriverStation.h"
+#include "Timer.h"
+#include "Utility.h"
+bool Error::m_suspendOnErrorEnabled = false;
+
+Error::Error()
+	: m_code(0)
+	, m_lineNumber(0)
+	, m_originatingObject(NULL)
+	, m_timestamp (0.0)
+{}
+
+Error::~Error()
+{}
+
+void Error::Clone(Error &error)
+{
+	m_code = error.m_code;
+	m_message = error.m_message;
+	m_filename = error.m_filename;
+	m_function = error.m_function;
+	m_lineNumber = error.m_lineNumber;
+	m_originatingObject = error.m_originatingObject;
+	m_timestamp = error.m_timestamp;
+}
+
+Error::Code Error::GetCode() const
+{	return m_code;  }
+
+const char * Error::GetMessage() const
+{	return m_message.c_str();  }
+
+const char * Error::GetFilename() const
+{	return m_filename.c_str();  }
+
+const char * Error::GetFunction() const
+{	return m_function.c_str();  }
+
+uint32_t Error::GetLineNumber() const
+{	return m_lineNumber;  }
+
+const ErrorBase* Error::GetOriginatingObject() const
+{	return m_originatingObject;  }
+
+double Error::GetTimestamp() const
+{	return m_timestamp;  }
+
+void Error::Set(Code code, const char* contextMessage, const char* filename, const char* function, uint32_t lineNumber, const ErrorBase* originatingObject)
+{
+	bool report = true;
+
+	if(code == m_code && GetTime() - m_timestamp < 1)
+	{
+		report = false;
+	}
+
+	m_code = code;
+	m_message = contextMessage;
+	m_filename = filename;
+	m_function = function;
+	m_lineNumber = lineNumber;
+	m_originatingObject = originatingObject;
+
+	if(report)
+	{
+		m_timestamp = GetTime();
+		Report();
+	}
+
+    if (m_suspendOnErrorEnabled) suspendTask(0);
+}
+
+void Error::Report()
+{
+	std::stringstream errorStream;
+
+	errorStream << "Error on line " << m_lineNumber << " ";
+	errorStream << "of "<< basename(m_filename.c_str()) << ": ";
+	errorStream << m_message << std::endl;
+	errorStream << GetStackTrace(4);
+
+	std::string error = errorStream.str();
+
+	DriverStation::ReportError(error);
+}
+
+void Error::Clear()
+{
+	m_code = 0;
+	m_message = "";
+	m_filename = "";
+	m_function = "";
+	m_lineNumber = 0;
+	m_originatingObject = NULL;
+	m_timestamp = 0.0;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/src/ErrorBase.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++/src/ErrorBase.cpp
new file mode 100644
index 0000000..e4dda4b
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/src/ErrorBase.cpp
@@ -0,0 +1,205 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ErrorBase.h"
+#include "HAL/cpp/Synchronized.hpp"
+#define WPI_ERRORS_DEFINE_STRINGS
+#include "WPIErrors.h"
+
+#include <errno.h>
+#include <cstring>
+#include <cstdio>
+
+Mutex ErrorBase::_globalErrorMutex;
+Error ErrorBase::_globalError;
+/**
+ * @brief Initialize the instance status to 0 for now.
+ */
+ErrorBase::ErrorBase()
+{}
+
+ErrorBase::~ErrorBase()
+{}
+
+/**
+ * @brief Retrieve the current error.
+ * Get the current error information associated with this sensor.
+ */
+Error& ErrorBase::GetError()
+{
+	return m_error;
+}
+
+const Error& ErrorBase::GetError() const
+{
+	return m_error;
+}
+
+/**
+ * @brief Clear the current error information associated with this sensor.
+ */
+void ErrorBase::ClearError() const
+{
+	m_error.Clear();
+}
+
+/**
+ * @brief Set error information associated with a C library call that set an error to the "errno" global variable.
+ *
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetErrnoError(const char *contextMessage,
+		const char* filename, const char* function, uint32_t lineNumber) const
+{
+	char err[256];
+	int errNo = errno;
+	if (errNo == 0)
+	{
+		sprintf(err, "OK: %s", contextMessage);
+	}
+	else
+	{
+		snprintf(err, 256, "%s (0x%08X): %s", strerror(errNo), errNo, contextMessage);
+	}
+
+	//  Set the current error information for this object.
+	m_error.Set(-1, err, filename, function, lineNumber, this);
+
+	// Update the global error if there is not one already set.
+	::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+	if (_globalError.GetCode() == 0) {
+		_globalError.Clone(m_error);
+	}
+}
+
+/**
+ * @brief Set the current error information associated from the nivision Imaq API.
+ *
+ * @param success The return from the function
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetImaqError(int success, const char *contextMessage, const char* filename, const char* function, uint32_t lineNumber) const
+{
+	//  If there was an error
+	if (success <= 0) {
+		char err[256];
+		sprintf(err, "%i: %s", success, contextMessage);
+
+		//  Set the current error information for this object.
+		m_error.Set(success, err, filename, function, lineNumber, this);
+
+		// Update the global error if there is not one already set.
+		::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+		if (_globalError.GetCode() == 0) {
+			_globalError.Clone(m_error);
+		}
+	}
+}
+
+/**
+ * @brief Set the current error information associated with this sensor.
+ *
+ * @param code The error code
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetError(Error::Code code, const char *contextMessage,
+		const char* filename, const char* function, uint32_t lineNumber) const
+{
+	//  If there was an error
+	if (code != 0) {
+		//  Set the current error information for this object.
+		m_error.Set(code, contextMessage, filename, function, lineNumber, this);
+
+		// Update the global error if there is not one already set.
+		::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+		if (_globalError.GetCode() == 0) {
+			_globalError.Clone(m_error);
+		}
+	}
+}
+
+/**
+ * @brief Set the current error information associated with this sensor.
+ *
+ * @param errorMessage The error message from WPIErrors.h
+ * @param contextMessage A custom message from the code that set the error.
+ * @param filename Filename of the error source
+ * @param function Function of the error source
+ * @param lineNumber Line number of the error source
+ */
+void ErrorBase::SetWPIError(const char *errorMessage, Error::Code code , const char *contextMessage,
+		const char* filename, const char* function, uint32_t lineNumber) const
+{
+	char err[256];
+	sprintf(err, "%s: %s", errorMessage, contextMessage);
+
+	//  Set the current error information for this object.
+	m_error.Set(code, err, filename, function, lineNumber, this);
+
+	// Update the global error if there is not one already set.
+	::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+	if (_globalError.GetCode() == 0) {
+		_globalError.Clone(m_error);
+	}
+}
+
+void ErrorBase::CloneError(ErrorBase *rhs) const
+{
+	m_error.Clone(rhs->GetError());
+}
+
+/**
+@brief Check if the current error code represents a fatal error.
+
+@return true if the current error is fatal.
+*/
+bool ErrorBase::StatusIsFatal() const
+{
+	return m_error.GetCode() < 0;
+}
+
+void ErrorBase::SetGlobalError(Error::Code code, const char *contextMessage,
+		const char* filename, const char* function, uint32_t lineNumber)
+{
+	//  If there was an error
+	if (code != 0) {
+		::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+
+		//  Set the current error information for this object.
+		_globalError.Set(code, contextMessage, filename, function, lineNumber, NULL);
+	}
+}
+
+void ErrorBase::SetGlobalWPIError(const char *errorMessage, const char *contextMessage,
+        const char* filename, const char* function, uint32_t lineNumber)
+{
+	char err[256];
+	sprintf(err, "%s: %s", errorMessage, contextMessage);
+
+	::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+	if (_globalError.GetCode() != 0) {
+		_globalError.Clear();
+	}
+	_globalError.Set(-1, err, filename, function, lineNumber, NULL);
+}
+
+/**
+  * Retrieve the current global error.
+*/
+Error& ErrorBase::GetGlobalError()
+{
+	::std::unique_lock<Mutex> mutex(_globalErrorMutex);
+	return _globalError;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/src/HLUsageReporting.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++/src/HLUsageReporting.cpp
new file mode 100644
index 0000000..c003298
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/src/HLUsageReporting.cpp
@@ -0,0 +1,20 @@
+
+#include "HLUsageReporting.h"
+
+HLUsageReportingInterface* HLUsageReporting::impl = 0;
+
+void HLUsageReporting::SetImplementation(HLUsageReportingInterface* i) {
+    impl = i;
+}
+
+void HLUsageReporting::ReportScheduler() {
+    if (impl != 0) {
+        impl->ReportScheduler();
+    }
+}
+
+void HLUsageReporting::ReportSmartDashboard() {
+    if (impl != 0) {
+        impl->ReportSmartDashboard();
+    }
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/src/Resource.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++/src/Resource.cpp
new file mode 100644
index 0000000..f582155
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/src/Resource.cpp
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Resource.h"
+#include "WPIErrors.h"
+#include "ErrorBase.h"
+
+ReentrantMutex Resource::m_createLock;
+
+/**
+ * Allocate storage for a new instance of Resource.
+ * Allocate a bool array of values that will get initialized to indicate that no resources
+ * have been allocated yet. The indicies of the resources are [0 .. elements - 1].
+ */
+Resource::Resource(uint32_t elements)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_createLock);
+	m_size = elements;
+	m_isAllocated = new bool[m_size];
+	for (uint32_t i=0; i < m_size; i++)
+	{
+		m_isAllocated[i] = false;
+	}
+}
+
+/**
+ * Factory method to create a Resource allocation-tracker *if* needed.
+ *
+ * @param r -- address of the caller's Resource pointer. If *r == NULL, this
+ *    will construct a Resource and make *r point to it. If *r != NULL, i.e.
+ *    the caller already has a Resource instance, this won't do anything.
+ * @param elements -- the number of elements for this Resource allocator to
+ *    track, that is, it will allocate resource numbers in the range
+ *    [0 .. elements - 1].
+ */
+/*static*/ void Resource::CreateResourceObject(Resource **r, uint32_t elements)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_createLock);
+	if (*r == NULL)
+	{
+		*r = new Resource(elements);
+	}
+}
+
+/**
+ * Delete the allocated array or resources.
+ * This happens when the module is unloaded (provided it was statically allocated).
+ */
+Resource::~Resource()
+{
+	delete[] m_isAllocated;
+}
+
+/**
+ * Allocate a resource.
+ * When a resource is requested, mark it allocated. In this case, a free resource value
+ * within the range is located and returned after it is marked allocated.
+ */
+uint32_t Resource::Allocate(const char *resourceDesc)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_allocateLock);
+	for (uint32_t i=0; i < m_size; i++)
+	{
+		if (!m_isAllocated[i])
+		{
+			m_isAllocated[i] = true;
+			return i;
+		}
+	}
+	wpi_setWPIErrorWithContext(NoAvailableResources, resourceDesc);
+	return ~0ul;
+}
+
+/**
+ * Allocate a specific resource value.
+ * The user requests a specific resource value, i.e. channel number and it is verified
+ * unallocated, then returned.
+ */
+uint32_t Resource::Allocate(uint32_t index, const char *resourceDesc)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_allocateLock);
+	if (index >= m_size)
+	{
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc);
+		return ~0ul;
+	}
+	if ( m_isAllocated[index] )
+	{
+		wpi_setWPIErrorWithContext(ResourceAlreadyAllocated, resourceDesc);
+		return ~0ul;
+	}
+	m_isAllocated[index] = true;
+	return index;
+}
+
+
+/**
+ * Free an allocated resource.
+ * After a resource is no longer needed, for example a destructor is called for a channel assignment
+ * class, Free will release the resource value so it can be reused somewhere else in the program.
+ */
+void Resource::Free(uint32_t index)
+{
+	::std::unique_lock<ReentrantMutex> sync(m_allocateLock);
+	if (index == ~0ul) return;
+	if (index >= m_size)
+	{
+		wpi_setWPIError(NotAllocated);
+		return;
+	}
+	if (!m_isAllocated[index])
+	{
+		wpi_setWPIError(NotAllocated);
+		return;
+	}
+	m_isAllocated[index] = false;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++/src/RobotState.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++/src/RobotState.cpp
new file mode 100644
index 0000000..747000a
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++/src/RobotState.cpp
@@ -0,0 +1,42 @@
+#include "RobotState.h"
+
+RobotStateInterface* RobotState::impl = 0;
+
+void RobotState::SetImplementation(RobotStateInterface* i) {
+    impl = i;
+}
+
+bool RobotState::IsDisabled() {
+    if (impl != nullptr) {
+        return impl->IsDisabled();
+    }
+    return true;
+}
+
+bool RobotState::IsEnabled() {
+    if (impl != nullptr) {
+        return impl->IsEnabled();
+    }
+    return false;
+}
+
+bool RobotState::IsOperatorControl() {
+    if (impl != nullptr) {
+        return impl->IsOperatorControl();
+    }
+    return true;
+}
+
+bool RobotState::IsAutonomous() {
+    if (impl != nullptr) {
+        return impl->IsAutonomous();
+    }
+    return false;
+}
+
+bool RobotState::IsTest() {
+    if (impl != nullptr) {
+        return impl->IsTest();
+    }
+    return false;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/CMakeLists.txt b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/CMakeLists.txt
new file mode 100644
index 0000000..f73522c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/CMakeLists.txt
@@ -0,0 +1,13 @@
+cmake_minimum_required(VERSION 2.8)
+project(WPILibC++Devices)
+
+file(GLOB_RECURSE SRC_FILES src/*.cpp)
+include_directories(include/ ${WPILIB_INCLUDES} ${HAL_API_INCLUDES} ${NWT_API_INCLUDES})
+add_library(wpilib_nonshared STATIC ${SRC_FILES} ${COM_SRC_FILES})
+target_link_libraries(wpilib_nonshared HALAthena NetworkTables ${NI_LIBS})
+INSTALL(TARGETS wpilib_nonshared ARCHIVE DESTINATION lib COMPONENT lib)
+INSTALL(DIRECTORY include DESTINATION ${CMAKE_INSTALL_PREFIX} COMPONENT headers)
+# lib/ c m gcc_s ld-linux
+# usr/lib stdc++
+# ni_emb
+# HAL NWT
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ADXL345_I2C.h
new file mode 100644
index 0000000..5cff335
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ADXL345_I2C.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 "interfaces/Accelerometer.h"
+#include "I2C.h"
+
+/**
+ * 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
+{
+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();
+
+	// Accelerometer interface
+	virtual void SetRange(Range range);
+	virtual double GetX();
+	virtual double GetY();
+	virtual double GetZ();
+
+	virtual double GetAcceleration(Axes axis);
+	virtual AllAxes GetAccelerations();
+
+protected:
+	//I2C* m_i2c;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h
new file mode 100644
index 0000000..4cfc64e
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ADXL345_SPI.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+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, public SensorBase
+{
+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();
+
+	// Accelerometer interface
+	virtual void SetRange(Range range);
+	virtual double GetX();
+	virtual double GetY();
+	virtual double GetZ();
+
+	virtual double GetAcceleration(Axes axis);
+	virtual AllAxes GetAccelerations();
+
+protected:
+	void Init(Range range);
+
+	SPI* m_spi;
+	SPI::Port m_port;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.h
new file mode 100644
index 0000000..8d7a3f0
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogAccelerometer.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 "AnalogInput.h"
+#include "SensorBase.h"
+#include "PIDSource.h"
+
+/**
+ * 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:
+	explicit AnalogAccelerometer(int32_t channel);
+	explicit AnalogAccelerometer(AnalogInput *channel);
+	virtual ~AnalogAccelerometer();
+
+	float GetAcceleration();
+	void SetSensitivity(float sensitivity);
+	void SetZero(float zero);
+	double PIDGet();
+
+private:
+	void InitAccelerometer();
+
+	AnalogInput *m_AnalogInput;
+	float m_voltsPerG;
+	float m_zeroGVoltage;
+	bool m_allocatedChannel;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogInput.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogInput.h
new file mode 100644
index 0000000..8e10808
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogInput.h
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "HAL/HAL.hpp"
+#include "SensorBase.h"
+#include "PIDSource.h"
+
+/**
+ * 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:
+	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();
+	int32_t GetAverageValue();
+
+	float GetVoltage();
+	float GetAverageVoltage();
+
+	uint32_t GetChannel();
+
+	void SetAverageBits(uint32_t bits);
+	uint32_t GetAverageBits();
+	void SetOversampleBits(uint32_t bits);
+	uint32_t GetOversampleBits();
+
+	uint32_t GetLSBWeight();
+	int32_t GetOffset();
+
+	bool IsAccumulatorChannel();
+	void InitAccumulator();
+	void SetAccumulatorInitialValue(int64_t value);
+	void ResetAccumulator();
+	void SetAccumulatorCenter(int32_t center);
+	void SetAccumulatorDeadband(int32_t deadband);
+	int64_t GetAccumulatorValue();
+	uint32_t GetAccumulatorCount();
+	void GetAccumulatorOutput(int64_t *value, uint32_t *count);
+
+	static void SetSampleRate(float samplesPerSecond);
+	static float GetSampleRate();
+
+	double PIDGet();
+
+private:
+	void InitAnalogInput(uint32_t channel);
+	uint32_t m_channel;
+	void* m_port;
+	int64_t m_accumulatorOffset;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogOutput.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogOutput.h
new file mode 100644
index 0000000..14abcb2
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogOutput.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 the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/HAL.hpp"
+#include "SensorBase.h"
+
+/**
+ * MXP analog output class.
+ */
+class AnalogOutput : public SensorBase
+{
+public:
+    explicit AnalogOutput(uint32_t channel);
+    virtual ~AnalogOutput();
+
+    void SetVoltage(float voltage);
+    float GetVoltage();
+
+protected:
+    void InitAnalogOutput(uint32_t channel);
+    uint32_t m_channel;
+    void* m_port;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h
new file mode 100644
index 0000000..8b8cd76
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogPotentiometer.h
@@ -0,0 +1,64 @@
+
+#include "AnalogInput.h"
+#include "interfaces/Potentiometer.h"
+
+/**
+ * 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:
+    /**
+     * 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(AnalogInput &input, double fullRange = 1.0, double offset = 0.0);
+
+    virtual ~AnalogPotentiometer();
+
+    /**
+     * Get the current reading of the potentiomer.
+     *
+     * @return The current position of the potentiometer.
+     */
+    virtual double Get();
+
+
+    /**
+     * Implement the PIDSource interface.
+     *
+     * @return The current reading.
+     */
+    virtual double PIDGet();
+
+private:
+    double m_fullRange, m_offset;
+    AnalogInput* m_analog_input;
+    bool m_init_analog_input;
+
+    /**
+     * Common initialization code called by all constructors.
+     */
+    void initPot(AnalogInput *input, double fullRange, double offset);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogTrigger.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogTrigger.h
new file mode 100644
index 0000000..9b18a33
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogTrigger.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 "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();
+	bool GetInWindow();
+	bool GetTriggerState();
+	AnalogTriggerOutput *CreateOutput(AnalogTriggerType type);
+
+private:
+	void InitTrigger(uint32_t channel);
+
+	uint8_t m_index;
+	void* m_trigger;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h
new file mode 100644
index 0000000..e4d8cd5
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/AnalogTriggerOutput.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+
+	// DigitalSource interface
+	virtual uint32_t GetChannelForRouting();
+	virtual uint32_t GetModuleForRouting();
+	virtual bool GetAnalogTriggerForRouting();
+protected:
+	AnalogTriggerOutput(AnalogTrigger *trigger, AnalogTriggerType outputType);
+
+private:
+	AnalogTrigger *m_trigger;
+	AnalogTriggerType m_outputType;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h
new file mode 100644
index 0000000..563df99
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/BuiltInAccelerometer.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * Built-in accelerometer.
+ *
+ * This class allows access to the RoboRIO's internal accelerometer.
+ */
+class BuiltInAccelerometer : public Accelerometer, public SensorBase
+{
+public:
+	BuiltInAccelerometer(Range range = kRange_8G);
+        virtual ~BuiltInAccelerometer();
+
+	// Accelerometer interface
+	virtual void SetRange(Range range);
+	virtual double GetX();
+	virtual double GetY();
+	virtual double GetZ();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CAN/can_proto.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CAN/can_proto.h
new file mode 100644
index 0000000..5113b02
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CAN/can_proto.h
@@ -0,0 +1,428 @@
+//*****************************************************************************
+//
+// 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANJaguar.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANJaguar.h
new file mode 100644
index 0000000..67d6db3
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANJaguar.h
@@ -0,0 +1,208 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Semaphore.hpp"
+#include "HAL/HAL.hpp"
+#include "NetworkCommunication/CANSessionMux.h"
+
+#include <utility>
+
+/**
+ * Luminary Micro / Vex Robotics Jaguar Speed Control
+ */
+class CANJaguar : public MotorSafety,
+					public CANSpeedController,
+					public ErrorBase
+{
+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();
+
+	// PIDOutput interface
+	virtual void PIDWrite(float output);
+
+	// 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() 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() override;
+	virtual double GetI() override;
+	virtual double GetD() override;
+	virtual float GetBusVoltage() override;
+	virtual float GetOutputVoltage() override;
+	virtual float GetOutputCurrent() override;
+	virtual float GetTemperature() override;
+	virtual double GetPosition() override;
+	virtual double GetSpeed() override;
+	virtual bool GetForwardLimitOK() override;
+	virtual bool GetReverseLimitOK() override;
+	virtual uint16_t GetFaults() override;
+	virtual void SetVoltageRampRate(double rampRate) override;
+	virtual uint32_t GetFirmwareVersion() 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();
+
+ 	static void UpdateSyncGroup(uint8_t syncGroup);
+
+	void SetExpiration(float timeout);
+	float GetExpiration();
+	bool IsAlive();
+	void StopMotor();
+	bool IsSafetyEnabled();
+	void SetSafetyEnabled(bool enabled);
+	void GetDescription(char *desc);
+	uint8_t GetDeviceID();
+
+protected:
+	// Control mode helpers
+	void SetSpeedReference(uint8_t reference);
+	uint8_t GetSpeedReference();
+
+	void SetPositionReference(uint8_t reference);
+	uint8_t GetPositionReference();
+
+	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);
+	double unpackFXP8_8(uint8_t *buffer);
+	double unpackFXP16_16(uint8_t *buffer);
+	int16_t unpackint16_t(uint8_t *buffer);
+	int32_t unpackint32_t(uint8_t *buffer);
+
+	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);
+
+	void setupPeriodicStatus();
+	void updatePeriodicStatus();
+
+	uint8_t m_deviceNumber;
+	float m_value;
+
+	// Parameters/configuration
+	ControlMode m_controlMode;
+	uint8_t m_speedReference;
+	uint8_t m_positionReference;
+	double m_p;
+	double m_i;
+	double m_d;
+	NeutralMode m_neutralMode;
+	uint16_t m_encoderCodesPerRev;
+	uint16_t m_potentiometerTurns;
+	LimitMode m_limitMode;
+	double m_forwardLimit;
+	double m_reverseLimit;
+	double m_maxOutputVoltage;
+	double m_voltageRampRate;
+	float m_faultTime;
+
+	// Which parameters have been verified since they were last set?
+	bool m_controlModeVerified;
+	bool m_speedRefVerified;
+	bool m_posRefVerified;
+	bool m_pVerified;
+	bool m_iVerified;
+	bool m_dVerified;
+	bool m_neutralModeVerified;
+	bool m_encoderCodesPerRevVerified;
+	bool m_potentiometerTurnsVerified;
+	bool m_forwardLimitVerified;
+	bool m_reverseLimitVerified;
+	bool m_limitModeVerified;
+	bool m_maxOutputVoltageVerified;
+	bool m_voltageRampRateVerified;
+	bool m_faultTimeVerified;
+
+	// Status data
+	float m_busVoltage;
+	float m_outputVoltage;
+	float m_outputCurrent;
+	float m_temperature;
+	double m_position;
+	double m_speed;
+	uint8_t m_limits;
+	uint16_t m_faults;
+	uint32_t m_firmwareVersion;
+	uint8_t m_hardwareVersion;
+
+	// Which periodic status messages have we received at least once?
+	bool m_receivedStatusMessage0;
+	bool m_receivedStatusMessage1;
+	bool m_receivedStatusMessage2;
+
+	bool m_controlEnabled;
+
+	void verify();
+
+	MotorSafetyHelper *m_safetyHelper;
+
+private:
+	void InitCANJaguar();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANSpeedController.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANSpeedController.h
new file mode 100644
index 0000000..16d3088
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANSpeedController.h
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* 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.
+	};
+
+	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() = 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() = 0;
+	virtual double GetI() = 0;
+	virtual double GetD() = 0;
+	virtual float GetBusVoltage() = 0;
+	virtual float GetOutputVoltage() = 0;
+	virtual float GetOutputCurrent() = 0;
+	virtual float GetTemperature() = 0;
+	virtual double GetPosition() = 0;
+	virtual double GetSpeed() = 0;
+	virtual bool GetForwardLimitOK() = 0;
+	virtual bool GetReverseLimitOK() = 0;
+	virtual uint16_t GetFaults() = 0;
+	virtual void SetVoltageRampRate(double rampRate) = 0;
+	virtual uint32_t GetFirmwareVersion() = 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() = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANTalon.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANTalon.h
new file mode 100644
index 0000000..c720ea0
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CANTalon.h
@@ -0,0 +1,171 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "MotorSafetyHelper.h"
+
+class CanTalonSRX;
+
+/**
+ * CTRE Talon SRX Speed Controller with CAN Control
+ */
+class CANTalon : public MotorSafety,
+                 public CANSpeedController,
+                 public ErrorBase
+{
+public:
+  enum FeedbackDevice {
+    QuadEncoder=0,
+    AnalogPot=2,
+    AnalogEncoder=3,
+    EncRising=4,
+    EncFalling=5
+  };
+  enum StatusFrameRate {
+    StatusFrameRateGeneral=0,
+    StatusFrameRateFeedback=1,
+    StatusFrameRateQuadEncoder=2,
+    StatusFrameRateAnalogTempVbat=3,
+  };
+	explicit CANTalon(int deviceNumber);
+	explicit CANTalon(int deviceNumber,int controlPeriodMs);
+	virtual ~CANTalon();
+
+	// PIDController interface
+	virtual void PIDWrite(float output) override;
+
+	// MotorSafety interface
+	virtual void SetExpiration(float timeout) override;
+	virtual float GetExpiration() override;
+	virtual bool IsAlive() override;
+	virtual void StopMotor() override;
+	virtual void SetSafetyEnabled(bool enabled) override;
+	virtual bool IsSafetyEnabled() override;
+	virtual void GetDescription(char *desc) override;
+
+	// CANSpeedController interface
+	virtual float Get() override;
+	virtual void Set(float value, uint8_t syncGroup=0) override;
+	virtual void Disable() override;
+  virtual void EnableControl();
+	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;
+	void SetPID(double p, double i, double d, double f);
+	virtual double GetP() override;
+	virtual double GetI() override;
+	virtual double GetD() override;
+	double GetF();
+	virtual float GetBusVoltage() override;
+	virtual float GetOutputVoltage() override;
+	virtual float GetOutputCurrent() override;
+	virtual float GetTemperature() override;
+	void SetPosition(double pos);
+	virtual double GetPosition() override;
+	virtual double GetSpeed() override;
+  virtual int GetClosedLoopError();
+  virtual int GetAnalogIn();
+  virtual int GetAnalogInRaw();
+  virtual int GetAnalogInVel();
+  virtual int GetEncPosition();
+  virtual int GetEncVel();
+	int GetPinStateQuadA();
+	int GetPinStateQuadB();
+	int GetPinStateQuadIdx();
+	int IsFwdLimitSwitchClosed();
+	int IsRevLimitSwitchClosed();
+	int GetNumberOfQuadIdxRises();
+	void SetNumberOfQuadIdxRises(int rises);
+	virtual bool GetForwardLimitOK() override;
+	virtual bool GetReverseLimitOK() override;
+	virtual uint16_t GetFaults() override;
+	uint16_t GetStickyFaults();
+	void ClearStickyFaults();
+	virtual void SetVoltageRampRate(double rampRate) override;
+	virtual uint32_t GetFirmwareVersion() 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;
+	virtual void ConfigFaultTime(float faultTime) override;
+	virtual void SetControlMode(ControlMode mode);
+  void SetFeedbackDevice(FeedbackDevice device);
+	void SetStatusFrameRateMs(StatusFrameRate stateFrame, int periodMs);
+	virtual ControlMode GetControlMode();
+	void SetSensorDirection(bool reverseSensor);
+	void SetCloseLoopRampRate(double rampRate);
+	void SelectProfileSlot(int slotIdx);
+	int GetIzone();
+	int GetIaccum();
+	void ClearIaccum();
+	int GetBrakeEnableDuringNeutral();
+
+  bool IsControlEnabled();
+  double GetSetpoint();
+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;
+	CanTalonSRX *m_impl;
+	MotorSafetyHelper *m_safetyHelper;
+  int m_profile; // Profile from CANTalon to use. Set to zero until we can actually test this.
+
+  bool m_controlEnabled;
+  ControlMode m_controlMode;
+  TalonControlMode m_sendMode;
+
+  double m_setPoint;
+  static const unsigned int kDelayForSolicitedSignalsUs = 4000;
+  /**
+   * 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);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Compressor.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Compressor.h
new file mode 100644
index 0000000..ffe6e65
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Compressor.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * PCM compressor
+ */
+class Compressor: public SensorBase {
+public:
+	explicit Compressor(uint8_t pcmID);
+	Compressor();
+	virtual ~Compressor();
+
+	void Start();
+	void Stop();
+	bool Enabled();
+
+	bool GetPressureSwitchValue();
+
+	float GetCompressorCurrent();
+
+	void SetClosedLoopControl(bool on);
+	bool GetClosedLoopControl();
+
+	bool GetCompressorCurrentTooHighFault();
+	bool GetCompressorCurrentTooHighStickyFault();
+	bool GetCompressorShortedStickyFault();
+	bool GetCompressorShortedFault();
+	bool GetCompressorNotConnectedStickyFault();
+	bool GetCompressorNotConnectedFault();
+	void ClearAllPCMStickyFaults();
+
+protected:
+	void *m_pcm_pointer;
+
+private:
+	void InitCompressor(uint8_t module);
+	void SetCompressor(bool on);
+};
+
+#endif /* Compressor_H_ */
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ControllerPower.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ControllerPower.h
new file mode 100644
index 0000000..654cfb5
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ControllerPower.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Counter.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Counter.h
new file mode 100644
index 0000000..0eace8c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Counter.h
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "HAL/HAL.hpp"
+#include "AnalogTriggerOutput.h"
+#include "CounterBase.h"
+#include "SensorBase.h"
+
+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:
+
+	Counter();
+	explicit Counter(int32_t channel);
+	explicit Counter(DigitalSource *source);
+	explicit Counter(DigitalSource &source);
+	explicit Counter(AnalogTrigger *trigger);
+	explicit Counter(AnalogTrigger &trigger);
+	Counter(EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource,
+			bool inverted);
+	virtual ~Counter();
+
+	void SetUpSource(int32_t channel);
+	void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType);
+	void SetUpSource(AnalogTrigger &analogTrigger, AnalogTriggerType triggerType);
+	void SetUpSource(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(AnalogTrigger &analogTrigger, AnalogTriggerType triggerType);
+	void SetDownSource(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();
+	void Reset();
+	double GetPeriod();
+	void SetMaxPeriod(double maxPeriod);
+	void SetUpdateWhenEmpty(bool enabled);
+	bool GetStopped();
+	bool GetDirection();
+	void SetSamplesToAverage(int samplesToAverage);
+	int GetSamplesToAverage();
+	uint32_t GetFPGAIndex()
+	{
+		return m_index;
+	}
+
+protected:
+	DigitalSource *m_upSource;		///< What makes the counter count up.
+	DigitalSource *m_downSource;	///< What makes the counter count down.
+	void* m_counter;				///< The FPGA counter object.
+private:
+	void InitCounter(Mode mode = kTwoPulse);
+
+	bool m_allocatedUpSource;		///< Was the upSource allocated locally?
+	bool m_allocatedDownSource;	///< Was the downSource allocated locally?
+	uint32_t m_index;					///< The index of this counter.
+
+  friend class DigitalGlitchFilter;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CounterBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CounterBase.h
new file mode 100644
index 0000000..f475ddf
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/CounterBase.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 <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() {}
+	virtual int32_t Get() = 0;
+	virtual void Reset() = 0;
+	virtual double GetPeriod() = 0;
+	virtual void SetMaxPeriod(double maxPeriod) = 0;
+	virtual bool GetStopped() = 0;
+	virtual bool GetDirection() = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalInput.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalInput.h
new file mode 100644
index 0000000..2b548d3
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalInput.h
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <array>
+
+#include "DigitalSource.h"
+
+class Encoder;
+class Counter;
+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:
+	explicit DigitalInput(uint32_t channel);
+	virtual ~DigitalInput();
+	bool Get();
+	uint32_t GetChannel();
+
+	// Digital Source Interface
+	virtual uint32_t GetChannelForRouting();
+	virtual uint32_t GetModuleForRouting();
+	virtual bool GetAnalogTriggerForRouting();
+
+private:
+	void InitDigitalInput(uint32_t channel);
+	uint32_t m_channel;
+	bool m_lastValue;
+
+  friend DigitalGlitchFilter;
+};
+
+/**
+ * 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 ErrorBase {
+ public:
+  DigitalGlitchFilter();
+  ~DigitalGlitchFilter();
+
+  /**
+   * Assigns the DigitalSource to this glitch filter.
+   *
+   * @param input The DigitalSource to add.
+   */
+  void Add(DigitalSource *input);
+
+  /**
+   * Assigns the Encoder to this glitch filter.
+   *
+   * @param input The Encoder to add.
+   */
+  void Add(Encoder *input);
+
+  /**
+   * Assigns the Counter to this glitch filter.
+   *
+   * @param input The Counter to add.
+   */
+  void Add(Counter *input);
+
+  /**
+   * 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 Remove(DigitalSource *input);
+  void Remove(Encoder *input);
+  void Remove(Counter *input);
+
+  /**
+   * Sets the number of cycles that the input must not change state for.
+   *
+   * @param fpga_cycles The number of FPGA cycles.
+   */
+  void SetPeriodCycles(uint32_t fpga_cycles);
+
+  /**
+   * Sets the number of nanoseconds that the input must not change state for.
+   *
+   * @param nanoseconds The number of nanoseconds.
+   */
+  void SetPeriodNanoSeconds(uint64_t nanoseconds);
+
+  /**
+   * Gets the number of cycles that the input must not change state for.
+   *
+   * @return The number of cycles.
+   */
+  uint32_t GetPeriodCycles();
+  /**
+   * Gets the number of nanoseconds that the input must not change state for.
+   *
+   * @return The number of nanoseconds.
+   */
+  uint64_t GetPeriodNanoSeconds();
+
+ private:
+  int channel_index_;
+  static Mutex mutex_;
+  static ::std::array<int, 3> filter_allocated_;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalOutput.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalOutput.h
new file mode 100644
index 0000000..c04ef05
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalOutput.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 "DigitalSource.h"
+
+/**
+ * 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:
+	explicit DigitalOutput(uint32_t channel);
+	virtual ~DigitalOutput();
+	void Set(uint32_t value);
+	uint32_t GetChannel();
+	void Pulse(float length);
+	bool IsPulsing();
+	void SetPWMRate(float rate);
+	void EnablePWM(float initialDutyCycle);
+	void DisablePWM();
+	void UpdateDutyCycle(float dutyCycle);
+
+	// Digital Source Interface
+	virtual uint32_t GetChannelForRouting();
+	virtual uint32_t GetModuleForRouting();
+	virtual bool GetAnalogTriggerForRouting();
+
+private:
+	void InitDigitalOutput(uint32_t channel);
+
+	uint32_t m_channel;
+	void *m_pwmGenerator;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalSource.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalSource.h
new file mode 100644
index 0000000..491fa7c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DigitalSource.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+	virtual uint32_t GetChannelForRouting() = 0;
+	virtual uint32_t GetModuleForRouting() = 0;
+	virtual bool GetAnalogTriggerForRouting() = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DoubleSolenoid.h
new file mode 100644
index 0000000..5241f89
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DoubleSolenoid.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 "SolenoidBase.h"
+
+/**
+ * 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:
+	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();
+	bool IsFwdSolenoidBlackListed();
+	bool IsRevSolenoidBlackListed();
+
+private:
+	virtual void InitSolenoid();
+
+	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.
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DriverStation.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DriverStation.h
new file mode 100644
index 0000000..0397ca3
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/DriverStation.h
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "SensorBase.h"
+#include "RobotState.h"
+#include "Task.h"
+#include "HAL/HAL.hpp"
+
+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);
+	bool GetStickButton(uint32_t stick, uint8_t button);
+
+	int GetStickAxisCount(uint32_t stick);
+	int GetStickPOVCount(uint32_t stick);
+	int GetStickButtonCount(uint32_t stick);
+
+	bool IsEnabled();
+	bool IsDisabled();
+	bool IsAutonomous();
+	bool IsOperatorControl();
+	bool IsTest();
+	bool IsDSAttached();
+	bool IsNewControlData();
+	bool IsFMSAttached();
+	bool IsSysActive();
+	bool IsSysBrownedOut();
+
+	Alliance GetAlliance();
+	uint32_t GetLocation();
+	void WaitForData();
+	double GetMatchTime();
+	float GetBatteryVoltage();
+
+	/** 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 void InitTask(DriverStation *ds);
+	static DriverStation *m_instance;
+	void ReportJoystickUnpluggedError(std::string message);
+	void Run();
+
+	HALJoystickAxes m_joystickAxes[kJoystickPorts];
+	HALJoystickPOVs m_joystickPOVs[kJoystickPorts];
+	HALJoystickButtons m_joystickButtons[kJoystickPorts];
+	Task m_task;
+	SEMAPHORE_ID m_newControlData;
+	MULTIWAIT_ID m_packetDataAvailableMultiWait;
+	MUTEX_ID m_packetDataAvailableMutex;
+	MULTIWAIT_ID m_waitForDataSem;
+	MUTEX_ID m_waitForDataMutex;
+	bool m_userInDisabled;
+	bool m_userInAutonomous;
+	bool m_userInTeleop;
+	bool m_userInTest;
+	double m_nextMessageTime;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Encoder.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Encoder.h
new file mode 100644
index 0000000..45c4e5f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Encoder.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 "HAL/HAL.hpp"
+#include "CounterBase.h"
+#include "SensorBase.h"
+#include "Counter.h"
+#include "PIDSource.h"
+
+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:
+
+	Encoder(uint32_t aChannel, uint32_t bChannel, 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();
+	int32_t GetRaw();
+	int32_t GetEncodingScale();
+	void Reset();
+	double GetPeriod();
+	void SetMaxPeriod(double maxPeriod);
+	bool GetStopped();
+	bool GetDirection();
+	double GetDistance();
+	double GetRate();
+	void SetMinRate(double minRate);
+	void SetDistancePerPulse(double distancePerPulse);
+	void SetReverseDirection(bool reverseDirection);
+	void SetSamplesToAverage(int samplesToAverage);
+	int GetSamplesToAverage();
+	void SetPIDSourceParameter(PIDSourceParameter pidSource);
+	double PIDGet();
+
+	int32_t GetFPGAIndex()
+	{
+		return m_index;
+	}
+
+private:
+	void InitEncoder(bool _reverseDirection, EncodingType encodingType);
+	double DecodingScaleFactor();
+
+	DigitalSource *m_aSource;		// the A phase of the quad encoder
+	DigitalSource *m_bSource;		// the B phase of the quad encoder
+	bool m_allocatedASource;		// was the A source allocated locally?
+	bool m_allocatedBSource;		// was the B source allocated locally?
+	void* m_encoder;
+	int32_t m_index;				// The encoder's FPGA index.
+	double m_distancePerPulse;		// distance of travel for each encoder tick
+	Counter *m_counter;				// Counter object for 1x and 2x encoding
+	EncodingType m_encodingType;	// Encoding type
+	int32_t m_encodingScale;		// 1x, 2x, or 4x, per the encodingType
+	PIDSourceParameter m_pidSource;	// Encoder parameter that sources a PID controller
+
+  friend class DigitalGlitchFilter;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/GearTooth.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/GearTooth.h
new file mode 100644
index 0000000..a30e50d
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/GearTooth.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * 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(DigitalSource &source, bool directionSensitive = false);
+	virtual ~GearTooth();
+	void EnableDirectionSensing(bool directionSensitive);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Gyro.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Gyro.h
new file mode 100644
index 0000000..240d983
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Gyro.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+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.
+ */
+class Gyro : public SensorBase, public PIDSource
+{
+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 Gyro(int32_t channel);
+	explicit Gyro(AnalogInput *channel);
+	explicit Gyro(AnalogInput &channel);
+	virtual ~Gyro();
+	virtual float GetAngle();
+	virtual double GetRate();
+	void SetSensitivity(float voltsPerDegreePerSecond);
+	void SetDeadband(float volts);
+	void SetPIDSourceParameter(PIDSourceParameter pidSource);
+	virtual void Reset();
+	void InitGyro();
+
+	// PIDSource interface
+	double PIDGet();
+
+protected:
+	AnalogInput *m_analog;
+
+private:
+	float m_voltsPerDegreePerSecond;
+	float m_offset;
+	bool m_channelAllocated;
+	uint32_t m_center;
+	PIDSourceParameter m_pidSource;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/I2C.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/I2C.h
new file mode 100644
index 0000000..a90e4c6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/I2C.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Internal/HardwareHLReporting.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Internal/HardwareHLReporting.h
new file mode 100644
index 0000000..aa7ebc8
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Internal/HardwareHLReporting.h
@@ -0,0 +1,9 @@
+
+#include "HLUsageReporting.h"
+
+class HardwareHLReporting : public HLUsageReportingInterface
+{
+public:
+    virtual void ReportScheduler();
+    virtual void ReportSmartDashboard();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.h
new file mode 100644
index 0000000..fb0db4f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/InterruptableSensorBase.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 "HAL/HAL.hpp"
+#include "SensorBase.h"
+#include "Resource.h"
+
+class InterruptableSensorBase : public SensorBase
+{
+public:
+	enum WaitResult {
+		kTimeout = 0x0,
+		kRisingEdge = 0x1,
+		kFallingEdge = 0x100,
+		kBoth = 0x101,
+	};
+
+	InterruptableSensorBase();
+	virtual ~InterruptableSensorBase();
+	virtual uint32_t GetChannelForRouting() = 0;
+	virtual uint32_t GetModuleForRouting() = 0;
+	virtual bool GetAnalogTriggerForRouting() = 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;
+	uint32_t m_interruptIndex;
+	void AllocateInterrupts(bool watcher);
+
+	static Resource *m_interrupts;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/IterativeRobot.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/IterativeRobot.h
new file mode 100644
index 0000000..76a1cc0
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/IterativeRobot.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 "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 void Prestart();
+
+	virtual ~IterativeRobot();
+	IterativeRobot();
+
+private:
+	bool m_disabledInitialized;
+	bool m_autonomousInitialized;
+	bool m_teleopInitialized;
+	bool m_testInitialized;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Jaguar.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Jaguar.h
new file mode 100644
index 0000000..1cb7b69
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Jaguar.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+	virtual void Set(float value, uint8_t syncGroup = 0);
+	virtual float Get();
+	virtual void Disable();
+
+	virtual void PIDWrite(float output);
+
+private:
+	void InitJaguar();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Joystick.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Joystick.h
new file mode 100644
index 0000000..7ee06f6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Joystick.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "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;
+
+	explicit Joystick(uint32_t port);
+	Joystick(uint32_t port, uint32_t numAxisTypes, uint32_t numButtonTypes);
+	virtual ~Joystick();
+
+	uint32_t GetAxisChannel(AxisType axis);
+	void SetAxisChannel(AxisType axis, uint32_t channel);
+
+	virtual float GetX(JoystickHand hand = kRightHand);
+	virtual float GetY(JoystickHand hand = kRightHand);
+	virtual float GetZ();
+	virtual float GetTwist();
+	virtual float GetThrottle();
+	virtual float GetAxis(AxisType axis);
+	float GetRawAxis(uint32_t axis);
+
+	virtual bool GetTrigger(JoystickHand hand = kRightHand);
+	virtual bool GetTop(JoystickHand hand = kRightHand);
+	virtual bool GetBumper(JoystickHand hand = kRightHand);
+	virtual bool GetRawButton(uint32_t button);
+	virtual int GetPOV(uint32_t pov = 0);
+	bool GetButton(ButtonType button);
+	static Joystick* GetStickForPort(uint32_t port);
+
+	virtual float GetMagnitude();
+	virtual float GetDirectionRadians();
+	virtual float GetDirectionDegrees();
+
+	int GetAxisCount();
+	int GetButtonCount();
+	int GetPOVCount();
+	
+	void SetRumble(RumbleType type, float value);
+	void SetOutput(uint8_t outputNumber, bool value);
+	void SetOutputs(uint32_t value);
+
+private:
+	DISALLOW_COPY_AND_ASSIGN(Joystick);
+	void InitJoystick(uint32_t numAxisTypes, uint32_t numButtonTypes);
+
+	DriverStation *m_ds;
+	uint32_t m_port;
+	uint32_t *m_axes;
+	uint32_t *m_buttons;
+	uint32_t m_outputs;
+	uint16_t m_leftRumble;
+	uint16_t m_rightRumble;
+};
+
+#endif
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/MotorSafety.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/MotorSafety.h
new file mode 100644
index 0000000..ea7dfc4
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/MotorSafety.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+class MotorSafety
+{
+public:
+	virtual void SetExpiration(float timeout) = 0;
+	virtual float GetExpiration() = 0;
+	virtual bool IsAlive() = 0;
+	virtual void StopMotor() = 0;
+	virtual void SetSafetyEnabled(bool enabled) = 0;
+	virtual bool IsSafetyEnabled() = 0;
+	virtual void GetDescription(char *desc) = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.h
new file mode 100644
index 0000000..4434263
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/MotorSafetyHelper.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 "ErrorBase.h"
+#include "HAL/cpp/Synchronized.hpp"
+
+class MotorSafety;
+
+class MotorSafetyHelper : public ErrorBase
+{
+public:
+	MotorSafetyHelper(MotorSafety *safeObject);
+	~MotorSafetyHelper();
+	void Feed();
+	void SetExpiration(float expirationTime);
+	float GetExpiration();
+	bool IsAlive();
+	void Check();
+	void SetSafetyEnabled(bool enabled);
+	bool IsSafetyEnabled();
+	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
+	ReentrantMutex m_syncMutex;			// protect accesses to the state for this object
+	MotorSafety *m_safeObject;		// the object that is using the helper
+	MotorSafetyHelper *m_nextHelper; // next object in the list of MotorSafetyHelpers
+	static MotorSafetyHelper *m_headHelper; // the head of the list of MotorSafetyHelper objects
+	static ReentrantMutex m_listMutex;	// protect accesses to the list of helpers
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NIIMAQdx.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NIIMAQdx.h
new file mode 100644
index 0000000..4940063
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NIIMAQdx.h
@@ -0,0 +1,646 @@
+//==============================================================================

+//

+//  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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/AICalibration.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/AICalibration.h
new file mode 100644
index 0000000..b2f366c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/AICalibration.h
@@ -0,0 +1,19 @@
+

+#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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/CANInterfacePlugin.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/CANInterfacePlugin.h
new file mode 100644
index 0000000..f4c4064
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/CANInterfacePlugin.h
@@ -0,0 +1,80 @@
+// 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 NULL 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;

+

+	/**

+	 * 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;}

+};

+

+/**

+ * 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 NULL, unregister the current plugin.

+ */

+void FRC_NetworkCommunication_CANSessionMux_registerInterface(CANInterfacePlugin* interface);

+

+#endif // __CANInterfacePlugin_h__

diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/CANSessionMux.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/CANSessionMux.h
new file mode 100644
index 0000000..81f63c5
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/CANSessionMux.h
@@ -0,0 +1,63 @@
+// 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__

+

+#if defined(__vxworks)

+#include <vxWorks.h>

+#else

+#include <stdint.h>

+#endif

+

+#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

+

+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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/FRCComm.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/FRCComm.h
new file mode 100644
index 0000000..d542eca
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/FRCComm.h
@@ -0,0 +1,121 @@
+/*************************************************************

+ * 					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

+#if defined(__vxworks)

+#include <vxWorks.h>

+#define EXPORT_FUNC

+#else

+#include <stdint.h>

+#include <pthread.h>

+#define EXPORT_FUNC

+#endif

+#endif

+

+#define ERR_FRCSystem_NetCommNotResponding -44049

+

+enum AllianceStationID_t {

+	kAllianceStationID_red1,

+	kAllianceStationID_red2,

+	kAllianceStationID_red3,

+	kAllianceStationID_blue1,

+	kAllianceStationID_blue2,

+	kAllianceStationID_blue3,

+};

+

+struct ControlWord_t {

+#ifndef __vxworks

+	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;

+#else

+	uint32_t control_reserved : 26;

+	uint32_t dsAttached:1;

+	uint32_t fmsAttached:1;

+	uint32_t eStop : 1;

+	uint32_t test :1;

+	uint32_t autonomous : 1;

+	uint32_t enabled : 1;

+#endif

+};

+

+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

+# if defined (__vxworks)

+	void EXPORT_FUNC setNewDataSem(SEM_ID);

+# else

+	void EXPORT_FUNC setNewDataSem(pthread_mutex_t *);

+# endif

+#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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/LoadOut.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/LoadOut.h
new file mode 100644
index 0000000..fce88a2
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/LoadOut.h
@@ -0,0 +1,58 @@
+

+#ifndef __LoadOut_h__

+#define __LoadOut_h__

+

+#ifdef SIMULATION

+#include <vxWorks_compat.h>

+#define EXPORT_FUNC __declspec(dllexport) __cdecl

+#elif defined (__vxworks)

+#include <vxWorks.h>

+#define EXPORT_FUNC

+#else

+#include <stdint.h>

+#define EXPORT_FUNC

+#endif

+

+#define kMaxModuleNumber 2

+namespace nLoadOut

+{

+#if defined(__vxworks) || 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(__vxworks) || 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(__vxworks) || 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/UsageReporting.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/UsageReporting.h
new file mode 100644
index 0000000..918ac5a
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/UsageReporting.h
@@ -0,0 +1,139 @@
+

+#ifndef __UsageReporting_h__

+#define __UsageReporting_h__

+

+#ifdef SIMULATION

+#include <vxWorks_compat.h>

+#define EXPORT_FUNC __declspec(dllexport) __cdecl

+#elif defined (__vxworks)

+#include <vxWorks.h>

+#define EXPORT_FUNC

+#else

+#include <stdint.h>

+#include <stdlib.h>

+#define EXPORT_FUNC

+#endif

+

+#define kUsageReporting_version 1

+

+namespace nUsageReporting

+{

+    typedef enum

+    {

+        kResourceType_Controller,

+        kResourceType_Module,

+        kResourceType_Language,

+        kResourceType_CANPlugin,

+        kResourceType_Accelerometer,

+        kResourceType_ADXL345,

+        kResourceType_AnalogChannel,

+        kResourceType_AnalogTrigger,

+        kResourceType_AnalogTriggerOutput,

+        kResourceType_CANJaguar,

+        kResourceType_Compressor,

+        kResourceType_Counter,

+        kResourceType_Dashboard,

+        kResourceType_DigitalInput,

+        kResourceType_DigitalOutput,

+        kResourceType_DriverStationCIO,

+        kResourceType_DriverStationEIO,

+        kResourceType_DriverStationLCD,

+        kResourceType_Encoder,

+        kResourceType_GearTooth,

+        kResourceType_Gyro,

+        kResourceType_I2C,

+        kResourceType_Framework,

+        kResourceType_Jaguar,

+        kResourceType_Joystick,

+        kResourceType_Kinect,

+        kResourceType_KinectStick,

+        kResourceType_PIDController,

+        kResourceType_Preferences,

+        kResourceType_PWM,

+        kResourceType_Relay,

+        kResourceType_RobotDrive,

+        kResourceType_SerialPort,

+        kResourceType_Servo,

+        kResourceType_Solenoid,

+        kResourceType_SPI,

+        kResourceType_Task,

+        kResourceType_Ultrasonic,

+        kResourceType_Victor,

+        kResourceType_Button,

+        kResourceType_Command,

+        kResourceType_AxisCamera,

+        kResourceType_PCVideoServer,

+        kResourceType_SmartDashboard,

+        kResourceType_Talon,

+        kResourceType_HiTechnicColorSensor,

+        kResourceType_HiTechnicAccel,

+        kResourceType_HiTechnicCompass,

+		kResourceType_SRF08,

+    } tResourceType;

+

+    typedef enum

+    {

+        kLanguage_LabVIEW = 1,

+        kLanguage_CPlusPlus = 2,

+        kLanguage_Java = 3,

+        kLanguage_Python = 4,

+

+        kCANPlugin_BlackJagBridge = 1,

+        kCANPlugin_2CAN = 2,

+

+        kFramework_Iterative = 1,

+        kFramework_Simple = 2,

+

+        kRobotDrive_ArcadeStandard = 1,

+        kRobotDrive_ArcadeButtonSpin = 2,

+        kRobotDrive_ArcadeRatioCurve = 3,

+        kRobotDrive_Tank = 4,

+        kRobotDrive_MecanumPolar = 5,

+        kRobotDrive_MecanumCartesian = 6,

+

+        kDriverStationCIO_Analog = 1,

+        kDriverStationCIO_DigitalIn = 2,

+        kDriverStationCIO_DigitalOut = 3,

+

+        kDriverStationEIO_Acceleration = 1,

+        kDriverStationEIO_AnalogIn = 2,

+        kDriverStationEIO_AnalogOut = 3,

+        kDriverStationEIO_Button = 4,

+        kDriverStationEIO_LED = 5,

+        kDriverStationEIO_DigitalIn = 6,

+        kDriverStationEIO_DigitalOut = 7,

+        kDriverStationEIO_FixedDigitalOut = 8,

+        kDriverStationEIO_PWM = 9,

+        kDriverStationEIO_Encoder = 10,

+        kDriverStationEIO_TouchSlider = 11,

+

+        kADXL345_SPI = 1,

+        kADXL345_I2C = 2,

+

+        kCommand_Scheduler = 1,

+

+        kSmartDashboard_Instance = 1,

+    } tInstances;

+

+    /**

+     * Report the usage of a resource of interest.

+     * 

+     * @param resource one of the values in the tResourceType above (max value 51).

+     * @param instanceNumber an index that identifies the resource instance.

+     * @param context an optional additional context number for some cases (such as module number).  Set to 0 to omit.

+     * @param feature a string to be included describing features in use on a specific resource.  Setting the same resource more than once allows you to change the feature string.

+     */

+    uint32_t EXPORT_FUNC report(tResourceType resource, uint8_t instanceNumber, uint8_t context = 0, const char *feature = NULL);

+}

+

+#ifdef __cplusplus

+extern "C" {

+#endif

+

+    uint32_t EXPORT_FUNC FRC_NetworkCommunication_nUsageReporting_report(uint8_t resource, uint8_t instanceNumber, uint8_t context, const char *feature);

+

+#ifdef __cplusplus

+}

+#endif

+

+#endif // __UsageReporting_h__

diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/symModuleLink.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/symModuleLink.h
new file mode 100644
index 0000000..00867a5
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/NetworkCommunication/symModuleLink.h
@@ -0,0 +1,21 @@
+#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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/PWM.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/PWM.h
new file mode 100644
index 0000000..93785bb
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/PWM.h
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "SensorBase.h"
+
+/**
+ * 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:
+	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();
+	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()
+	{
+		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();
+	virtual void SetSpeed(float speed);
+	virtual float GetSpeed();
+
+	bool m_eliminateDeadband;
+	int32_t m_maxPwm;
+	int32_t m_deadbandMaxPwm;
+	int32_t m_centerPwm;
+	int32_t m_deadbandMinPwm;
+	int32_t m_minPwm;
+
+private:
+	void InitPWM(uint32_t channel);
+	uint32_t m_channel;
+	int32_t GetMaxPositivePwm()
+	{
+		return m_maxPwm;
+	}
+	int32_t GetMinPositivePwm()
+	{
+		return m_eliminateDeadband ? m_deadbandMaxPwm : m_centerPwm + 1;
+	}
+	int32_t GetCenterPwm()
+	{
+		return m_centerPwm;
+	}
+	int32_t GetMaxNegativePwm()
+	{
+		return m_eliminateDeadband ? m_deadbandMinPwm : m_centerPwm - 1;
+	}
+	int32_t GetMinNegativePwm()
+	{
+		return m_minPwm;
+	}
+	int32_t GetPositiveScaleFactor()
+	{
+		return GetMaxPositivePwm() - GetMinPositivePwm();
+	} ///< The scale for positive speeds.
+	int32_t GetNegativeScaleFactor()
+	{
+		return GetMaxNegativePwm() - GetMinNegativePwm();
+	} ///< The scale for negative speeds.
+	int32_t GetFullRangeScaleFactor()
+	{
+		return GetMaxPositivePwm() - GetMinNegativePwm();
+	} ///< The scale for positions.
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h
new file mode 100644
index 0000000..2094e08
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/PowerDistributionPanel.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the CAN PDP.
+ * The PDP must be at CAN Address 0.
+ * @author Thomas Clark
+ */
+class PowerDistributionPanel : public SensorBase {
+	public:
+		PowerDistributionPanel();
+		
+		double GetVoltage();
+		double GetTemperature();
+		double GetCurrent(uint8_t channel);
+		double GetTotalCurrent();
+		double GetTotalPower();
+		double GetTotalEnergy();
+		void ResetTotalEnergy();
+		void ClearStickyFaults();
+};
+
+#endif /* __WPILIB_POWER_DISTRIBUTION_PANEL_H__ */
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Relay.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Relay.h
new file mode 100644
index 0000000..7dc9cc9
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Relay.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * 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 SensorBase
+{
+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();
+
+private:
+	void InitRelay();
+
+	uint32_t m_channel;
+	Direction m_direction;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/RobotBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/RobotBase.h
new file mode 100644
index 0000000..90530be
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/RobotBase.h
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+	bool IsDisabled();
+	bool IsAutonomous();
+	bool IsOperatorControl();
+	bool IsTest();
+	bool IsNewDataAvailable();
+	static void startRobotTask(FUNCPTR factory);
+	static void robotTask(FUNCPTR factory, Task *task);
+	virtual void StartCompetition() = 0;
+	
+	static void robotSetup(RobotBase *robot);
+
+protected:
+	virtual ~RobotBase();
+	RobotBase();
+
+	virtual void Prestart();
+
+	Task *m_task;
+	DriverStation *m_ds;
+
+private:
+	static RobotBase *m_instance;
+
+	DISALLOW_COPY_AND_ASSIGN(RobotBase);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/RobotDrive.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/RobotDrive.h
new file mode 100644
index 0000000..e6cd031
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/RobotDrive.h
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "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(SpeedController *frontLeftMotor, SpeedController *rearLeftMotor,
+			SpeedController *frontRightMotor, SpeedController *rearRightMotor);
+	RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
+			SpeedController &frontRightMotor, SpeedController &rearRightMotor);
+	virtual ~RobotDrive();
+
+	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 SetExpiration(float timeout);
+	float GetExpiration();
+	bool IsAlive();
+	void StopMotor();
+	bool IsSafetyEnabled();
+	void SetSafetyEnabled(bool enabled);
+	void GetDescription(char *desc);
+
+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;
+
+	int32_t m_invertedMotors[kMaxNumberOfMotors];
+	float m_sensitivity;
+	double m_maxOutput;
+	bool m_deleteSpeedControllers;
+	SpeedController *m_frontLeftMotor;
+	SpeedController *m_frontRightMotor;
+	SpeedController *m_rearLeftMotor;
+	SpeedController *m_rearRightMotor;
+	MotorSafetyHelper *m_safetyHelper;
+
+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;
+	}
+	DISALLOW_COPY_AND_ASSIGN(RobotDrive);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SPI.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SPI.h
new file mode 100644
index 0000000..7c6d61f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SPI.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+
+	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);
+
+
+protected:
+	uint8_t m_port;
+	bool m_msbFirst;
+	bool m_sampleOnTrailing;
+	bool m_clk_idle_high;
+
+private:
+	void Init();
+
+	DISALLOW_COPY_AND_ASSIGN(SPI);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SafePWM.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SafePWM.h
new file mode 100644
index 0000000..bed5c21
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SafePWM.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+class MotorSafetyHelper;
+
+/**
+ * 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);
+	~SafePWM();
+
+	void SetExpiration(float timeout);
+	float GetExpiration();
+	bool IsAlive();
+	void StopMotor();
+	bool IsSafetyEnabled();
+	void SetSafetyEnabled(bool enabled);
+	void GetDescription(char *desc);
+
+	virtual void SetSpeed(float speed);
+private:
+	void InitSafePWM();
+	MotorSafetyHelper *m_safetyHelper;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SampleRobot.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SampleRobot.h
new file mode 100644
index 0000000..66842b6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/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() {}
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Servo.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Servo.h
new file mode 100644
index 0000000..25cfe1f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Servo.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * 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();
+	void SetAngle(float angle);
+	float GetAngle();
+	static float GetMaxAngle()
+	{
+		return kMaxServoAngle;
+	}
+	static float GetMinAngle()
+	{
+		return kMinServoAngle;
+	}
+
+private:
+	void InitServo();
+	float GetServoAngleRange()
+	{
+		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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Solenoid.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Solenoid.h
new file mode 100644
index 0000000..fe54ea2
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Solenoid.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 "SolenoidBase.h"
+
+/**
+ * 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:
+	explicit Solenoid(uint32_t channel);
+	Solenoid(uint8_t moduleNumber, uint32_t channel);
+	virtual ~Solenoid();
+	virtual void Set(bool on);
+	virtual bool Get();
+	bool IsBlackListed();
+
+private:
+	void InitSolenoid();
+
+	uint32_t m_channel; ///< The channel on the module to control.
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SolenoidBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SolenoidBase.h
new file mode 100644
index 0000000..d70823f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SolenoidBase.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* 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/cpp/Synchronized.hpp"
+
+/**
+ * SolenoidBase class is the common base class for the Solenoid and
+ * DoubleSolenoid classes.
+ */
+class SolenoidBase : public SensorBase
+{
+public:
+	virtual ~SolenoidBase();
+	uint8_t GetAll();
+
+	uint8_t GetPCMSolenoidBlackList();
+	bool GetPCMSolenoidVoltageStickyFault();
+	bool GetPCMSolenoidVoltageFault();
+	void ClearAllPCMStickyFaults();
+protected:
+	explicit SolenoidBase(uint8_t pcmID);
+	void Set(uint8_t value, uint8_t mask);
+	virtual void InitSolenoid() = 0;
+
+	uint32_t m_moduleNumber; ///< Slot number where the module is plugged into the chassis.
+	static Resource *m_allocated;
+
+private:
+	void* m_ports[kSolenoidChannels];
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SpeedController.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SpeedController.h
new file mode 100644
index 0000000..96d9266
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/SpeedController.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 "PIDOutput.h"
+
+/**
+ * Interface for speed controlling devices.
+ */
+class SpeedController : public PIDOutput
+{
+public:
+	virtual ~SpeedController() {}
+	/**
+	 * 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() = 0;
+	/**
+	 * Common interface for disabling a motor.
+	 */
+	virtual void Disable() = 0;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Talon.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Talon.h
new file mode 100644
index 0000000..6e11ccd
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Talon.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+	virtual void Set(float value, uint8_t syncGroup = 0);
+	virtual float Get();
+	virtual void Disable();
+
+	virtual void PIDWrite(float output);
+
+private:
+	void InitTalon();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/TalonSRX.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/TalonSRX.h
new file mode 100644
index 0000000..fe36b45
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/TalonSRX.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+	virtual void Set(float value, uint8_t syncGroup = 0);
+	virtual float Get();
+	virtual void Disable();
+
+	virtual void PIDWrite(float output);
+
+private:
+	void InitTalonSRX();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Ultrasonic.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Ultrasonic.h
new file mode 100644
index 0000000..e84e4ca
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Ultrasonic.h
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Task.h"
+#include "PIDSource.h"
+
+class Counter;
+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:
+	enum DistanceUnit
+	{
+		kInches = 0,
+		kMilliMeters = 1
+	};
+
+	Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units = kInches);
+	Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units = kInches);
+	Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, DistanceUnit units = kInches);
+	virtual ~Ultrasonic();
+
+	void Ping();
+	bool IsRangeValid();
+	static void SetAutomaticMode(bool enabling);
+	double GetRangeInches();
+	double GetRangeMM();
+	bool IsEnabled()
+	{
+		return m_enabled;
+	}
+	void SetEnabled(bool enable)
+	{
+		m_enabled = enable;
+	}
+
+	double PIDGet();
+	void SetDistanceUnits(DistanceUnit units);
+	DistanceUnit GetDistanceUnits();
+
+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 = 90;	///< 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 bool m_automaticEnabled; // automatic round robin mode
+	static SEMAPHORE_ID m_semaphore; // synchronize access to the list of sensors
+
+	DigitalInput *m_echoChannel;
+	DigitalOutput *m_pingChannel;
+	bool m_allocatedChannels;
+	bool m_enabled;
+	Counter *m_counter;
+	Ultrasonic *m_nextSensor;
+	DistanceUnit m_units;
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Victor.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Victor.h
new file mode 100644
index 0000000..9a83519
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Victor.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 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();
+	virtual void Set(float value, uint8_t syncGroup = 0);
+	virtual float Get();
+	virtual void Disable();
+
+	virtual void PIDWrite(float output);
+
+private:
+	void InitVictor();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/VictorSP.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/VictorSP.h
new file mode 100644
index 0000000..e2ba4dc
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/VictorSP.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+	virtual void Set(float value, uint8_t syncGroup = 0);
+	virtual float Get();
+	virtual void Disable();
+
+	virtual void PIDWrite(float output);
+
+private:
+	void InitVictorSP();
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/AxisCamera.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/AxisCamera.h
new file mode 100644
index 0000000..9792093
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/AxisCamera.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <mutex>
+
+#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();
+
+	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;
+	std::mutex m_captureMutex;
+
+	std::mutex m_imageDataMutex;
+	std::vector<uint8_t> m_imageData;
+	bool m_freshImage;
+
+	int m_brightness;
+	WhiteBalance m_whiteBalance;
+	int m_colorLevel;
+	ExposureControl m_exposureControl;
+	int m_exposurePriority;
+	int m_maxFPS;
+	Resolution m_resolution;
+	int m_compression;
+	Rotation m_rotation;
+	bool m_parametersDirty;
+	bool m_streamDirty;
+	std::mutex m_parametersMutex;
+
+	bool m_done;
+
+	void Capture();
+	void ReadImagesFromCamera();
+	bool WriteParameters();
+
+	int CreateCameraSocket(std::string const& requestString, bool setError);
+
+	DISALLOW_COPY_AND_ASSIGN(AxisCamera);
+};
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/BaeUtilities.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/BaeUtilities.h
new file mode 100644
index 0000000..a684b07
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/BaeUtilities.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/BinaryImage.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/BinaryImage.h
new file mode 100644
index 0000000..7c33f54
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/BinaryImage.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 $(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:
+	BinaryImage();
+	virtual ~BinaryImage();
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/ColorImage.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/ColorImage.h
new file mode 100644
index 0000000..595ed83
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/ColorImage.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.  */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ImageBase.h"
+#include "BinaryImage.h"
+#include "Threshold.h"
+
+class ColorImage : public ImageBase
+{
+public:
+	ColorImage(ImageType type);
+	virtual ~ColorImage();
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/FrcError.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/FrcError.h
new file mode 100644
index 0000000..9bd47f4
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/FrcError.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/HSLImage.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/HSLImage.h
new file mode 100644
index 0000000..71428aa
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/HSLImage.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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();
+};
+
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/ImageBase.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/ImageBase.h
new file mode 100644
index 0000000..ee5e895
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/ImageBase.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/MonoImage.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/MonoImage.h
new file mode 100644
index 0000000..e0e35eb
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/MonoImage.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

+

+#include "ImageBase.h"

+

+#include <vector>

+

+class MonoImage : public ImageBase

+{

+public:

+	MonoImage();

+	virtual ~MonoImage();

+

+	std::vector<EllipseMatch> *DetectEllipses(EllipseDescriptor *ellipseDescriptor,

+	                                          CurveOptions *curveOptions,

+	                                          ShapeDetectionOptions *shapeDetectionOptions,

+	                                          ROI *roi);

+	std::vector<EllipseMatch> * DetectEllipses(EllipseDescriptor *ellipseDescriptor);

+};

+

diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/RGBImage.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/RGBImage.h
new file mode 100644
index 0000000..0ef2d72
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/RGBImage.h
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+
+#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();
+};
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/Threshold.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/Threshold.h
new file mode 100644
index 0000000..9070cbf
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/Threshold.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/

+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/VisionAPI.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/VisionAPI.h
new file mode 100644
index 0000000..ce291bf
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/Vision/VisionAPI.h
@@ -0,0 +1,148 @@
+/*----------------------------------------------------------------------------*/
+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/WPILib.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/WPILib.h
new file mode 100644
index 0000000..d0f6f92
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/WPILib.h
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogAccelerometer.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 "Gyro.h"
+#include "interfaces/Accelerometer.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 "HAL/cpp/Synchronized.hpp"
+#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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h
new file mode 100644
index 0000000..37bd5e4
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h
@@ -0,0 +1,374 @@
+/**

+ * @brief CAN TALON SRX driver.

+ *

+ * The TALON SRX is designed to instrument all runtime signals periodically.  The default periods are chosen to support 16 TALONs

+ * with 10ms update rate for control (throttle or setpoint).  However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate

+ * The getters for these unsolicited signals are auto generated at the bottom of this module.

+ *

+ * Likewise most control signals are sent periodically using the fire-and-forget CAN API.

+ * The setters for these unsolicited signals are auto generated at the bottom of this module.

+ *

+ * Signals that are not available in an unsolicited fashion are the Close Loop gains.

+ * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once

+ * 	or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application.  These parameters are saved to flash so once they are

+ * 	loaded in the TALON, they will persist through power cycles and mode changes.

+ *

+ * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from

+ * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.

+ *

+ * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters.  Most likely

+ * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.

+ * If this API is used, be mindful of the CAN utilization reported in the driver station.

+ *

+ * Encoder position is measured in encoder edges.  Every edge is counted (similar to roboRIO 4X mode).

+ * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).

+ * Use SetFeedbackDeviceSelect to select which sensor type you need.  Once you do that you can use GetSensorPosition()

+ * and GetSensorVelocity().  These signals are updated on CANBus every 20ms (by default).

+ * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.

+ *

+ * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.

+ * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms.  This allows easy instrumentation

+ * for "in the pits" checking of all sensors regardless of modeselect.  The 100ms rate is overridable for teams who want to acquire sensor

+ * data for processing, not just instrumentation.  Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.

+ *

+ * Velocity is in position ticks / 100ms.

+ *

+ * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).

+ *  This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).

+ *

+ * Pos and velocity close loops are calc'd as

+ * 		err = target - posOrVel.

+ * 		iErr += err;

+ * 		if(   (IZone!=0)  and  abs(err) > IZone)

+ * 			ClearIaccum()

+ * 		output = P X err + I X iErr + D X dErr + F X target

+ * 		dErr = err - lastErr

+ *	P, I,and D gains are always positive. F can be negative.

+ *	Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.

+ *	Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.

+ *

+ * P gain is specified in throttle per error tick.  For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1

+ * 		ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

+ *

+ * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)

+ *  	for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.

+ *  	Close loop and integral accumulator runs every 1ms.

+ *

+ * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)

+ * 	per change of 1 unit (ADC or encoder) per ms.

+ *

+ * I Zone is specified in the same units as sensor position (ADC units or quadrature edges).  If pos/vel error is outside of

+ * 		this value, the integrated error will auto-clear...

+ * 		if(   (IZone!=0)  and  abs(err) > IZone)

+ * 			ClearIaccum()

+ * 		...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.

+ *

+ * CloseLoopRampRate is in throttle units per 1ms.  Set to zero to disable ramping.

+ * 		Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.

+ *

+ * auto generated using spreadsheet and WpiClassGen.csproj

+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967

+ */

+#ifndef CanTalonSRX_H_

+#define CanTalonSRX_H_

+#include "ctre.h"				//BIT Defines + Typedefs

+#include "CtreCanNode.h"

+#include <NetworkCommunication/CANSessionMux.h>	//CAN Comm

+#include <map>

+class CanTalonSRX : public CtreCanNode

+{

+private:

+

+	/** just in case user wants to modify periods of certain status frames.

+	 * 	Default the vars to match the firmware default. */

+	uint32_t _statusRateMs[4];

+	//---------------------- Vars for opening a CAN stream if caller needs signals that require soliciting */

+	uint32_t _can_h; 	//!< Session handle for catching response params.

+	int32_t _can_stat; //!< Session handle status.

+	struct tCANStreamMessage _msgBuff[20];

+	static int const kMsgCapacity	= 20;

+	typedef std::map<uint32_t, uint32_t> sigs_t;

+	sigs_t _sigs; //!< Catches signal updates that are solicited.  Expect this to be very few.

+	void OpenSessionIfNeedBe();

+	void ProcessStreamMessages();

+	/**

+	 * Send a one shot frame to set an arbitrary signal.

+	 * Most signals are in the control frame so avoid using this API unless you have to.

+	 * Use this api for...

+	 * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

+	 * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

+	 * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

+	 */

+	CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits);

+	/**

+	 * Checks cached CAN frames and updating solicited signals.

+	 */

+	CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits);

+public:

+	static const int kDefaultControlPeriodMs = 10; //!< default control update rate is 10ms.

+	CanTalonSRX(int deviceNumber = 0,int controlPeriodMs = kDefaultControlPeriodMs);

+	~CanTalonSRX();

+	void Set(double value);

+	/* mode select enumerations */

+	static const int kMode_DutyCycle = 0; //!< Demand is 11bit signed duty cycle [-1023,1023].

+	static const int kMode_PositionCloseLoop = 1; //!< Position PIDF.

+	static const int kMode_VelocityCloseLoop = 2; //!< Velocity PIDF.

+	static const int kMode_CurrentCloseLoop = 3; //!< Current close loop - not done.

+	static const int kMode_VoltCompen = 4; //!< Voltage Compensation Mode - not done.  Demand is fixed pt target 8.8 volts.

+	static const int kMode_SlaveFollower = 5; //!< Demand is the 6 bit Device ID of the 'master' TALON SRX.

+	static const int kMode_NoDrive = 15; //!< Zero the output (honors brake/coast) regardless of demand.  Might be useful if we need to change modes but can't atomically change all the signals we want in between.

+	/* limit switch enumerations */

+	static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1;

+	static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4;

+	static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5;

+	static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6;

+	static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7;

+	/* brake override enumerations */

+	static const int kBrakeOverride_UseDefaultsFromFlash = 0;

+	static const int kBrakeOverride_OverrideCoast = 1;

+	static const int kBrakeOverride_OverrideBrake = 2;

+	/* feedback device enumerations */

+	static const int kFeedbackDev_DigitalQuadEnc=0;

+	static const int kFeedbackDev_AnalogPot=2;

+	static const int kFeedbackDev_AnalogEncoder=3;

+	static const int kFeedbackDev_CountEveryRisingEdge=4;

+	static const int kFeedbackDev_CountEveryFallingEdge=5;

+	static const int kFeedbackDev_PosIsPulseWidth=8;

+	/* ProfileSlotSelect enumerations*/

+	static const int kProfileSlotSelect_Slot0 = 0;

+	static const int kProfileSlotSelect_Slot1 = 1;

+    /* status frame rate types */

+    static const int kStatusFrame_General = 0;

+    static const int kStatusFrame_Feedback = 1;

+    static const int kStatusFrame_Encoder = 2;

+    static const int kStatusFrame_AnalogTempVbat = 3;

+	/**

+	 * Signal enumeration for generic signal access.

+	 * Although every signal is enumerated, only use this for traffic that must be solicited.

+	 * Use the auto generated getters/setters at bottom of this header as much as possible.

+	 */

+	typedef enum _param_t{

+		eProfileParamSlot0_P=1,

+		eProfileParamSlot0_I=2,

+		eProfileParamSlot0_D=3,

+		eProfileParamSlot0_F=4,

+		eProfileParamSlot0_IZone=5,

+		eProfileParamSlot0_CloseLoopRampRate=6,

+		eProfileParamSlot1_P=11,

+		eProfileParamSlot1_I=12,

+		eProfileParamSlot1_D=13,

+		eProfileParamSlot1_F=14,

+		eProfileParamSlot1_IZone=15,

+		eProfileParamSlot1_CloseLoopRampRate=16,

+		eProfileParamSoftLimitForThreshold=21,

+		eProfileParamSoftLimitRevThreshold=22,

+		eProfileParamSoftLimitForEnable=23,

+		eProfileParamSoftLimitRevEnable=24,

+		eOnBoot_BrakeMode=31,

+		eOnBoot_LimitSwitch_Forward_NormallyClosed=32,

+		eOnBoot_LimitSwitch_Reverse_NormallyClosed=33,

+		eOnBoot_LimitSwitch_Forward_Disable=34,

+		eOnBoot_LimitSwitch_Reverse_Disable=35,

+		eFault_OverTemp=41,

+		eFault_UnderVoltage=42,

+		eFault_ForLim=43,

+		eFault_RevLim=44,

+		eFault_HardwareFailure=45,

+		eFault_ForSoftLim=46,

+		eFault_RevSoftLim=47,

+		eStckyFault_OverTemp=48,

+		eStckyFault_UnderVoltage=49,

+		eStckyFault_ForLim=50,

+		eStckyFault_RevLim=51,

+		eStckyFault_ForSoftLim=52,

+		eStckyFault_RevSoftLim=53,

+		eAppliedThrottle=61,

+		eCloseLoopErr=62,

+		eFeedbackDeviceSelect=63,

+		eRevMotDuringCloseLoopEn=64,

+		eModeSelect=65,

+		eProfileSlotSelect=66,

+		eRampThrottle=67,

+		eRevFeedbackSensor=68,

+		eLimitSwitchEn=69,

+		eLimitSwitchClosedFor=70,

+		eLimitSwitchClosedRev=71,

+		eSensorPosition=73,

+		eSensorVelocity=74,

+		eCurrent=75,

+		eBrakeIsEnabled=76,

+		eEncPosition=77,

+		eEncVel=78,

+		eEncIndexRiseEvents=79,

+		eQuadApin=80,

+		eQuadBpin=81,

+		eQuadIdxpin=82,

+		eAnalogInWithOv=83,

+		eAnalogInVel=84,

+		eTemp=85,

+		eBatteryV=86,

+		eResetCount=87,

+		eResetFlags=88,

+		eFirmVers=89,

+		eSettingsChanged=90,

+		eQuadFilterEn=91,	

+		ePidIaccum=93,

+	}param_t;

+    /*---------------------setters and getters that use the solicated param request/response-------------*//**

+     * Send a one shot frame to set an arbitrary signal.

+     * Most signals are in the control frame so avoid using this API unless you have to.

+     * Use this api for...

+     * -A motor controller profile signal eProfileParam_XXXs.  These are backed up in flash.  If you are gain-scheduling then call this periodically.

+     * -Default brake and limit switch signals... eOnBoot_XXXs.  Avoid doing this, use the override signals in the control frame.

+     * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.

+     */

+	CTR_Code SetParam(param_t paramEnum, double value);

+	/**

+	 * Asks TALON to immedietely respond with signal value.  This API is only used for signals that are not sent periodically.

+	 * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.

+	  * @param param to request.

+	 */

+	CTR_Code RequestParam(param_t paramEnum);

+	CTR_Code GetParamResponse(param_t paramEnum, double & value);

+	CTR_Code GetParamResponseInt32(param_t paramEnum, int & value);

+    /*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/

+	/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/

+	/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/

+	/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/

+	CTR_Code SetPgain(unsigned slotIdx,double gain);

+	CTR_Code SetIgain(unsigned slotIdx,double gain);

+	CTR_Code SetDgain(unsigned slotIdx,double gain);

+	CTR_Code SetFgain(unsigned slotIdx,double gain);

+	CTR_Code SetIzone(unsigned slotIdx,int zone);

+	CTR_Code SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate);

+	CTR_Code SetSensorPosition(int pos);

+	CTR_Code SetForwardSoftLimit(int forwardLimit);

+	CTR_Code SetReverseSoftLimit(int reverseLimit);

+	CTR_Code SetForwardSoftEnable(int enable);

+	CTR_Code SetReverseSoftEnable(int enable);

+	CTR_Code GetPgain(unsigned slotIdx,double & gain);

+	CTR_Code GetIgain(unsigned slotIdx,double & gain);

+	CTR_Code GetDgain(unsigned slotIdx,double & gain);

+	CTR_Code GetFgain(unsigned slotIdx,double & gain);

+	CTR_Code GetIzone(unsigned slotIdx,int & zone);

+	CTR_Code GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate);

+	CTR_Code GetForwardSoftLimit(int & forwardLimit);

+	CTR_Code GetReverseSoftLimit(int & reverseLimit);

+	CTR_Code GetForwardSoftEnable(int & enable);

+	CTR_Code GetReverseSoftEnable(int & enable);

+	/**

+	 * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for what's available.

+	 */

+	CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs);

+	/**

+	 * Clear all sticky faults in TALON.

+	 */

+	CTR_Code ClearStickyFaults();

+    /*------------------------ auto generated.  This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/

+    /*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/

+	CTR_Code GetFault_OverTemp(int &param);

+	CTR_Code GetFault_UnderVoltage(int &param);

+	CTR_Code GetFault_ForLim(int &param);

+	CTR_Code GetFault_RevLim(int &param);

+	CTR_Code GetFault_HardwareFailure(int &param);

+	CTR_Code GetFault_ForSoftLim(int &param);

+	CTR_Code GetFault_RevSoftLim(int &param);

+	CTR_Code GetStckyFault_OverTemp(int &param);

+	CTR_Code GetStckyFault_UnderVoltage(int &param);

+	CTR_Code GetStckyFault_ForLim(int &param);

+	CTR_Code GetStckyFault_RevLim(int &param);

+	CTR_Code GetStckyFault_ForSoftLim(int &param);

+	CTR_Code GetStckyFault_RevSoftLim(int &param);

+	CTR_Code GetAppliedThrottle(int &param);

+	CTR_Code GetCloseLoopErr(int &param);

+	CTR_Code GetFeedbackDeviceSelect(int &param);

+	CTR_Code GetModeSelect(int &param);

+	CTR_Code GetLimitSwitchEn(int &param);

+	CTR_Code GetLimitSwitchClosedFor(int &param);

+	CTR_Code GetLimitSwitchClosedRev(int &param);

+	CTR_Code GetSensorPosition(int &param);

+	CTR_Code GetSensorVelocity(int &param);

+	CTR_Code GetCurrent(double &param);

+	CTR_Code GetBrakeIsEnabled(int &param);

+	CTR_Code GetEncPosition(int &param);

+	CTR_Code GetEncVel(int &param);

+	CTR_Code GetEncIndexRiseEvents(int &param);

+	CTR_Code GetQuadApin(int &param);

+	CTR_Code GetQuadBpin(int &param);

+	CTR_Code GetQuadIdxpin(int &param);

+	CTR_Code GetAnalogInWithOv(int &param);

+	CTR_Code GetAnalogInVel(int &param);

+	CTR_Code GetTemp(double &param);

+	CTR_Code GetBatteryV(double &param);

+	CTR_Code GetResetCount(int &param);

+	CTR_Code GetResetFlags(int &param);

+	CTR_Code GetFirmVers(int &param);

+	CTR_Code SetDemand(int param);

+	CTR_Code SetOverrideLimitSwitchEn(int param);

+	CTR_Code SetFeedbackDeviceSelect(int param);

+	CTR_Code SetRevMotDuringCloseLoopEn(int param);

+	CTR_Code SetOverrideBrakeType(int param);

+	CTR_Code SetModeSelect(int param);

+	CTR_Code SetModeSelect(int modeSelect,int demand);

+	CTR_Code SetProfileSlotSelect(int param);

+	CTR_Code SetRampThrottle(int param);

+	CTR_Code SetRevFeedbackSensor(int param);

+};

+extern "C" {

+	void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs);

+	void c_TalonSRX_Destroy(void *handle);

+	CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value);

+	CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum);

+	CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value);

+	CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value);

+	CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs);

+	CTR_Code c_TalonSRX_ClearStickyFaults(void *handle);

+	CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param);

+	CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetTemp(void *handle, double *param);

+	CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param);

+	CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param);

+	CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param);

+	CTR_Code c_TalonSRX_SetDemand(void *handle, int param);

+	CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param);

+	CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param);

+	CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param);

+	CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param);

+	CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param);

+	CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param);

+	CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param);

+	CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param);

+}

+#endif

+

diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/CtreCanNode.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/CtreCanNode.h
new file mode 100644
index 0000000..59e0939
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/CtreCanNode.h
@@ -0,0 +1,116 @@
+#ifndef CtreCanNode_H_

+#define CtreCanNode_H_

+#include "ctre.h"				//BIT Defines + Typedefs

+#include <NetworkCommunication/CANSessionMux.h>	//CAN Comm

+#include <pthread.h>

+#include <map>

+#include <string.h> // memcpy

+#include <sys/time.h>

+class CtreCanNode

+{

+public:

+	CtreCanNode(UINT8 deviceNumber);

+    ~CtreCanNode();

+

+	UINT8 GetDeviceNumber()

+	{

+		return _deviceNumber;

+	}

+protected:

+

+

+	template <typename T> class txTask{

+		public:

+			uint32_t arbId;

+			T * toSend;

+			T * operator -> ()

+			{

+				return toSend;

+			}

+			T & operator*()

+			{

+				return *toSend;

+			}

+			bool IsEmpty()

+			{

+				if(toSend == 0)

+					return true;

+				return false;

+			}

+	};

+	template <typename T> class recMsg{

+		public:

+			uint32_t arbId;

+			uint8_t bytes[8];

+			CTR_Code err;

+			T * operator -> ()

+			{

+				return (T *)bytes;

+			}

+			T & operator*()

+			{

+				return *(T *)bytes;

+			}

+	};

+	UINT8 _deviceNumber;

+	void RegisterRx(uint32_t arbId);

+	void RegisterTx(uint32_t arbId, uint32_t periodMs);

+

+	CTR_Code GetRx(uint32_t arbId,uint8_t * dataBytes,uint32_t timeoutMs);

+	void FlushTx(uint32_t arbId);

+

+	template<typename T> txTask<T> GetTx(uint32_t arbId)

+	{

+		txTask<T> retval = {0};

+		txJobs_t::iterator i = _txJobs.find(arbId);

+		if(i != _txJobs.end()){

+			retval.arbId = i->second.arbId;

+			retval.toSend = (T*)i->second.toSend;

+		}

+		return retval;

+	}

+	template<class T> void FlushTx(T & par)

+	{

+		FlushTx(par.arbId);

+	}

+

+	template<class T> recMsg<T> GetRx(uint32_t arbId, uint32_t timeoutMs)

+	{

+		recMsg<T> retval;

+		retval.err = GetRx(arbId,retval.bytes, timeoutMs);

+		return retval;

+	}

+

+private:

+

+	class txJob_t {

+		public:

+			uint32_t arbId;

+			uint8_t toSend[8];

+			uint32_t periodMs;

+	};

+

+	class rxEvent_t{

+		public:

+			uint8_t bytes[8];

+			struct timespec time;

+			rxEvent_t()

+			{

+				bytes[0] = 0;

+				bytes[1] = 0;

+				bytes[2] = 0;

+				bytes[3] = 0;

+				bytes[4] = 0;

+				bytes[5] = 0;

+				bytes[6] = 0;

+				bytes[7] = 0;

+			}

+	};

+

+	typedef std::map<uint32_t,txJob_t> txJobs_t;

+	txJobs_t _txJobs;

+

+	typedef std::map<uint32_t,rxEvent_t> rxRxEvents_t;

+	rxRxEvents_t _rxRxEvents;

+};

+#endif

diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/ctre.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/ctre.h
new file mode 100644
index 0000000..c2d3f69
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/ctre/ctre.h
@@ -0,0 +1,50 @@
+#ifndef GLOBAL_H

+#define GLOBAL_H

+

+//Bit Defines

+#define BIT0 0x01

+#define BIT1 0x02

+#define BIT2 0x04

+#define BIT3 0x08

+#define BIT4 0x10

+#define BIT5 0x20

+#define BIT6 0x40

+#define BIT7 0x80

+#define BIT8  0x0100

+#define BIT9  0x0200

+#define BIT10 0x0400

+#define BIT11 0x0800

+#define BIT12 0x1000

+#define BIT13 0x2000

+#define BIT14 0x4000

+#define BIT15 0x8000

+

+//Signed

+typedef	signed char	INT8;

+typedef	signed short	INT16;

+typedef	signed int	INT32;

+typedef	signed long long INT64;

+

+//Unsigned

+typedef	unsigned char	UINT8;

+typedef	unsigned short	UINT16;

+typedef	unsigned int	UINT32;

+typedef	unsigned long long UINT64;

+

+//Other

+typedef	unsigned char	UCHAR;

+typedef unsigned short	USHORT;

+typedef	unsigned int	UINT;

+typedef unsigned long	ULONG;

+

+typedef enum {

+		CTR_OKAY,				//!< No Error - Function executed as expected

+		CTR_RxTimeout,			//!< CAN frame has not been received within specified period of time.

+		CTR_TxTimeout,			//!< Not used.

+		CTR_InvalidParamValue, 	//!< Caller passed an invalid param

+		CTR_UnexpectedArbId,	//!< Specified CAN Id is invalid.

+		CTR_TxFailed,			//!< Could not transmit the CAN frame.

+		CTR_SigNotUpdated,		//!< Have not received an value response for signal.

+}CTR_Code;

+

+#endif

diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/nivision.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/nivision.h
new file mode 100644
index 0000000..09bb984
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/nivision.h
@@ -0,0 +1,5345 @@
+/*============================================================================*/
+/*                        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    0
+    #else
+        #define NULL    ((void *)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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/pcre.h b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/pcre.h
new file mode 100644
index 0000000..f8ddcbf
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/include/pcre.h
@@ -0,0 +1,338 @@
+/*************************************************
+*       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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp
new file mode 100644
index 0000000..997cf59
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ADXL345_I2C.cpp
@@ -0,0 +1,103 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+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)
+{
+		//m_i2c = new I2C((I2C::Port)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);
+}
+
+/**
+ * Destructor.
+ */
+ADXL345_I2C::~ADXL345_I2C()
+{
+	//delete m_i2c;
+	//m_i2c = NULL;
+}
+
+/** {@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;
+	//if(m_i2c)
+	//{
+		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];
+	//if (m_i2c)
+	//{
+		Read(kDataRegister, sizeof(rawData), (uint8_t*)rawData);
+
+		data.XAxis = rawData[0] * kGsPerLSB;
+		data.YAxis = rawData[1] * kGsPerLSB;
+		data.ZAxis = rawData[2] * kGsPerLSB;
+	//}
+	return data;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp
new file mode 100644
index 0000000..77c793d
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ADXL345_SPI.cpp
@@ -0,0 +1,140 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SPI.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)
+{
+	m_port = port;
+	Init(range);
+}
+
+/**
+ * Internal common init function.
+ */
+void ADXL345_SPI::Init(Range range)
+{
+		m_spi = new SPI(m_port);
+		m_spi->SetClockRate(500000);
+		m_spi->SetMSBFirst();
+		m_spi->SetSampleDataOnFalling();
+		m_spi->SetClockActiveLow();
+		m_spi->SetChipSelectActiveHigh();
+
+		uint8_t commands[2];
+		// Turn on the measurements
+		commands[0] = kPowerCtlRegister;
+		commands[1] = kPowerCtl_Measure;
+		m_spi->Transaction(commands, commands, 2);
+
+		SetRange(range);
+
+		HALReport(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_SPI);
+}
+
+/**
+ * Destructor.
+ */
+ADXL345_SPI::~ADXL345_SPI()
+{
+	delete m_spi;
+	m_spi = NULL;
+}
+
+/** {@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);
+	m_spi->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)
+{
+	int16_t rawAccel = 0;
+	if(m_spi)
+	{
+		uint8_t buffer[3];
+		uint8_t command[3] = {0,0,0};
+		command[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister) + (uint8_t)axis;
+		m_spi->Transaction(command, buffer, 3);
+
+		// Sensor is little endian... swap bytes
+		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];
+	if (m_spi)
+	{
+		// Select the data address.
+		dataBuffer[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister);
+		m_spi->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;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.cpp
new file mode 100644
index 0000000..15edf4b
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogAccelerometer.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 "AnalogAccelerometer.h"
+//#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Common function for initializing the accelerometer.
+ */
+void AnalogAccelerometer::InitAccelerometer()
+{
+	m_voltsPerG = 1.0;
+	m_zeroGVoltage = 2.5;
+	HALReport(HALUsageReporting::kResourceType_Accelerometer, m_AnalogInput->GetChannel());
+}
+
+/**
+ * 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 = new AnalogInput(channel);
+	m_allocatedChannel = true;
+	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)
+{
+	if (channel == NULL)
+	{
+		wpi_setWPIError(NullParameter);
+	}
+	else
+	{
+		m_AnalogInput = channel;
+		InitAccelerometer();
+	}
+	m_allocatedChannel = false;
+}
+
+/**
+ * Delete the analog components used for the accelerometer.
+ */
+AnalogAccelerometer::~AnalogAccelerometer()
+{
+	if (m_allocatedChannel)
+	{
+		delete m_AnalogInput;
+	}
+}
+
+/**
+ * Return the acceleration in Gs.
+ *
+ * The acceleration is returned units of Gs.
+ *
+ * @return The current acceleration of the sensor in Gs.
+ */
+float AnalogAccelerometer::GetAcceleration()
+{
+	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();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogInput.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogInput.cpp
new file mode 100644
index 0000000..bf19a9c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogInput.cpp
@@ -0,0 +1,414 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+static Resource *inputs = NULL;
+
+const uint8_t AnalogInput::kAccumulatorModuleNumber;
+const uint32_t AnalogInput::kAccumulatorNumChannels;
+const uint32_t AnalogInput::kAccumulatorChannels[] = {0, 1};
+
+/**
+ * Common initialization.
+ */
+void AnalogInput::InitAnalogInput(uint32_t channel)
+{
+	char buf[64];
+	Resource::CreateResourceObject(&inputs, kAnalogInputs);
+
+	if (!checkAnalogInputChannel(channel))
+	{
+		snprintf(buf, 64, "analog input %d", channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+
+	snprintf(buf, 64, "Analog Input %d", channel);
+	if (inputs->Allocate(channel, buf) == ~0ul)
+	{
+		CloneError(inputs);
+		return;
+	}
+
+	m_channel = channel;
+
+	void* port = getPort(channel);
+	int32_t status = 0;
+	m_port = initializeAnalogInputPort(port, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+	HALReport(HALUsageReporting::kResourceType_AnalogChannel, channel);
+}
+
+/**
+ * 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)
+{
+	InitAnalogInput(channel);
+}
+
+/**
+ * Channel destructor.
+ */
+AnalogInput::~AnalogInput()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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 Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void AnalogInput::GetAccumulatorOutput(int64_t *value, uint32_t *count)
+{
+	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();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp
new file mode 100644
index 0000000..6cdfaa6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogOutput.cpp
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "AnalogOutput.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+static Resource *outputs = NULL;
+
+void AnalogOutput::InitAnalogOutput(uint32_t channel) {
+    Resource::CreateResourceObject(&outputs, kAnalogOutputs);
+
+    char buf[64];
+
+    if(!checkAnalogOutputChannel(channel))
+    {
+        snprintf(buf, 64, "analog input %d", channel);
+        wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+        return;
+    }
+
+    if(outputs->Allocate(channel, buf) == ~0ul)
+    {
+        CloneError(outputs);
+        return;
+    }
+
+    m_channel = channel;
+
+    void* port = getPort(m_channel);
+    int32_t status = 0;
+    m_port = initializeAnalogOutputPort(port, &status);
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+    HALReport(HALUsageReporting::kResourceType_AnalogChannel, m_channel, 0);
+}
+
+/**
+ * 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) {
+    InitAnalogOutput(channel);
+}
+
+/**
+ * Destructor. Frees analog output resource
+ */
+AnalogOutput::~AnalogOutput() {
+    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() {
+    int32_t status = 0;
+    float voltage = getAnalogOutput(m_port, &status);
+
+    wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+    return voltage;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp
new file mode 100644
index 0000000..0ba7dbd
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogPotentiometer.cpp
@@ -0,0 +1,73 @@
+
+#include "AnalogPotentiometer.h"
+#include "ControllerPower.h"
+
+/**
+ * Common initialization code called by all constructors.
+ */
+void AnalogPotentiometer::initPot(AnalogInput *input, double fullRange, double offset) {
+    m_fullRange = fullRange;
+    m_offset = offset;
+    m_analog_input = input;
+}
+
+/**
+ * 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_init_analog_input = true;
+    initPot(new AnalogInput(channel), fullRange, 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_init_analog_input = false;
+    initPot(input, fullRange, offset);
+}
+
+/**
+ * Construct an Analog Potentiometer object from an existing Analog Input reference.
+ * @param channel The existing Analog Input reference 
+ * @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_init_analog_input = false;
+    initPot(&input, fullRange, offset);
+}
+
+/**
+ * Destructor. Releases the Analog Input resource if it was allocated by this object
+ */
+AnalogPotentiometer::~AnalogPotentiometer() {
+  if(m_init_analog_input){
+    delete m_analog_input;
+    m_init_analog_input = false;
+  }
+}
+
+/**
+ * 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() {
+    return (m_analog_input->GetVoltage() / ControllerPower::GetVoltage5V()) * m_fullRange + m_offset;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current reading.
+ */
+double AnalogPotentiometer::PIDGet() {
+    return Get();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp
new file mode 100644
index 0000000..61cd014
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogTrigger.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+/**
+ * Initialize an analog trigger from a channel.
+ */
+void AnalogTrigger::InitTrigger(uint32_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));
+	m_index = index;
+
+	HALReport(HALUsageReporting::kResourceType_AnalogTrigger, channel);
+}
+
+/**
+ * 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)
+{
+	InitTrigger(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)
+{
+	InitTrigger(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()
+{
+	if (StatusIsFatal()) return ~0ul;
+	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.
+ */
+AnalogTriggerOutput *AnalogTrigger::CreateOutput(AnalogTriggerType type)
+{
+	if (StatusIsFatal()) return NULL;
+	return new AnalogTriggerOutput(this, type);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp
new file mode 100644
index 0000000..65febfa
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/AnalogTriggerOutput.cpp
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.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(AnalogTrigger *trigger, AnalogTriggerType outputType)
+	: m_trigger (trigger)
+	, m_outputType (outputType)
+{
+	HALReport(HALUsageReporting::kResourceType_AnalogTriggerOutput, trigger->GetIndex(), outputType);
+}
+
+AnalogTriggerOutput::~AnalogTriggerOutput()
+{
+	if (m_interrupt != NULL)
+	{
+		int32_t status = 0;
+		cleanInterrupts(m_interrupt, &status);
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+		m_interrupt = NULL;
+		m_interrupts->Free(m_interruptIndex);
+	}
+}
+
+/**
+ * Get the state of the analog trigger output.
+ * @return The state of the analog trigger output.
+ */
+bool AnalogTriggerOutput::Get()
+{
+  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()
+{
+	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()
+{
+	return 0;
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+bool AnalogTriggerOutput::GetAnalogTriggerForRouting()
+{
+	return true;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp
new file mode 100644
index 0000000..57f7b57
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/BuiltInAccelerometer.cpp
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * Constructor.
+ * @param range The range the accelerometer will measure
+ */
+BuiltInAccelerometer::BuiltInAccelerometer(Range range)
+{
+	SetRange(range);
+
+	HALReport(HALUsageReporting::kResourceType_Accelerometer, 0, 0, "Built-in accelerometer");
+}
+
+BuiltInAccelerometer::~BuiltInAccelerometer()
+{
+}
+
+/** {@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();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/CANJaguar.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/CANJaguar.cpp
new file mode 100644
index 0000000..61b22a5
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/CANJaguar.cpp
@@ -0,0 +1,2084 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "CAN/can_proto.h"
+//#include "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+#include <cstdio>
+#include <cassert>
+#include <cstring>
+
+/* 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 Resource *allocated = NULL;
+
+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 (uint8_t i=0; i<(sizeof(kTrustedMessages)/sizeof(kTrustedMessages[0])); i++)
+	{
+		if ((kFullMessageIDMask & messageID) == kTrustedMessages[i])
+		{
+			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 = new MotorSafetyHelper(this);
+
+	m_value = 0.0f;
+	m_speedReference = LM_REF_NONE;
+	m_positionReference = LM_REF_NONE;
+	m_p = 0.0;
+	m_i = 0.0;
+	m_d = 0.0;
+	m_busVoltage = 0.0f;
+	m_outputVoltage = 0.0f;
+	m_outputCurrent = 0.0f;
+	m_temperature = 0.0f;
+	m_position = 0.0;
+	m_speed = 0.0;
+	m_limits = 0x00;
+	m_faults = 0x0000;
+	m_firmwareVersion = 0;
+	m_hardwareVersion = 0;
+	m_neutralMode = kNeutralMode_Jumper;
+	m_encoderCodesPerRev = 0;
+	m_potentiometerTurns = 0;
+	m_limitMode = kLimitMode_SwitchInputsOnly;
+	m_forwardLimit = 0.0;
+	m_reverseLimit = 0.0;
+	m_maxOutputVoltage = 30.0;
+	m_voltageRampRate = 0.0;
+	m_faultTime = 0.0f;
+
+	// Parameters only need to be verified if they are set
+	m_controlModeVerified = false; // Needs to be verified because it's set in the constructor
+	m_speedRefVerified = true;
+	m_posRefVerified = true;
+	m_pVerified = true;
+	m_iVerified = true;
+	m_dVerified = true;
+	m_neutralModeVerified = true;
+	m_encoderCodesPerRevVerified = true;
+	m_potentiometerTurnsVerified = true;
+	m_limitModeVerified = true;
+	m_forwardLimitVerified = true;
+	m_reverseLimitVerified = true;
+	m_maxOutputVoltageVerified = true;
+	m_voltageRampRateVerified = true;
+	m_faultTimeVerified = true;
+
+	m_receivedStatusMessage0 = false;
+	m_receivedStatusMessage1 = false;
+	m_receivedStatusMessage2 = false;
+
+	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)
+	{
+		char buf[256];
+		snprintf(buf, 256, "device number \"%d\" must be between 1 and 63", m_deviceNumber);
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, buf);
+		return;
+	}
+
+	if (StatusIsFatal())
+		return;
+
+	// 3330 was the first shipping RDK firmware version for the Jaguar
+	if (m_firmwareVersion >= 3330 || m_firmwareVersion < 108)
+	{
+		char buf[256];
+		if (m_firmwareVersion < 3330)
+		{
+			snprintf(buf, 256, "Jag #%d firmware (%d) is too old (must be at least version 108 of the FIRST approved firmware)", m_deviceNumber, m_firmwareVersion);
+		}
+		else
+		{
+			snprintf(buf, 256, "Jag #%d firmware (%d) is not FIRST approved (must be at least version 108 of the FIRST approved firmware)", m_deviceNumber, m_firmwareVersion);
+		}
+		wpi_setWPIErrorWithContext(JaguarVersionError, buf);
+		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);
+}
+
+/**
+ * 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)
+	, m_maxOutputVoltage (kApproxBusVoltage)
+	, m_safetyHelper (NULL)
+{
+	char buf[64];
+	snprintf(buf, 64, "CANJaguar device number %d", m_deviceNumber);
+	Resource::CreateResourceObject(&allocated, 63);
+
+	if (allocated->Allocate(m_deviceNumber-1, buf) == ~0ul)
+	{
+		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, NULL, 0, CAN_SEND_PERIOD_STOP_REPEATING, &status);
+	else if(m_controlMode == kSpeed)
+		FRC_NetworkCommunication_CANSessionMux_sendMessage(m_deviceNumber | LM_API_SPD_T_SET, NULL, 0, CAN_SEND_PERIOD_STOP_REPEATING, &status);
+	else if(m_controlMode == kPosition)
+		FRC_NetworkCommunication_CANSessionMux_sendMessage(m_deviceNumber | LM_API_POS_T_SET, NULL, 0, CAN_SEND_PERIOD_STOP_REPEATING, &status);
+	else if(m_controlMode == kCurrent)
+		FRC_NetworkCommunication_CANSessionMux_sendMessage(m_deviceNumber | LM_API_ICTRL_T_SET, NULL, 0, CAN_SEND_PERIOD_STOP_REPEATING, &status);
+	else if(m_controlMode == kVoltage)
+		FRC_NetworkCommunication_CANSessionMux_sendMessage(m_deviceNumber | LM_API_VCOMP_T_SET, NULL, 0, CAN_SEND_PERIOD_STOP_REPEATING, &status);
+
+	delete m_safetyHelper;
+	m_safetyHelper = NULL;
+}
+
+/**
+ * @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, outputValue);
+			}
+			break;
+		case kSpeed:
+			{
+				messageID = LM_API_SPD_T_SET;
+				dataSize = packFXP16_16(dataBuffer, 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, 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()
+{
+	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 swapped = swap16(intValue);
+  memcpy(buffer, &swapped, sizeof(int16_t));
+	return sizeof(int16_t);
+}
+
+uint8_t CANJaguar::packFXP8_8(uint8_t *buffer, double value)
+{
+	int16_t intValue = (int16_t)(value * 256.0);
+  int16_t swapped = swap16(intValue);
+  memcpy(buffer, &swapped, sizeof(int16_t));
+	return sizeof(int16_t);
+}
+
+uint8_t CANJaguar::packFXP16_16(uint8_t *buffer, double value)
+{
+	int32_t intValue = (int32_t)(value * 65536.0);
+  int32_t swapped = swap32(intValue);
+  memcpy(buffer, &swapped, sizeof(int32_t));
+	return sizeof(int32_t);
+}
+
+uint8_t CANJaguar::packint16_t(uint8_t *buffer, int16_t value)
+{
+  int16_t swapped = swap16(value);
+  memcpy(buffer, &swapped, sizeof(int16_t));
+	return sizeof(int16_t);
+}
+
+uint8_t CANJaguar::packint32_t(uint8_t *buffer, int32_t value)
+{
+  int32_t swapped = swap32(value);
+  memcpy(buffer, &swapped, sizeof(int32_t));
+	return sizeof(int32_t);
+}
+
+double CANJaguar::unpackPercentage(uint8_t *buffer)
+{
+	int16_t value;
+  memcpy(&value, buffer, sizeof(value));
+	value = swap16(value);
+	return value / 32767.0;
+}
+
+double CANJaguar::unpackFXP8_8(uint8_t *buffer)
+{
+	int16_t value;
+  memcpy(&value, buffer, sizeof(value));
+	value = swap16(value);
+	return value / 256.0;
+}
+
+double CANJaguar::unpackFXP16_16(uint8_t *buffer)
+{
+	int32_t value;
+  memcpy(&value, buffer, sizeof(value));
+	value = swap32(value);
+	return value / 65536.0;
+}
+
+int16_t CANJaguar::unpackint16_t(uint8_t *buffer)
+{
+	int16_t value;
+  memcpy(&value, buffer, sizeof(value));
+	return swap16(value);
+}
+
+int32_t CANJaguar::unpackint32_t(uint8_t *buffer)
+{
+	int32_t value;
+  memcpy(&value, buffer, sizeof(value));
+	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, NULL, 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)
+{
+	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() {
+	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_busVoltage    = unpackFXP8_8(data);
+		m_outputVoltage = unpackPercentage(data + 2) * m_busVoltage;
+		m_outputCurrent = unpackFXP8_8(data + 4);
+		m_temperature   = unpackFXP8_8(data + 6);
+
+		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_position = unpackFXP16_16(data);
+		m_speed    = unpackFXP16_16(data + 4);
+
+		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_limits = data[0];
+		m_faults = data[1];
+
+		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;
+
+		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;
+
+		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;
+
+		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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	return m_controlMode;
+}
+
+/**
+ * Get the voltage at the battery input terminals of the Jaguar.
+ *
+ * @return The bus voltage in volts.
+ */
+float CANJaguar::GetBusVoltage()
+{
+	updatePeriodicStatus();
+
+	return m_busVoltage;
+}
+
+/**
+ * Get the voltage being output from the motor terminals of the Jaguar.
+ *
+ * @return The output voltage in volts.
+ */
+float CANJaguar::GetOutputVoltage()
+{
+	updatePeriodicStatus();
+
+	return m_outputVoltage;
+}
+
+/**
+ * Get the current through the motor terminals of the Jaguar.
+ *
+ * @return The output current in amps.
+ */
+float CANJaguar::GetOutputCurrent()
+{
+	updatePeriodicStatus();
+
+	return m_outputCurrent;
+}
+
+/**
+ * Get the internal temperature of the Jaguar.
+ *
+ * @return The temperature of the Jaguar in degrees Celsius.
+ */
+float CANJaguar::GetTemperature()
+{
+	updatePeriodicStatus();
+
+	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()
+{
+	updatePeriodicStatus();
+
+	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()
+{
+	updatePeriodicStatus();
+
+	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()
+{
+	updatePeriodicStatus();
+
+	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()
+{
+	updatePeriodicStatus();
+
+	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()
+{
+	updatePeriodicStatus();
+
+	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()
+{
+	return m_firmwareVersion;
+}
+
+/**
+ * Get the version of the Jaguar hardware.
+ *
+ * @return The hardware version. 1: Jaguar,  2: Black Jaguar
+ */
+uint8_t CANJaguar::GetHardwareVersion()
+{
+	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];
+	uint8_t dataSize;
+
+	// Set the codes per revolution mode
+	dataSize = packint16_t(dataBuffer, codesPerRev);
+	sendMessage(LM_API_CFG_ENC_LINES, dataBuffer, dataSize);
+
+	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()
+{
+	if (!m_safetyHelper) return 0.0;
+	return m_safetyHelper->GetExpiration();
+}
+
+bool CANJaguar::IsAlive()
+{
+	if (!m_safetyHelper) return false;
+	return m_safetyHelper->IsAlive();
+}
+
+bool CANJaguar::IsSafetyEnabled()
+{
+	if (!m_safetyHelper) return false;
+	return m_safetyHelper->IsSafetyEnabled();
+}
+
+void CANJaguar::SetSafetyEnabled(bool enabled)
+{
+	if (m_safetyHelper) m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void CANJaguar::GetDescription(char *desc)
+{
+	sprintf(desc, "CANJaguar ID %d", m_deviceNumber);
+}
+
+uint8_t CANJaguar::GetDeviceID()
+{
+	return m_deviceNumber;
+}
+
+/**
+ * Common interface for stopping the motor
+ * Part of the MotorSafety interface
+ *
+ * @deprecated Call DisableControl instead.
+ */
+void CANJaguar::StopMotor()
+{
+	DisableControl();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/CANTalon.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/CANTalon.cpp
new file mode 100644
index 0000000..83cf5d2
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/CANTalon.cpp
@@ -0,0 +1,1231 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ctre/CanTalonSRX.h"
+#include <unistd.h> // usleep
+/**
+ * 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))
+  , m_profile(0)
+  , m_controlEnabled(true)
+  , m_controlMode(kPercentVbus)
+  , m_setPoint(0)
+{
+  ApplyControlMode(m_controlMode);
+  m_impl->SetProfileSlotSelect(m_profile);
+}
+/**
+ * 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)) /* bounded underneath to be within [1 ms,95 ms] */
+	, m_safetyHelper(new MotorSafetyHelper(this))
+  , m_profile(0)
+  , m_controlEnabled(true)
+  , m_controlMode(kPercentVbus)
+  , m_setPoint(0)
+{
+  ApplyControlMode(m_controlMode);
+  m_impl->SetProfileSlotSelect(m_profile);
+}
+CANTalon::~CANTalon() {
+	delete m_impl;
+	delete m_safetyHelper;
+}
+
+/**
+* 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");
+	}
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+float CANTalon::Get()
+{
+  int value;
+  switch(m_controlMode) {
+    case kVoltage:
+      return GetOutputVoltage();
+    case kCurrent:
+      return GetOutputCurrent();
+    case kSpeed:
+      m_impl->GetSensorVelocity(value);
+      return value;
+    case kPosition:
+      m_impl->GetSensorPosition(value);
+      return value;
+    case kPercentVbus:
+    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, outputValue is in volts.
+ * In Current mode, outputValue is in amperes.
+ * In Speed mode, outputValue is in position change / 10ms.
+ * In Position mode, outputValue is in encoder ticks or an analog value,
+ *   depending on the sensor.
+ *
+ * @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;
+    CTR_Code status = CTR_OKAY;
+    switch(m_controlMode) {
+      case CANSpeedController::kPercentVbus:
+        {
+          m_impl->Set(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(value * 256);
+          status = m_impl->SetDemand(volts);
+        }
+        break;
+      case CANSpeedController::kSpeed:
+        status = m_impl->SetDemand(value);
+        break;
+      case CANSpeedController::kPosition:
+        status = m_impl->SetDemand(value);
+        break;
+      default:
+        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));
+    }
+
+  }
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::Disable()
+{
+  // Until Modes other than throttle work, just disable by setting throttle to 0.0.
+  m_impl->SetModeSelect((int)CANTalon::kDisabled);
+  m_controlEnabled = false;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::EnableControl() {
+  SetControlMode(m_controlMode);
+  m_controlEnabled = true;
+}
+
+/**
+ * @return Whether the Talon is currently enabled.
+ */
+bool CANTalon::IsControlEnabled() {
+  return m_controlEnabled;
+}
+
+/**
+ * @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));
+	}
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * @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));
+	}
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * @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));
+	}
+}
+/**
+ *
+ * @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));
+	}
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * 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);
+}
+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 device)
+{
+	CTR_Code status = m_impl->SetFeedbackDeviceSelect((int)device);
+	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));
+	}
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ * @see SelectProfileSlot to choose between the two sets of gains.
+ */
+double CANTalon::GetP()
+{
+  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()
+{
+  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()
+{
+  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()
+{
+  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()
+{
+  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() {
+  return m_setPoint;
+}
+
+/**
+ * Returns the voltage coming in from the battery.
+ *
+ * @return The input voltage in vols.
+ */
+float CANTalon::GetBusVoltage()
+{
+  double voltage;
+  CTR_Code status = m_impl->GetBatteryV(voltage);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+  return voltage;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+float CANTalon::GetOutputVoltage()
+{
+  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;
+}
+
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+float CANTalon::GetOutputCurrent()
+{
+  double current;
+
+  CTR_Code status = m_impl->GetCurrent(current);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+
+	return current;
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+float CANTalon::GetTemperature()
+{
+  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)
+{
+	m_impl->SetSensorPosition(pos);
+}
+/**
+ * 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()
+{
+  int postition;
+
+  CTR_Code status = m_impl->GetSensorPosition(postition);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+	return (double)postition;
+}
+/**
+ * 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));
+	}
+}
+
+/**
+ * Returns the current error in the controller.
+ *
+ * @return the difference between the setpoint and the sensor value.
+ */
+int CANTalon::GetClosedLoopError() {
+  int error;
+  CTR_Code status = m_impl->GetCloseLoopErr(error);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+  return error;
+}
+
+/**
+ * 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()
+{
+  int speed;
+  // TODO convert from int to appropriate units (or at least document it).
+
+  CTR_Code status = m_impl->GetSensorVelocity(speed);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+	return (double)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()
+{
+  int position;
+  CTR_Code status = m_impl->GetAnalogInWithOv(position);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+  return position;
+}
+/**
+ * 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()
+{
+    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()
+{
+  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()
+{
+  int position;
+  CTR_Code status = m_impl->GetEncPosition(position);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+  return position;
+}
+
+/**
+ * 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()
+{
+  int vel;
+  CTR_Code status = m_impl->GetEncVel(vel);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+  return vel;
+}
+/**
+ * @return IO level of QUADA pin.
+ */
+int CANTalon::GetPinStateQuadA()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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));
+	}
+}
+/**
+ * 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()
+{
+	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()
+{
+	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()
+{
+  int brakeEn = 0;
+  CTR_Code status = m_impl->GetBrakeIsEnabled(brakeEn);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+	return brakeEn;
+}
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigEncoderCodesPerRev(uint16_t codesPerRev)
+{
+	/* TALON SRX does not scale units, they are raw from the sensor.  Unit scaling can be done in API or by caller */
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigPotentiometerTurns(uint16_t turns)
+{
+	/* TALON SRX does not scale units, they are raw from the sensor.  Unit scaling can be done in API or by caller */
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+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;
+	status = m_impl->SetForwardSoftLimit(forwardLimitPosition);
+	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;
+	status = m_impl->SetReverseSoftLimit(reverseLimitPosition);
+	if(status != CTR_OKAY) {
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+}
+
+/**
+ * TODO documentation (see CANJaguar.cpp)
+ */
+void CANTalon::ConfigMaxOutputVoltage(double voltage)
+{
+	/* SRX does not support max output  */
+	wpi_setWPIErrorWithContext(IncompatibleMode, "MaxOutputVoltage not supported.");
+}
+
+/**
+ * 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;
+  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()
+{
+  return m_controlMode;
+}
+
+void CANTalon::SetExpiration(float timeout)
+{
+	m_safetyHelper->SetExpiration(timeout);
+}
+
+float CANTalon::GetExpiration()
+{
+	return m_safetyHelper->GetExpiration();
+}
+
+bool CANTalon::IsAlive()
+{
+	return m_safetyHelper->IsAlive();
+}
+
+bool CANTalon::IsSafetyEnabled()
+{
+	return m_safetyHelper->IsSafetyEnabled();
+}
+
+void CANTalon::SetSafetyEnabled(bool enabled)
+{
+	m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void CANTalon::GetDescription(char *desc)
+{
+	sprintf(desc, "CANTalon ID %d", m_deviceNumber);
+}
+
+/**
+ * Common interface for stopping the motor
+ * Part of the MotorSafety interface
+ *
+ * @deprecated Call Disable instead.
+*/
+void CANTalon::StopMotor()
+{
+  Disable();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Compressor.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Compressor.cpp
new file mode 100644
index 0000000..430eab1
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Compressor.cpp
@@ -0,0 +1,261 @@
+/*
+ * Compressor.cpp
+ */
+
+#include "Compressor.h"
+#include "WPIErrors.h"
+
+void Compressor::InitCompressor(uint8_t pcmID) {
+	m_pcm_pointer = initializeCompressor(pcmID);
+
+	SetClosedLoopControl(true);
+}
+
+/**
+ * Constructor
+ *
+ * Uses the default PCM ID (0)
+ */
+Compressor::Compressor() {
+	InitCompressor(GetDefaultSolenoidModule());
+}
+
+/**
+ * Constructor
+ *
+ * @param module The PCM ID to use (0-62)
+ */
+Compressor::Compressor(uint8_t pcmID) {
+	InitCompressor(pcmID);
+}
+
+Compressor::~Compressor() {
+
+}
+
+/**
+ *  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() {
+	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() {
+	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() {
+	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() {
+	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() {
+	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() {
+	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() {
+	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() {
+	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() {
+	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() {
+	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);
+	}
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ControllerPower.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ControllerPower.cpp
new file mode 100644
index 0000000..157929b
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/ControllerPower.cpp
@@ -0,0 +1,170 @@
+/*----------------------------------------------------------------------------*/
+/* 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Counter.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Counter.cpp
new file mode 100644
index 0000000..964b774
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Counter.cpp
@@ -0,0 +1,619 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+/**
+ * Create an instance of a counter object.
+ * This creates a ChipObject counter and initializes status variables appropriately
+ *
+ * The counter will start counting immediately.
+ * @param mode The counter mode
+ */
+void Counter::InitCounter(Mode mode)
+{
+	int32_t status = 0;
+	m_index = 0;
+	m_counter = initializeCounter(mode, &m_index, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+	m_upSource = NULL;
+	m_downSource = NULL;
+	m_allocatedUpSource = false;
+	m_allocatedDownSource = false;
+
+	SetMaxPeriod(.5);
+
+	HALReport(HALUsageReporting::kResourceType_Counter, m_index, mode);
+}
+
+/**
+ * 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.
+ *
+ * The counter will start counting immediately.
+ */
+Counter::Counter() :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	InitCounter();
+}
+
+/**
+ * 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) :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	InitCounter();
+	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 reference to the existing DigitalSource object. It will be set as the Up Source.
+ */
+Counter::Counter(DigitalSource &source) :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	InitCounter();
+	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) :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	InitCounter();
+	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.
+ */
+Counter::Counter(AnalogTrigger *trigger) :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	InitCounter();
+	SetUpSource(trigger->CreateOutput(kState));
+	ClearDownSource();
+	m_allocatedUpSource = true;
+}
+
+/**
+ * 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(AnalogTrigger &trigger) :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	InitCounter();
+	SetUpSource(trigger.CreateOutput(kState));
+	ClearDownSource();
+	m_allocatedUpSource = true;
+}
+
+/**
+ * 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) :
+	m_upSource(NULL),
+	m_downSource(NULL),
+	m_counter(NULL)
+{
+	if (encodingType != k1X && encodingType != k2X)
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "Counter only supports 1X and 2X quadrature decoding.");
+		return;
+	}
+	InitCounter(kExternalDirection);
+	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);
+	if (m_allocatedUpSource)
+	{
+		delete m_upSource;
+		m_upSource = NULL;
+	}
+	if (m_allocatedDownSource)
+	{
+		delete m_downSource;
+		m_downSource = NULL;
+	}
+
+	int32_t status = 0;
+	freeCounter(m_counter, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	m_counter = NULL;
+}
+
+/**
+ * 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(new DigitalInput(channel));
+    m_allocatedUpSource = true;
+}
+
+/**
+ * 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)
+{
+	if (StatusIsFatal()) return;
+	SetUpSource(analogTrigger->CreateOutput(triggerType));
+	m_allocatedUpSource = true;
+}
+
+/**
+ * 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(&analogTrigger, 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(DigitalSource *source)
+{
+	if (StatusIsFatal()) return;
+	if (m_allocatedUpSource)
+	{
+		delete m_upSource;
+		m_upSource = NULL;
+		m_allocatedUpSource = false;
+	}
+	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));
+	}
+}
+
+/**
+ * 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(&source);
+}
+
+/**
+ * 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 == NULL)
+	{
+		wpi_setWPIErrorWithContext(NullParameter, "Must set non-NULL 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;
+	if (m_allocatedUpSource)
+	{
+		delete m_upSource;
+		m_upSource = NULL;
+		m_allocatedUpSource = false;
+	}
+	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(new DigitalInput(channel));
+	m_allocatedDownSource = true;
+}
+
+/**
+ * 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)
+{
+	if (StatusIsFatal()) return;
+	SetDownSource(analogTrigger->CreateOutput(triggerType));
+	m_allocatedDownSource = true;
+}
+
+/**
+ * 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(&analogTrigger, 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(DigitalSource *source)
+{
+	if (StatusIsFatal()) return;
+	if (m_allocatedDownSource)
+	{
+		delete m_downSource;
+		m_downSource = NULL;
+		m_allocatedDownSource = false;
+	}
+	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));
+	}
+}
+
+/**
+ * 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(&source);
+}
+
+/**
+ * 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 == NULL)
+	{
+		wpi_setWPIErrorWithContext(NullParameter, "Must set non-NULL 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;
+	if (m_allocatedDownSource)
+	{
+		delete m_downSource;
+		m_downSource = NULL;
+		m_allocatedDownSource = false;
+	}
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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));
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalInput.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalInput.cpp
new file mode 100644
index 0000000..8c6f39a
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalInput.cpp
@@ -0,0 +1,231 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <algorithm>
+#include <array>
+
+#include "DigitalInput.h"
+//#include "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "Encoder.h"
+#include "Counter.h"
+
+::std::array<int, 3> DigitalGlitchFilter::filter_allocated_ = {
+    {false, false, false}};
+Mutex DigitalGlitchFilter::mutex_;
+
+/**
+ * Create an instance of a DigitalInput.
+ * Creates a digital input given a channel. Common creation routine for all
+ * constructors.
+ */
+void DigitalInput::InitDigitalInput(uint32_t channel)
+{
+	char buf[64];
+
+	if (!CheckDigitalChannel(channel))
+	{
+		snprintf(buf, 64, "Digital Channel %d", channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+	m_channel = channel;
+
+	int32_t status = 0;
+	allocateDIO(m_digital_ports[channel], true, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+	HALReport(HALUsageReporting::kResourceType_DigitalInput, channel);
+}
+
+/**
+ * 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)
+{
+	InitDigitalInput(channel);
+}
+
+/**
+ * Free resources associated with the Digital Input class.
+ */
+DigitalInput::~DigitalInput()
+{
+	if (StatusIsFatal()) return;
+	if (m_interrupt != NULL)
+	{
+		int32_t status = 0;
+		cleanInterrupts(m_interrupt, &status);
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+		m_interrupt = NULL;
+		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()
+{
+	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()
+{
+	return m_channel;
+}
+
+/**
+ * @return The value to be written to the channel field of a routing mux.
+ */
+uint32_t DigitalInput::GetChannelForRouting()
+{
+	return GetChannel();
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+uint32_t DigitalInput::GetModuleForRouting()
+{
+	return 0;
+}
+
+/**
+ * @return The value to be written to the analog trigger field of a routing mux.
+ */
+bool DigitalInput::GetAnalogTriggerForRouting()
+{
+	return false;
+}
+
+DigitalGlitchFilter::DigitalGlitchFilter() : channel_index_(-1) {
+  ::std::unique_lock<Mutex> sync(DigitalGlitchFilter::mutex_);
+  auto index =
+      ::std::find(filter_allocated_.begin(), filter_allocated_.end(), false);
+  if (index != filter_allocated_.end()) {
+    channel_index_ = index - filter_allocated_.begin();
+    *index = true;
+  }
+}
+
+DigitalGlitchFilter::~DigitalGlitchFilter() {
+  ::std::unique_lock<Mutex> sync(DigitalGlitchFilter::mutex_);
+  filter_allocated_[channel_index_] = false;
+}
+
+void DigitalGlitchFilter::Add(DigitalSource *input) {
+  int32_t status = 0;
+  setFilterSelect(input->m_digital_ports[input->GetChannelForRouting()],
+                  channel_index_ + 1, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_DigitalInput,
+            input->GetChannelForRouting());
+
+  printf("Source filter %d is %d\n", input->GetChannelForRouting(),
+         getFilterSelect(input->m_digital_ports[input->GetChannelForRouting()],
+                         &status));
+}
+
+void DigitalGlitchFilter::Remove(DigitalSource *input) {
+	int32_t status = 0;
+	setFilterSelect(input->m_digital_ports[input->GetChannelForRouting()], 0, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+	HALReport(HALUsageReporting::kResourceType_DigitalInput, input->GetChannelForRouting());
+}
+
+void DigitalGlitchFilter::SetPeriodCycles(uint32_t fpga_cycles) {
+  int32_t status = 0;
+  setFilterPeriod(channel_index_, fpga_cycles, &status);
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_DigitalGlitchFilter,
+            channel_index_);
+}
+
+void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
+  int32_t status = 0;
+  uint32_t fpga_cycles =
+      nanoseconds * kSystemClockTicksPerMicrosecond / 4 / 1000;
+  setFilterPeriod(channel_index_, fpga_cycles, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_DigitalGlitchFilter,
+            channel_index_);
+}
+
+uint32_t DigitalGlitchFilter::GetPeriodCycles() {
+  int32_t status = 0;
+  uint32_t fpga_cycles = getFilterPeriod(channel_index_, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_DigitalGlitchFilter,
+            channel_index_);
+  return fpga_cycles;
+}
+
+uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() {
+  int32_t status = 0;
+  uint32_t fpga_cycles = getFilterPeriod(channel_index_, &status);
+
+  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+  HALReport(HALUsageReporting::kResourceType_DigitalGlitchFilter,
+            channel_index_);
+  return static_cast<uint64_t>(fpga_cycles) * 1000l /
+         static_cast<uint64_t>(kSystemClockTicksPerMicrosecond / 4);
+}
+
+void DigitalGlitchFilter::Add(Encoder *input) {
+  Add(input->m_aSource);
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_bSource);
+}
+
+void DigitalGlitchFilter::Add(Counter *input) {
+  Add(input->m_upSource);
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_downSource);
+}
+
+void DigitalGlitchFilter::Remove(Encoder *input) {
+  Remove(input->m_aSource);
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_bSource);
+}
+
+void DigitalGlitchFilter::Remove(Counter *input) {
+  Remove(input->m_upSource);
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_downSource);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp
new file mode 100644
index 0000000..a3fc2d1
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalOutput.cpp
@@ -0,0 +1,223 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+
+/**
+ * Create an instance of a DigitalOutput.
+ * Creates a digital output given a channel. Common creation routine for all
+ * constructors.
+ */
+void DigitalOutput::InitDigitalOutput(uint32_t channel)
+{
+	char buf[64];
+
+	if (!CheckDigitalChannel(channel))
+	{
+		snprintf(buf, 64, "Digital Channel %d", channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+	m_channel = channel;
+	m_pwmGenerator = (void *)~0ul;
+
+	int32_t status = 0;
+	allocateDIO(m_digital_ports[channel], false, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+
+	HALReport(HALUsageReporting::kResourceType_DigitalOutput, channel);
+}
+
+/**
+ * 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)
+{
+	InitDigitalOutput(channel);
+}
+
+/**
+ * Free the resources associated with a digital output.
+ */
+DigitalOutput::~DigitalOutput()
+{
+	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()
+{
+	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()
+{
+	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 *)~0ul) 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 *)~0ul) 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 *)~0ul;
+}
+
+/**
+ * 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()
+{
+	return GetChannel();
+}
+
+/**
+ * @return The value to be written to the module field of a routing mux.
+ */
+uint32_t DigitalOutput::GetModuleForRouting()
+{
+	return 0;
+}
+
+/**
+ * @return The value to be written to the analog trigger field of a routing mux.
+ */
+bool DigitalOutput::GetAnalogTriggerForRouting()
+{
+	return false;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalSource.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalSource.cpp
new file mode 100644
index 0000000..40cc75c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DigitalSource.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DigitalSource.h"
+
+/**
+ * DigitalSource destructor.
+ */
+DigitalSource::~DigitalSource()
+{
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp
new file mode 100644
index 0000000..091bae4
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DoubleSolenoid.cpp
@@ -0,0 +1,163 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Common function to implement constructor behaviour.
+ */
+void DoubleSolenoid::InitSolenoid()
+{
+	char buf[64];
+	if (!CheckSolenoidModule(m_moduleNumber))
+	{
+		snprintf(buf, 64, "Solenoid Module %d", m_moduleNumber);
+		wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+		return;
+	}
+	if (!CheckSolenoidChannel(m_forwardChannel))
+	{
+		snprintf(buf, 64, "Solenoid Channel %d", m_forwardChannel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+	if (!CheckSolenoidChannel(m_reverseChannel))
+	{
+		snprintf(buf, 64, "Solenoid Channel %d", m_reverseChannel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+	Resource::CreateResourceObject(&m_allocated, solenoid_kNumDO7_0Elements * kSolenoidChannels);
+
+	snprintf(buf, 64, "Solenoid %d (Module: %d)", m_forwardChannel, m_moduleNumber);
+	if (m_allocated->Allocate(m_moduleNumber * kSolenoidChannels + m_forwardChannel, buf) == ~0ul)
+	{
+		CloneError(m_allocated);
+		return;
+	}
+
+	snprintf(buf, 64, "Solenoid %d (Module: %d)", m_reverseChannel, m_moduleNumber);
+	if (m_allocated->Allocate(m_moduleNumber * kSolenoidChannels + m_reverseChannel, buf) == ~0ul)
+	{
+		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);
+}
+
+/**
+ * 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)
+	: SolenoidBase (GetDefaultSolenoidModule())
+	, m_forwardChannel (forwardChannel)
+	, m_reverseChannel (reverseChannel)
+{
+	InitSolenoid();
+}
+
+/**
+ * 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)
+{
+	InitSolenoid();
+}
+
+/**
+ * Destructor.
+ */
+DoubleSolenoid::~DoubleSolenoid()
+{
+	if (CheckSolenoidModule(m_moduleNumber))
+	{
+		m_allocated->Free(m_moduleNumber * kSolenoidChannels + m_forwardChannel);
+		m_allocated->Free(m_moduleNumber * kSolenoidChannels + m_reverseChannel);
+	}
+}
+
+/**
+ * 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);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+DoubleSolenoid::Value DoubleSolenoid::Get()
+{
+	if (StatusIsFatal()) return kOff;
+	uint8_t value = GetAll();
+
+	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()
+{
+	int blackList = GetPCMSolenoidBlackList();
+	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()
+{
+	int blackList = GetPCMSolenoidBlackList();
+	return (blackList & m_reverseMask) ? 1 : 0;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DriverStation.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DriverStation.cpp
new file mode 100644
index 0000000..7821289
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/DriverStation.cpp
@@ -0,0 +1,533 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HAL/cpp/Synchronized.hpp"
+#include "Timer.h"
+#include "NetworkCommunication/FRCComm.h"
+#include "NetworkCommunication/UsageReporting.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* DriverStation::m_instance = NULL;
+
+/**
+ * DriverStation constructor.
+ *
+ * This is only called once the first time GetInstance() is called
+ */
+DriverStation::DriverStation()
+	: m_task ("DriverStation", (FUNCPTR)DriverStation::InitTask)
+	, m_newControlData(0)
+	, m_packetDataAvailableMultiWait(0)
+	, m_waitForDataSem(0)
+	, m_userInDisabled(false)
+	, m_userInAutonomous(false)
+	, m_userInTeleop(false)
+	, m_userInTest(false)
+	, m_nextMessageTime(0)
+{
+	// 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;
+	}
+	// Create a new semaphore
+	m_packetDataAvailableMultiWait = initializeMultiWait();
+	m_newControlData = initializeSemaphore(SEMAPHORE_EMPTY);
+
+	m_waitForDataSem = initializeMultiWait();
+	m_waitForDataMutex = initializeMutexNormal();
+
+	m_packetDataAvailableMultiWait = initializeMultiWait();
+	m_packetDataAvailableMutex = initializeMutexNormal();
+
+	// Register that semaphore with the network communications task.
+	// It will signal when new packet data is available.
+	HALSetNewDataSem(m_packetDataAvailableMultiWait);
+
+	AddToSingletonList();
+
+	if (!m_task.Start((int32_t)this))
+	{
+		wpi_setWPIError(DriverStationTaskError);
+	}
+}
+
+DriverStation::~DriverStation()
+{
+	m_task.Stop();
+	m_instance = NULL;
+	deleteMultiWait(m_waitForDataSem);
+	// Unregister our semaphore.
+	HALSetNewDataSem(NULL);
+	deleteMultiWait(m_packetDataAvailableMultiWait);
+	deleteMutex(m_packetDataAvailableMutex);
+	deleteMutex(m_waitForDataMutex);
+}
+
+void DriverStation::InitTask(DriverStation *ds)
+{
+	ds->Run();
+}
+
+void DriverStation::Run()
+{
+	int period = 0;
+	while (true)
+	{
+		takeMultiWait(m_packetDataAvailableMultiWait, m_packetDataAvailableMutex, 0);
+		GetData();
+		giveMultiWait(m_waitForDataSem);
+
+		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()
+{
+	if (m_instance == NULL)
+	{
+		m_instance = new DriverStation();
+	}
+	return m_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 < 4; stick++) {
+		HALGetJoystickAxes(stick, &m_joystickAxes[stick]);
+		HALGetJoystickButtons(stick, &m_joystickButtons[stick]);
+	}
+	giveSemaphore(m_newControlData);
+}
+
+/**
+ * Read the battery voltage.
+ *
+ * @return The battery voltage in Volts.
+ */
+float DriverStation::GetBatteryVoltage()
+{
+	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)
+{
+    if (stick >= kJoystickPorts)
+    {
+        wpi_setWPIError(BadJoystickIndex);
+        return 0;
+    }
+   	HALJoystickAxes joystickAxes;
+   	HALGetJoystickAxes(stick, &joystickAxes);
+   	return joystickAxes.count;
+}
+
+/**	
+ * 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)
+{
+    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)
+{
+    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 0;
+	}
+
+	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 0;
+	}
+
+	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)
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	return tryTakeSemaphore(m_newControlData) == 0;
+}
+
+/**
+ * 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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	takeMultiWait(m_waitForDataSem, m_waitForDataMutex, SEMAPHORE_WAIT_FOREVER);
+}
+
+/**
+ * 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()
+{
+	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;
+    HALSetErrorData(error.c_str(), error.size(), 0);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Encoder.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Encoder.cpp
new file mode 100644
index 0000000..310051d
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Encoder.cpp
@@ -0,0 +1,505 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.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;
+	m_index = 0;
+	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 = NULL;
+			SetMaxPeriod(.5);
+			break;
+		}
+		case k1X:
+		case k2X:
+		{
+			m_encodingScale = encodingType == k1X ? 1 : 2;
+			m_counter = new Counter(m_encodingType, m_aSource, m_bSource, reverseDirection);
+			m_index = m_counter->GetFPGAIndex();
+			break;
+		}
+		default:
+			wpi_setErrorWithContext(-1, "Invalid encodingType argument");
+			break;
+	}
+	m_distancePerPulse = 1.0;
+	m_pidSource = kDistance;
+
+	HALReport(HALUsageReporting::kResourceType_Encoder, m_index, encodingType);
+}
+
+/**
+ * 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_encoder(NULL),
+	m_counter(NULL)
+{
+	m_aSource = new DigitalInput(aChannel);
+	m_bSource = new DigitalInput(bChannel);
+	InitEncoder(reverseDirection, encodingType);
+	m_allocatedASource = true;
+	m_allocatedBSource = true;
+}
+
+/**
+ * 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_encoder(NULL),
+	m_counter(NULL)
+{
+	m_aSource = aSource;
+	m_bSource = bSource;
+	m_allocatedASource = false;
+	m_allocatedBSource = false;
+	if (m_aSource == NULL || m_bSource == NULL)
+		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_encoder(NULL),
+	m_counter(NULL)
+{
+	m_aSource = &aSource;
+	m_bSource = &bSource;
+	m_allocatedASource = false;
+	m_allocatedBSource = false;
+	InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Free the resources for an Encoder.
+ * Frees the FPGA resources associated with an Encoder.
+ */
+Encoder::~Encoder()
+{
+	if (m_allocatedASource) delete m_aSource;
+	if (m_allocatedBSource) delete m_bSource;
+	if (m_counter)
+	{
+		delete m_counter;
+	}
+	else
+	{
+	  	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() { 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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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;
+}
+
+
+
+/**
+ * Set which parameter of the encoder you are using as a process control variable.
+ *
+ * @param pidSource An enum to select the parameter.
+ */
+void Encoder::SetPIDSourceParameter(PIDSourceParameter pidSource)
+{
+	if (StatusIsFatal()) return;
+	m_pidSource = pidSource;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current value of the selected source parameter.
+ */
+double Encoder::PIDGet()
+{
+	if (StatusIsFatal()) return 0.0;
+	switch (m_pidSource)
+	{
+	case kDistance:
+		return GetDistance();
+	case kRate:
+		return GetRate();
+	default:
+		return 0.0;
+	}
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/GearTooth.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/GearTooth.cpp
new file mode 100644
index 0000000..8e8f25d
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/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"
+
+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);
+}
+
+/**
+ * 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(DigitalSource &source, bool directionSensitive): Counter(source)
+{
+	EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Free the resources associated with a gear tooth sensor.
+ */
+GearTooth::~GearTooth()
+{
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Gyro.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Gyro.cpp
new file mode 100644
index 0000000..b1650de
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Gyro.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 "Gyro.h"
+#include "AnalogInput.h"
+//#include "NetworkCommunication/UsageReporting.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+#include <climits>
+const uint32_t Gyro::kOversampleBits;
+const uint32_t Gyro::kAverageBits;
+constexpr float Gyro::kSamplesPerSecond;
+constexpr float Gyro::kCalibrationSampleTime;
+constexpr float Gyro::kDefaultVoltsPerDegreePerSecond;
+
+/**
+ * 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 Gyro::InitGyro()
+{
+	if (!m_analog->IsAccumulatorChannel())
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange,
+            " channel (must be accumulator channel)");
+		if (m_channelAllocated)
+		{
+			delete m_analog;
+			m_analog = NULL;
+		}
+		return;
+	}
+
+	m_voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond;
+	m_analog->SetAverageBits(kAverageBits);
+	m_analog->SetOversampleBits(kOversampleBits);
+	float sampleRate = kSamplesPerSecond *
+		(1 << (kAverageBits + kOversampleBits));
+	m_analog->SetSampleRate(sampleRate);
+	Wait(1.0);
+
+	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();
+
+	SetDeadband(0.0f);
+
+	SetPIDSourceParameter(kAngle);
+
+	HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel());
+}
+
+/**
+ * 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.
+ */
+Gyro::Gyro(int32_t channel)
+{
+	m_analog = new AnalogInput(channel);
+	m_channelAllocated = true;
+	InitGyro();
+}
+
+/**
+ * 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.
+ */
+Gyro::Gyro(AnalogInput *channel)
+{
+	m_analog = channel;
+	m_channelAllocated = false;
+	if (channel == NULL)
+	{
+		wpi_setWPIError(NullParameter);
+	}
+	else
+	{
+		InitGyro();
+	}
+}
+
+/**
+ * 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 reference to the AnalogInput object that the gyro is connected to.
+ */
+Gyro::Gyro(AnalogInput &channel)
+{
+	m_analog = &channel;
+	m_channelAllocated = false;
+	InitGyro();
+}
+
+/**
+ * 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 Gyro::Reset()
+{
+	m_analog->ResetAccumulator();
+}
+
+/**
+ * Delete (free) the accumulator and the analog components used for the gyro.
+ */
+Gyro::~Gyro()
+{
+	if (m_channelAllocated)
+		delete m_analog;
+}
+
+/**
+ * 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 Gyro::GetAngle( void )
+{
+	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 Gyro::GetRate( void )
+{
+	return (m_analog->GetAverageValue() - ((double)m_center + m_offset)) * 1e-9 * m_analog->GetLSBWeight()
+			/ ((1 << m_analog->GetOversampleBits()) * m_voltsPerDegreePerSecond);
+}
+
+
+/**
+ * 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 Gyro::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 Gyro::SetDeadband( float volts ) {
+	int32_t deadband = volts * 1e9 / m_analog->GetLSBWeight() * (1 << m_analog->GetOversampleBits());
+	m_analog->SetAccumulatorDeadband(deadband);
+}
+
+
+/**
+ * Sets the type of output to use with the WPILib PID class
+ * The gyro supports using either rate or angle for PID calculations
+ */
+void Gyro::SetPIDSourceParameter(PIDSourceParameter pidSource)
+{
+	if(pidSource == 0 || pidSource > 2)
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "Gyro pidSource");
+    m_pidSource = pidSource;
+}
+
+/**
+ * Get the PIDOutput for the PIDSource base object. Can be set to return
+ * angle or rate using SetPIDSourceParameter(). Defaults to angle.
+ *
+ * @return The PIDOutput (angle or rate, defaults to angle)
+ */
+double Gyro::PIDGet()
+{
+	switch(m_pidSource){
+	case kRate:
+		return GetRate();
+	case kAngle:
+		return GetAngle();
+	default:
+		return 0;
+	}
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/I2C.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/I2C.cpp
new file mode 100644
index 0000000..19e3f4f
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/I2C.cpp
@@ -0,0 +1,221 @@
+/*----------------------------------------------------------------------------*/
+/* 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. [0..6]
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize Number of bytes to read from the device. [0..7]
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Transaction(uint8_t *dataToSend, uint8_t sendSize, uint8_t *dataReceived, uint8_t receiveSize)
+{
+	if (sendSize > 6) // Optional, provides better error message.
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "sendSize");
+		return true;
+	}
+	if (receiveSize > 7) // Optional, provides better error message.
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "receiveSize");
+		return true;
+	}
+
+	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(NULL, 0, NULL, 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 1 to 7 bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally
+ *   allowing you to read up to 7 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. [1..7]
+ * @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 || count > 7)
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+		return true;
+	}
+	if (buffer == NULL)
+	{
+		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 1 to 7 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. [1..7]
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::ReadOnly(uint8_t count, uint8_t *buffer)
+{
+	if (count < 1 || count > 7)
+	{
+		wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+		return true;
+	}
+	if (buffer == NULL)
+	{
+		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.
+ */
+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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Internal/HardwareHLReporting.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Internal/HardwareHLReporting.cpp
new file mode 100644
index 0000000..9c21b7a
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp
new file mode 100644
index 0000000..512c567
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/InterruptableSensorBase.cpp
@@ -0,0 +1,207 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+Resource *InterruptableSensorBase::m_interrupts = NULL;
+
+InterruptableSensorBase::InterruptableSensorBase()
+{
+	m_interrupt = NULL;
+	Resource::CreateResourceObject(&m_interrupts, 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 == ~0ul)
+	{
+		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 == ~0ul)
+	{
+		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 == NULL);
+	// 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 != NULL);
+	int32_t status = 0;
+	cleanInterrupts(m_interrupt, &status);
+	wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	m_interrupt = NULL;
+	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 != NULL);
+	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 != NULL);
+	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 != NULL);
+	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 != NULL);
+	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 != NULL);
+	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 == NULL)
+	{
+		wpi_setWPIErrorWithContext(NullParameter, "You must call RequestInterrupts before SetUpSourceEdge");
+		return;
+	}
+	if (m_interrupt != NULL)
+	{
+		int32_t status = 0;
+		setInterruptUpSourceEdge(m_interrupt, risingEdge, fallingEdge, &status);
+		wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Jaguar.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Jaguar.cpp
new file mode 100644
index 0000000..ebc9ae2
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Jaguar.cpp
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+
+
+#include "Jaguar.h"
+//#include "NetworkCommunication/UsageReporting.h"
+
+/**
+ * Common initialization code called by all constructors.
+ */
+void Jaguar::InitJaguar()
+{
+	/**
+	 * 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());
+}
+
+/**
+ * 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)
+{
+	InitJaguar();
+}
+
+Jaguar::~Jaguar()
+{
+}
+
+/**
+ * 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(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()
+{
+	return GetSpeed();
+}
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Jaguar::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 Jaguar::PIDWrite(float output)
+{
+	Set(output);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Joystick.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Joystick.cpp
new file mode 100644
index 0000000..790f0d7
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Joystick.cpp
@@ -0,0 +1,389 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+#include <math.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)
+	: m_ds (NULL)
+	, m_port (port)
+	, m_axes (NULL)
+	, m_buttons (NULL)
+	, m_outputs (0)
+	, m_leftRumble (0)
+	, m_rightRumble (0)
+{
+	InitJoystick(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 (NULL)
+	, m_port (port)
+	, m_axes (NULL)
+	, m_buttons (NULL)
+{
+	InitJoystick(numAxisTypes, numButtonTypes);
+}
+
+void Joystick::InitJoystick(uint32_t numAxisTypes, uint32_t numButtonTypes)
+{
+	if ( !joySticksInitialized )
+	{
+		for (unsigned i = 0; i < DriverStation::kJoystickPorts; i++)
+			joysticks[i] = NULL;
+		joySticksInitialized = true;
+	}
+	if (m_port >= DriverStation::kJoystickPorts) {
+		wpi_setWPIError(BadJoystickIndex);
+	} else {
+		joysticks[m_port] = this;
+	}
+
+	m_ds = DriverStation::GetInstance();
+	m_axes = new uint32_t[numAxisTypes];
+	m_buttons = new uint32_t[numButtonTypes];
+}
+
+Joystick * Joystick::GetStickForPort(uint32_t port)
+{
+	Joystick *stick = joysticks[port];
+	if (stick == NULL)
+	{
+		stick = new Joystick(port);
+		joysticks[port] = stick;
+	}
+	return stick;
+}
+
+Joystick::~Joystick()
+{
+	delete [] m_buttons;
+	delete [] m_axes;
+}
+
+/**
+ * Get the X value of the joystick.
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+float Joystick::GetX(JoystickHand hand)
+{
+	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.
+ */
+float Joystick::GetY(JoystickHand hand)
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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)
+{
+	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)
+{
+	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)
+{
+	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)
+{
+	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)
+{
+	// 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)
+{
+	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) {
+	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)
+{
+	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()
+{
+    return m_ds->GetStickAxisCount(m_port);
+}
+
+/**
+  * Get the number of axis for a joystick
+  *
+* @return the number of buttons on the current joystick
+ */
+int Joystick::GetButtonCount()
+{
+    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()
+{
+    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)
+{
+	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(){
+	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(){
+	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(){
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp
new file mode 100644
index 0000000..6bb7f48
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/MotorSafetyHelper.cpp
@@ -0,0 +1,156 @@
+/*----------------------------------------------------------------------------*/
+/* 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>
+
+MotorSafetyHelper *MotorSafetyHelper::m_headHelper = NULL;
+ReentrantMutex 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::unique_lock<ReentrantMutex> sync(m_listMutex);
+	m_nextHelper = m_headHelper;
+	m_headHelper = this;
+}
+
+
+MotorSafetyHelper::~MotorSafetyHelper()
+{
+	::std::unique_lock<ReentrantMutex> sync(m_listMutex);
+	if (m_headHelper == this)
+	{
+		m_headHelper = m_nextHelper;
+	}
+	else
+	{
+		MotorSafetyHelper *prev = NULL;
+		MotorSafetyHelper *cur = m_headHelper;
+		while (cur != this && cur != NULL)
+			prev = cur, cur = cur->m_nextHelper;
+		if (cur == this)
+			prev->m_nextHelper = cur->m_nextHelper;
+	}
+}
+
+/**
+ * Feed the motor safety object.
+ * Resets the timer on this object that is used to do the timeouts.
+ */
+void MotorSafetyHelper::Feed()
+{
+	::std::unique_lock<ReentrantMutex> 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::unique_lock<ReentrantMutex> 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()
+{
+	::std::unique_lock<ReentrantMutex> 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()
+{
+	::std::unique_lock<ReentrantMutex> 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::unique_lock<ReentrantMutex> sync(m_syncMutex);
+	if (m_stopTime < Timer::GetFPGATimestamp())
+	{
+		char buf[128];
+		char desc[64];
+		m_safeObject->GetDescription(desc);
+		snprintf(buf, 128, "%s... Output not updated often enough.", desc);
+		wpi_setWPIErrorWithContext(Timeout, buf);
+		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::unique_lock<ReentrantMutex> 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()
+{
+	::std::unique_lock<ReentrantMutex> 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::unique_lock<ReentrantMutex> sync(m_listMutex);
+	for (MotorSafetyHelper *msh = m_headHelper; msh != NULL; msh = msh->m_nextHelper)
+	{
+		msh->Check();
+	}
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Notifier.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Notifier.cpp
new file mode 100644
index 0000000..70d6bf5
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Notifier.cpp
@@ -0,0 +1,265 @@
+/*----------------------------------------------------------------------------*/
+/* 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 = NULL;
+ReentrantMutex Notifier::queueSemaphore;
+void* Notifier::m_notifier = NULL;
+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 == NULL)
+		wpi_setWPIErrorWithContext(NullParameter, "handler must not be NULL");
+	m_handler = handler;
+	m_param = param;
+	m_periodic = false;
+	m_expirationTime = 0;
+	m_period = 0;
+	m_nextEvent = NULL;
+	m_queued = false;
+	m_handlerSemaphore = initializeSemaphore(SEMAPHORE_FULL);
+	{
+		::std::unique_lock<ReentrantMutex> sync(queueSemaphore);
+		// do the first time intialization of static variables
+		if (refcount == 0)
+		{
+			int32_t status = 0;
+			m_notifier = initializeNotifier(ProcessQueue, &status);
+			wpi_setErrorWithContext(status, getHALErrorMessage(status));
+		}
+		refcount++;
+	}
+}
+
+/**
+ * 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::unique_lock<ReentrantMutex> sync(queueSemaphore);
+		DeleteFromQueue();
+
+		// Delete the static variables when the last one is going away
+		if (!(--refcount))
+		{
+			int32_t status = 0;
+			cleanNotifier(m_notifier, &status);
+			wpi_setErrorWithContext(status, getHALErrorMessage(status));
+		}
+	}
+
+	// Acquire the semaphore; this makes certain that the handler is 
+	// not being executed by the interrupt manager.
+	takeSemaphore(m_handlerSemaphore);
+	// Delete while holding the semaphore so there can be no race.
+	deleteSemaphore(m_handlerSemaphore);
+}
+
+/**
+ * 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 != NULL)
+	{
+		int32_t status = 0;
+		updateNotifierAlarm(m_notifier, (uint32_t)(timerQueueHead->m_expirationTime * 1e6), &status);
+		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 mask, void *params)
+{
+	Notifier *current;
+	while (true)				// keep processing past events until no more
+	{
+		{
+			::std::unique_lock<ReentrantMutex> sync(queueSemaphore);
+			double currentTime = GetClock();
+			current = timerQueueHead;
+			if (current == NULL || 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 semaphore while holding queue semaphore to make sure
+			//  the handler will execute to completion in case we are being deleted.
+			takeSemaphore(current->m_handlerSemaphore);
+		}
+
+		current->m_handler(current->m_param);	// call the event handler
+		giveSemaphore(current->m_handlerSemaphore);
+	}
+	// reschedule the first item in the queue
+	::std::unique_lock<ReentrantMutex> sync(queueSemaphore);
+	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 == NULL || 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 == NULL || 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 != NULL);
+		if (timerQueueHead == this)
+		{
+			// remove the first item in the list - update the alarm
+			timerQueueHead = this->m_nextEvent;
+			UpdateAlarm();
+		}
+		else
+		{
+			for (Notifier *n = timerQueueHead; n != NULL; 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::unique_lock<ReentrantMutex> sync(queueSemaphore);
+	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::unique_lock<ReentrantMutex> sync(queueSemaphore);
+	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::unique_lock<ReentrantMutex> sync(queueSemaphore);
+		DeleteFromQueue();
+	}
+	// Wait for a currently executing handler to complete before returning from Stop()
+	Synchronized sync(m_handlerSemaphore);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/PWM.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/PWM.cpp
new file mode 100644
index 0000000..8bb0f47
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/PWM.cpp
@@ -0,0 +1,363 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include "HAL/HAL.hpp"
+
+constexpr float PWM::kDefaultPwmPeriod;
+constexpr float PWM::kDefaultPwmCenter;
+const int32_t PWM::kDefaultPwmStepsDown;
+const int32_t PWM::kPwmDisabled;
+
+/**
+ * Initialize PWMs given a channel.
+ *
+ * This method is private and is the common path for all the constructors for creating PWM
+ * instances. 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
+ */
+void PWM::InitPWM(uint32_t channel)
+{
+	char buf[64];
+
+	if (!CheckPWMChannel(channel))
+	{
+		snprintf(buf, 64, "PWM Channel %d", channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		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);
+}
+
+/**
+ * Allocate a PWM given a channel number.
+ *
+ * @param channel The PWM channel.
+ */
+PWM::PWM(uint32_t channel)
+{
+	InitPWM(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));
+}
+
+/**
+ * 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()
+{
+	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()
+{
+	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()
+{
+	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));
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp
new file mode 100644
index 0000000..a7c40b3
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/PowerDistributionPanel.cpp
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ * Initialize the PDP.
+ */
+PowerDistributionPanel::PowerDistributionPanel() {
+}
+
+/**
+ * Query the input voltage of the PDP
+ * @return The voltage of the PDP in volts
+ */
+double
+PowerDistributionPanel::GetVoltage() {
+	int32_t status = 0;
+	
+	double voltage = getPDPVoltage(&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() {
+	int32_t status = 0;
+	
+	double temperature = getPDPTemperature(&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) {
+	int32_t status = 0;
+	
+	if(!CheckPDPChannel(channel))
+	{
+		char buf[64];
+		snprintf(buf, 64, "PDP Channel %d", channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+	}
+	
+	double current = getPDPChannelCurrent(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() {
+	int32_t status = 0;
+	
+	double current = getPDPTotalCurrent(&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() {
+	int32_t status = 0;
+	
+	double power = getPDPTotalPower(&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() {
+	int32_t status = 0;
+	
+	double energy = getPDPTotalEnergy(&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(&status);
+	
+	if(status) {
+		wpi_setWPIErrorWithContext(Timeout, "");
+	}
+}
+
+/**
+ * Remove all of the fault flags on the PDP
+ */
+void
+PowerDistributionPanel::ClearStickyFaults() {
+	int32_t status = 0;
+	
+	clearPDPStickyFaults(&status);
+	
+	if(status) {
+		wpi_setWPIErrorWithContext(Timeout, "");
+	}
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Relay.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Relay.cpp
new file mode 100644
index 0000000..6b3b50c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Relay.cpp
@@ -0,0 +1,210 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Resource.h"
+#include "WPIErrors.h"
+#include "HAL/HAL.hpp"
+
+// Allocate each direction separately.
+static Resource *relayChannels = NULL;
+
+/**
+ * Common relay initialization method.
+ * This code is common to all Relay constructors and initializes the relay and reserves
+ * all resources that need to be locked. Initially the relay is set to both lines at 0v.
+ */
+void Relay::InitRelay()
+{
+	char buf[64];
+	Resource::CreateResourceObject(&relayChannels, dio_kNumSystems * kRelayChannels * 2);
+	if (!SensorBase::CheckRelayChannel(m_channel))
+	{
+		snprintf(buf, 64, "Relay Channel %d", m_channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+
+	if (m_direction == kBothDirections || m_direction == kForwardOnly)
+	{
+		snprintf(buf, 64, "Forward Relay %d", m_channel);
+		if (relayChannels->Allocate(m_channel * 2, buf) == ~0ul)
+		{
+			CloneError(relayChannels);
+			return;
+		}
+
+		HALReport(HALUsageReporting::kResourceType_Relay, m_channel);
+	}
+	if (m_direction == kBothDirections || m_direction == kReverseOnly)
+	{
+		snprintf(buf, 64, "Reverse Relay %d", m_channel);
+		if (relayChannels->Allocate(m_channel * 2 + 1, buf) == ~0ul)
+		{
+			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));
+
+}
+
+/**
+ * Relay constructor given a channel.
+ * @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)
+{
+	InitRelay();
+}
+
+/**
+ * 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);
+	}
+}
+
+/**
+ * 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() {
+	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));
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/RobotBase.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/RobotBase.cpp
new file mode 100644
index 0000000..4b2c435
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/RobotBase.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/FRCComm.h"
+//#include "NetworkCommunication/symModuleLink.h"
+//#include "NetworkCommunication/UsageReporting.h"
+#include "RobotState.h"
+#include "HLUsageReporting.h"
+#include "Internal/HardwareHLReporting.h"
+#include "Utility.h"
+#include <cstring>
+#include "HAL/HAL.hpp"
+#include <cstdio>
+
+#ifdef __vxworks
+// VXWorks needs som special unloading code
+#include <moduleLib.h>
+#include <unldLib.h>
+#include <taskLib.h>
+#endif
+
+RobotBase* RobotBase::m_instance = NULL;
+
+void RobotBase::setInstance(RobotBase* robot)
+{
+	wpi_assert(m_instance == NULL);
+	m_instance = robot;
+}
+
+RobotBase &RobotBase::getInstance()
+{
+	return *m_instance;
+}
+
+void RobotBase::robotSetup(RobotBase *robot)
+{
+	robot->Prestart();
+	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_task (NULL)
+	, m_ds (NULL)
+{
+	m_ds = DriverStation::GetInstance();
+	RobotState::SetImplementation(DriverStation::GetInstance()); \
+	HLUsageReporting::SetImplementation(new HardwareHLReporting()); \
+
+	RobotBase::setInstance(this);
+	
+	FILE *file = NULL;
+	file = fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
+
+	fputs("2015 C++ 1.0.0 - modified by FRC Team 971 Spartan Robotics", file);
+	if (file != NULL)
+	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 = NULL;
+	m_instance = NULL;
+}
+
+/**
+ * Determine if the Robot is currently enabled.
+ * @return True if the Robot is currently enabled by the field controls.
+ */
+bool RobotBase::IsEnabled()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+	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()
+{
+    return m_ds->IsTest();
+}
+
+/**
+ * This hook is called right before startCompetition(). By default, tell the DS that the robot is now ready to
+ * be enabled. If you don't want for the robot to be enabled yet, you can override this method to do nothing.
+ * If you do so, you will need to call HALNetworkCommunicationObserveUserProgramStarting() from your code when
+ * you are ready for the robot to be enabled.
+ */
+void RobotBase::Prestart()
+{
+	HALNetworkCommunicationObserveUserProgramStarting();
+}
+
+/**
+ * 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()
+{
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/RobotDrive.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/RobotDrive.cpp
new file mode 100644
index 0000000..8d44ca0
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/RobotDrive.cpp
@@ -0,0 +1,740 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include <math.h>
+
+#undef max
+#include <algorithm>
+
+const int32_t RobotDrive::kMaxNumberOfMotors;
+
+/*
+ * 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_frontLeftMotor = NULL;
+	m_frontRightMotor = NULL;
+	m_rearRightMotor = NULL;
+	m_rearLeftMotor = NULL;
+	m_sensitivity = 0.5;
+	m_maxOutput = 1.0;
+	m_safetyHelper = new 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 = new Talon(leftMotorChannel);
+	m_rearRightMotor = new Talon(rightMotorChannel);
+	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
+	{
+		m_invertedMotors[i] = 1;
+	}
+	SetLeftRightMotorOutputs(0.0, 0.0);
+	m_deleteSpeedControllers = true;
+}
+
+/**
+ * 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 = new Talon(rearLeftMotor);
+	m_rearRightMotor = new Talon(rearRightMotor);
+	m_frontLeftMotor = new Talon(frontLeftMotor);
+	m_frontRightMotor = new Talon(frontRightMotor);
+	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
+	{
+		m_invertedMotors[i] = 1;
+	}
+	SetLeftRightMotorOutputs(0.0, 0.0);
+	m_deleteSpeedControllers = true;
+}
+
+/**
+ * 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 == NULL || rightMotor == NULL)
+	{
+		wpi_setWPIError(NullParameter);
+		m_rearLeftMotor = m_rearRightMotor = NULL;
+		return;
+	}
+	m_rearLeftMotor = leftMotor;
+	m_rearRightMotor = rightMotor;
+	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
+	{
+		m_invertedMotors[i] = 1;
+	}
+	m_deleteSpeedControllers = false;
+}
+
+RobotDrive::RobotDrive(SpeedController &leftMotor, SpeedController &rightMotor)
+{
+	InitRobotDrive();
+	m_rearLeftMotor = &leftMotor;
+	m_rearRightMotor = &rightMotor;
+	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
+	{
+		m_invertedMotors[i] = 1;
+	}
+	m_deleteSpeedControllers = false;
+}
+
+/**
+ * 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 == NULL || rearLeftMotor == NULL || frontRightMotor == NULL || rearRightMotor == NULL)
+	{
+		wpi_setWPIError(NullParameter);
+		return;
+	}
+	m_frontLeftMotor = frontLeftMotor;
+	m_rearLeftMotor = rearLeftMotor;
+	m_frontRightMotor = frontRightMotor;
+	m_rearRightMotor = rearRightMotor;
+	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
+	{
+		m_invertedMotors[i] = 1;
+	}
+	m_deleteSpeedControllers = false;
+}
+
+RobotDrive::RobotDrive(SpeedController &frontLeftMotor, SpeedController &rearLeftMotor,
+						SpeedController &frontRightMotor, SpeedController &rearRightMotor)
+{
+	InitRobotDrive();
+	m_frontLeftMotor = &frontLeftMotor;
+	m_rearLeftMotor = &rearLeftMotor;
+	m_frontRightMotor = &frontRightMotor;
+	m_rearRightMotor = &rearRightMotor;
+	for (int32_t i=0; i < kMaxNumberOfMotors; i++)
+	{
+		m_invertedMotors[i] = 1;
+	}
+	m_deleteSpeedControllers = false;
+}
+
+/**
+ * RobotDrive destructor.
+ * Deletes motor objects that were not passed in and created internally only.
+ **/
+RobotDrive::~RobotDrive()
+{
+	if (m_deleteSpeedControllers)
+	{
+		delete m_frontLeftMotor;
+		delete m_rearLeftMotor;
+		delete m_frontRightMotor;
+		delete m_rearRightMotor;
+	}
+	delete m_safetyHelper;
+}
+
+/**
+ * Drive the motors at "speed" and "curve".
+ *
+ * The speed and curve are -1.0 to +1.0 values where 0.0 represents stopped and
+ * not turning. The algorithm for adding in the direction attempts to provide a constant
+ * turn radius for differing speeds.
+ *
+ * This function will most likely be used in an autonomous routine.
+ *
+ * @param outputMagnitude The forward component of the output magnitude to send to the motors.
+ * @param curve The rate of turn, constant for different forward speeds.
+ */
+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 == NULL || rightStick == NULL)
+	{
+		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 == NULL || rightStick == NULL)
+	{
+		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);
+
+	uint8_t syncGroup = 0x80;
+
+	m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
+	m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
+	m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
+	m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
+
+	CANJaguar::UpdateSyncGroup(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);
+
+	uint8_t syncGroup = 0x80;
+
+	m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
+	m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
+	m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
+	m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
+
+	CANJaguar::UpdateSyncGroup(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 != NULL && m_rearRightMotor != NULL);
+
+	uint8_t syncGroup = 0x80;
+
+	if (m_frontLeftMotor != NULL)
+		m_frontLeftMotor->Set(Limit(leftOutput) * m_invertedMotors[kFrontLeftMotor] * m_maxOutput, syncGroup);
+	m_rearLeftMotor->Set(Limit(leftOutput) * m_invertedMotors[kRearLeftMotor] * m_maxOutput, syncGroup);
+
+	if (m_frontRightMotor != NULL)
+		m_frontRightMotor->Set(-Limit(rightOutput) * m_invertedMotors[kFrontRightMotor] * m_maxOutput, syncGroup);
+	m_rearRightMotor->Set(-Limit(rightOutput) * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup);
+
+	CANJaguar::UpdateSyncGroup(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;
+	}
+	m_invertedMotors[motor] = isInverted ? -1 : 1;
+}
+
+/**
+ * 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;
+}
+
+
+
+void RobotDrive::SetExpiration(float timeout)
+{
+	m_safetyHelper->SetExpiration(timeout);
+}
+
+float RobotDrive::GetExpiration()
+{
+	return m_safetyHelper->GetExpiration();
+}
+
+bool RobotDrive::IsAlive()
+{
+	return m_safetyHelper->IsAlive();
+}
+
+bool RobotDrive::IsSafetyEnabled()
+{
+	return m_safetyHelper->IsSafetyEnabled();
+}
+
+void RobotDrive::SetSafetyEnabled(bool enabled)
+{
+	m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void RobotDrive::GetDescription(char *desc)
+{
+	sprintf(desc, "RobotDrive");
+}
+
+void RobotDrive::StopMotor()
+{
+	if (m_frontLeftMotor != NULL) m_frontLeftMotor->Disable();
+	if (m_frontRightMotor != NULL) m_frontRightMotor->Disable();
+	if (m_rearLeftMotor != NULL) m_rearLeftMotor->Disable();
+	if (m_rearRightMotor != NULL) m_rearRightMotor->Disable();
+	m_safetyHelper->Feed();
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SPI.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SPI.cpp
new file mode 100644
index 0000000..4878dd9
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SPI.cpp
@@ -0,0 +1,185 @@
+/*----------------------------------------------------------------------------*/
+/* 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){
+		uint8_t* 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;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SafePWM.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SafePWM.cpp
new file mode 100644
index 0000000..289d5fe
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SafePWM.cpp
@@ -0,0 +1,106 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+#include "MotorSafetyHelper.h"
+
+/**
+ * Initialize a SafePWM object by setting defaults
+ */
+void SafePWM::InitSafePWM()
+{
+	m_safetyHelper = new MotorSafetyHelper(this);
+	m_safetyHelper->SetSafetyEnabled(false);
+}
+
+/**
+ * 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)
+{
+	InitSafePWM();
+}
+
+SafePWM::~SafePWM()
+{
+	delete m_safetyHelper;
+}
+
+/**
+ * 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()
+{
+	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()
+{
+	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()
+{
+	return m_safetyHelper->IsSafetyEnabled();
+}
+
+void SafePWM::GetDescription(char *desc)
+{
+	sprintf(desc, "PWM %d", 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SensorBase.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SensorBase.cpp
new file mode 100644
index 0000000..d403b14
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SensorBase.cpp
@@ -0,0 +1,202 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+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 = NULL;
+
+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));
+		}
+
+		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));
+		}
+
+		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));
+		}
+	}
+}
+
+/**
+ * Frees the resources for a SensorBase.
+ */
+SensorBase::~SensorBase()
+{
+}
+
+/**
+ * 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 != NULL;)
+	{
+		SensorBase *tmp = next;
+		next = next->m_nextSingleton;
+		delete tmp;
+	}
+	m_singletonList = NULL;
+}
+
+/**
+ * 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Servo.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Servo.cpp
new file mode 100644
index 0000000..d9a3dcd
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Servo.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+
+constexpr float Servo::kMaxServoAngle;
+constexpr float Servo::kMinServoAngle;
+
+constexpr float Servo::kDefaultMaxServoPWM;
+constexpr float Servo::kDefaultMinServoPWM;
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * InitServo() assigns defaults for the period multiplier for the servo PWM control signal, as
+ * well as the minimum and maximum PWM values supported by the servo.
+ */
+void Servo::InitServo()
+{
+	SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
+	SetPeriodMultiplier(kPeriodMultiplier_4X);
+
+	HALReport(HALUsageReporting::kResourceType_Servo, GetChannel());
+}
+
+/**
+ * @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)
+{
+	InitServo();
+//	printf("Done initializing servo %d\n", channel);
+}
+
+Servo::~Servo()
+{
+}
+
+/**
+ * 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()
+{
+	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()
+{
+	return (float)GetPosition() * GetServoAngleRange() + kMinServoAngle;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Solenoid.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Solenoid.cpp
new file mode 100644
index 0000000..1ef3d7a
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Solenoid.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+
+/**
+ * Common function to implement constructor behavior.
+ */
+void Solenoid::InitSolenoid()
+{
+	char buf[64];
+	if (!CheckSolenoidModule(m_moduleNumber))
+	{
+		snprintf(buf, 64, "Solenoid Module %d", m_moduleNumber);
+		wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf);
+		return;
+	}
+	if (!CheckSolenoidChannel(m_channel))
+	{
+		snprintf(buf, 64, "Solenoid Channel %d", m_channel);
+		wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf);
+		return;
+	}
+	Resource::CreateResourceObject(&m_allocated, kSolenoidChannels * 63);
+
+	snprintf(buf, 64, "Solenoid %d (Module: %d)", m_channel, m_moduleNumber);
+	if (m_allocated->Allocate(m_moduleNumber * kSolenoidChannels + m_channel, buf) == ~0ul)
+	{
+		CloneError(m_allocated);
+		return;
+	}
+
+	HALReport(HALUsageReporting::kResourceType_Solenoid, m_channel, m_moduleNumber);
+}
+
+/**
+ * Constructor using the default PCM ID (0).
+ *
+ * @param channel The channel on the PCM to control (0..7).
+ */
+Solenoid::Solenoid(uint32_t channel)
+	: SolenoidBase (GetDefaultSolenoidModule())
+	, m_channel (channel)
+{
+	InitSolenoid();
+}
+
+/**
+ * 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)
+{
+	InitSolenoid();
+}
+
+/**
+ * Destructor.
+ */
+Solenoid::~Solenoid()
+{
+	if (CheckSolenoidModule(m_moduleNumber))
+	{
+		m_allocated->Free(m_moduleNumber * kSolenoidChannels + m_channel);
+	}
+}
+
+/**
+ * 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);
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+bool Solenoid::Get()
+{
+	if (StatusIsFatal()) return false;
+	uint8_t value = GetAll() & ( 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()
+{
+	int value = GetPCMSolenoidBlackList() & ( 1 << m_channel);
+	return (value != 0);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp
new file mode 100644
index 0000000..f1b46d6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/SolenoidBase.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+// Needs to be global since the protected resource spans all Solenoid objects.
+Resource *SolenoidBase::m_allocated = NULL;
+
+/**
+ * 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;
+	  m_ports[i] = initializeSolenoidPort(port, &status);
+	  wpi_setErrorWithContext(status, getHALErrorMessage(status));
+	}
+}
+
+/**
+ * Destructor.
+ */
+SolenoidBase::~SolenoidBase()
+{
+}
+
+/**
+ * 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)
+{
+  	int32_t status = 0;
+		setSolenoids(m_ports[0], value, 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()
+{
+  	uint8_t value = 0;
+  	int32_t status = 0;
+	for (int i = 0; i < 8; i++) { // XXX: Unhardcode
+	  value |= getSolenoid(m_ports[i], &status) << i;
+	}
+	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()
+{
+	int32_t status = 0;
+	return getPCMSolenoidBlackList(m_ports[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()
+{
+	int32_t status = 0;
+	return getPCMSolenoidVoltageStickyFault(m_ports[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()
+{
+	int32_t status = 0;
+	return getPCMSolenoidVoltageFault(m_ports[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()
+{
+	int32_t status = 0;
+	return clearAllPCMStickyFaults_sol(m_ports[0], &status);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Talon.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Talon.cpp
new file mode 100644
index 0000000..a2eb396
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Talon.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * 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"
+ */
+void Talon::InitTalon() {
+	SetBounds(2.037, 1.539, 1.513, 1.487, .989);
+	SetPeriodMultiplier(kPeriodMultiplier_1X);
+	SetRaw(m_centerPwm);
+	SetZeroLatch();
+
+	HALReport(HALUsageReporting::kResourceType_Talon, GetChannel());
+}
+
+/**
+ * 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)
+{
+	InitTalon();
+}
+
+Talon::~Talon()
+{
+}
+
+/**
+ * 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(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()
+{
+	return GetSpeed();
+}
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Talon::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 Talon::PIDWrite(float output)
+{
+	Set(output);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/TalonSRX.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/TalonSRX.cpp
new file mode 100644
index 0000000..d0f9ce6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/TalonSRX.cpp
@@ -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.  */
+/*----------------------------------------------------------------------------*/
+
+#include "TalonSRX.h"
+
+//#include "NetworkCommunication/UsageReporting.h"
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * 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 behaviour 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"
+ */
+void TalonSRX::InitTalonSRX() {
+	SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+	SetPeriodMultiplier(kPeriodMultiplier_1X);
+	SetRaw(m_centerPwm);
+	SetZeroLatch();
+
+	HALReport(HALUsageReporting::kResourceType_Talon, GetChannel());
+}
+
+/**
+ * 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)
+{
+	InitTalonSRX();
+}
+
+TalonSRX::~TalonSRX()
+{
+}
+
+/**
+ * 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()
+{
+	return GetSpeed();
+}
+
+/**
+ * Common interface for disabling a motor.
+ */
+void TalonSRX::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 TalonSRX::PIDWrite(float output)
+{
+	Set(output);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Task.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Task.cpp
new file mode 100644
index 0000000..4b80142
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Task.cpp
@@ -0,0 +1,213 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "WPIErrors.h"
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+#include "HAL/HAL.hpp"
+
+#ifndef OK
+#define OK		0
+#endif /* OK */
+#ifndef ERROR
+#define ERROR		(-1)
+#endif /* ERROR */
+
+const uint32_t Task::kDefaultPriority;
+
+/**
+ * Create but don't launch a task.
+ * @param name The name of the task.  "FRC_" will be prepended to the task name.
+ * @param function The address of the function to run as the new task.
+ * @param priority The VxWorks priority for the task.
+ * @param stackSize The size of the stack for the task
+ */
+Task::Task(const char* name, FUNCPTR function, int32_t priority, uint32_t stackSize)
+{
+	m_taskID = NULL_TASK;
+	m_function = function;
+	m_priority = priority;
+	m_stackSize = stackSize;
+	m_taskName = new char[strlen(name) + 5];
+	strcpy(m_taskName, "FRC_");
+	strcpy(m_taskName+4, name);
+
+	static int32_t instances = 0;
+	instances++;
+	HALReport(HALUsageReporting::kResourceType_Task, instances, 0, m_taskName);
+}
+
+Task::~Task()
+{
+	if (m_taskID != NULL_TASK) Stop();
+	delete [] m_taskName;
+	m_taskName = NULL;
+}
+
+/**
+ * Starts this task.
+ * If it is already running or unable to start, it fails and returns false.
+ */
+bool Task::Start(uint32_t arg0, uint32_t arg1, uint32_t arg2, uint32_t arg3, uint32_t arg4, 
+		uint32_t arg5, uint32_t arg6, uint32_t arg7, uint32_t arg8, uint32_t arg9)
+{
+	m_taskID = spawnTask(m_taskName,
+						m_priority,
+						VXWORKS_FP_TASK,							// options
+						m_stackSize,						// stack size
+						m_function,							// function to start
+						arg0, arg1, arg2, arg3, arg4,	// parameter 1 - pointer to this class
+						arg5, arg6, arg7, arg8, arg9);// additional unused parameters
+	if (m_taskID == NULL_TASK) {
+		HandleError(ERROR);
+		return false;
+	}
+	return true;
+}
+
+/**
+ * Restarts a running task.
+ * If the task isn't started, it starts it.
+ * @return false if the task is running and we are unable to kill the previous instance
+ */
+bool Task::Restart()
+{
+	return HandleError(restartTask(m_taskID));
+}
+
+/**
+ * Kills the running task.
+ * @returns true on success false if the task doesn't exist or we are unable to kill it.
+ */
+bool Task::Stop()
+{
+	bool ok = true;
+	if (Verify())
+	{
+		ok = HandleError(deleteTask(m_taskID));
+	}
+	m_taskID = NULL_TASK;
+	return ok;
+}
+
+/**
+ * Returns true if the task is ready to execute (i.e. not suspended, delayed, or blocked).
+ * @return true if ready, false if not ready.
+ */
+bool Task::IsReady()
+{
+	return isTaskReady(m_taskID);
+}
+
+/**
+ * Returns true if the task was explicitly suspended by calling Suspend()
+ * @return true if suspended, false if not suspended.
+ */
+bool Task::IsSuspended()
+{
+	return isTaskSuspended(m_taskID);
+}
+
+/**
+ * Pauses a running task.
+ * Returns true on success, false if unable to pause or the task isn't running.
+ */
+bool Task::Suspend()
+{
+	return HandleError(suspendTask(m_taskID));
+}
+
+/**
+ * Resumes a paused task.
+ * Returns true on success, false if unable to resume or if the task isn't running/paused.
+ */
+bool Task::Resume()
+{
+	return HandleError(resumeTask(m_taskID));
+}
+
+/**
+ * Verifies a task still exists.
+ * @returns true on success.
+ */
+bool Task::Verify()
+{
+	return verifyTaskID(m_taskID) == OK;
+}
+
+/**
+ * Gets the priority of a task.
+ * @returns task priority or 0 if an error occured
+ */
+int32_t Task::GetPriority()
+{
+	if (HandleError(getTaskPriority(m_taskID, &m_priority)))
+		return m_priority;
+	else
+		return 0;
+}
+
+/**
+ * This routine changes a task's priority to a specified priority.
+ * Priorities range from 0, the highest priority, to 255, the lowest priority.
+ * Default task priority is 100.
+ * @param priority The priority the task should run at.
+ * @returns true on success.
+ */
+bool Task::SetPriority(int32_t priority)
+{
+	m_priority = priority;
+	return HandleError(setTaskPriority(m_taskID, m_priority));
+}
+
+/**
+ * Returns the name of the task.
+ * @returns Pointer to the name of the task or NULL if not allocated
+ */
+const char* Task::GetName()
+{
+	return m_taskName;
+}
+
+/**
+ * Get the ID of a task
+ * @returns Task ID of this task.  Task::kInvalidTaskID (-1) if the task has not been started or has already exited.
+ */
+TASK Task::GetID()
+{
+	if (Verify())
+		return m_taskID;
+	return NULL_TASK;
+}
+
+/**
+ * Handles errors generated by task related code.
+ */
+bool Task::HandleError(STATUS results)
+{
+	if (results != ERROR) return true;
+	int errsv = errno;
+	if (errsv == HAL_objLib_OBJ_ID_ERROR) {
+		wpi_setWPIErrorWithContext(TaskIDError, m_taskName);
+	} else if (errsv == HAL_objLib_OBJ_DELETED) {
+		wpi_setWPIErrorWithContext(TaskDeletedError, m_taskName);
+	} else if (errsv == HAL_taskLib_ILLEGAL_OPTIONS) {
+		wpi_setWPIErrorWithContext(TaskOptionsError, m_taskName);
+	} else if (errsv == HAL_memLib_NOT_ENOUGH_MEMORY) {
+		wpi_setWPIErrorWithContext(TaskMemoryError, m_taskName);
+	} else if (errsv == HAL_taskLib_ILLEGAL_PRIORITY) {
+		wpi_setWPIErrorWithContext(TaskPriorityError, m_taskName);
+	} else {
+		printf("ERROR: errno=%i", errsv);
+		wpi_setWPIErrorWithContext(TaskError, m_taskName);
+	}
+	return false;
+}
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Timer.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Timer.cpp
new file mode 100644
index 0000000..e13737c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Timer.cpp
@@ -0,0 +1,191 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HAL/cpp/Synchronized.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);
+}
+
+/**
+ * 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()
+	: m_startTime (0.0)
+	, m_accumulatedTime (0.0)
+	, m_running (false)
+{
+	//Creates a semaphore to control access to critical regions.
+	//Initially 'open'
+	Reset();
+}
+
+Timer::~Timer() {}
+
+/**
+ * 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()
+{
+	double result;
+	double currentTime = GetFPGATimestamp();
+
+	::std::unique_lock<Mutex> sync(m_lock);
+	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::unique_lock<Mutex> sync(m_lock);
+	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::unique_lock<Mutex> sync(m_lock);
+	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::unique_lock<Mutex> sync(m_lock);
+	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::unique_lock<Mutex> sync(m_lock);
+		// 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp
new file mode 100644
index 0000000..339ff7c
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Ultrasonic.cpp
@@ -0,0 +1,304 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.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;
+Task Ultrasonic::m_task("UltrasonicChecker", (FUNCPTR)UltrasonicChecker); // task doing the round-robin automatic sensing
+Ultrasonic *Ultrasonic::m_firstSensor = NULL; // head of the ultrasonic sensor list
+bool Ultrasonic::m_automaticEnabled = false; // automatic round robin mode
+SEMAPHORE_ID Ultrasonic::m_semaphore = 0;
+
+/**
+ * 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 = NULL;
+	while (m_automaticEnabled)
+	{
+		if (u == NULL) u = m_firstSensor;
+		if (u == NULL) 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;
+	if (m_semaphore == 0) m_semaphore = initializeSemaphore(SEMAPHORE_FULL);
+	SetAutomaticMode(false); // kill task when adding a new sensor
+	takeSemaphore(m_semaphore); // link this instance on the list
+	{
+		m_nextSensor = m_firstSensor;
+		m_firstSensor = this;
+	}
+	giveSemaphore(m_semaphore);
+
+	m_counter = new Counter(m_echoChannel); // set up counter for this sensor
+	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);
+}
+
+/**
+ * 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 = new DigitalOutput(pingChannel);
+	m_echoChannel = new DigitalInput(echoChannel);
+	m_allocatedChannels = true;
+	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)
+{
+	if (pingChannel == NULL || echoChannel == NULL)
+	{
+		wpi_setWPIError(NullParameter);
+		return;
+	}
+	m_allocatedChannels = false;
+	m_pingChannel = pingChannel;
+	m_echoChannel = 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_allocatedChannels = false;
+	m_pingChannel = &pingChannel;
+	m_echoChannel = &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);
+	if (m_allocatedChannels)
+	{
+		delete m_pingChannel;
+		delete m_echoChannel;
+	}
+	wpi_assert(m_firstSensor != NULL);
+
+	takeSemaphore(m_semaphore);
+	{
+		if (this == m_firstSensor)
+		{
+			m_firstSensor = m_nextSensor;
+			if (m_firstSensor == NULL)
+			{
+				SetAutomaticMode(false);
+			}
+		}
+		else
+		{
+			wpi_assert(m_firstSensor->m_nextSensor != NULL);
+			for (Ultrasonic *s = m_firstSensor; s != NULL; s = s->m_nextSensor)
+			{
+				if (this == s->m_nextSensor)
+				{
+					s->m_nextSensor = s->m_nextSensor->m_nextSensor;
+					break;
+				}
+			}
+		}
+	}
+	giveSemaphore(m_semaphore);
+	if (m_firstSensor != NULL && 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 preffered, 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 != NULL; 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.Start();
+	}
+	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 != NULL; u = u->m_nextSensor)
+		{
+			u->m_counter->Reset();
+		}
+		m_task.Stop();
+	}
+}
+
+/**
+ * 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()
+{
+	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()
+{
+	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()
+{
+	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;
+	}
+}
+
+/**
+ * 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()
+{
+	return m_units;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Utility.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Utility.cpp
new file mode 100644
index 0000000..d94472b
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Utility.cpp
@@ -0,0 +1,271 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+static bool suspendOnAssertEnabled = false;
+
+/**
+ * Enable suspend on assert.
+ * If enabled, the user task will be suspended whenever an assert fails. This
+ * will allow the user to attach to the task with the debugger and examine variables
+ * around the failure.
+ */
+void wpi_suspendOnAssertEnabled(bool enabled)
+{
+	suspendOnAssertEnabled = enabled;
+}
+
+/**
+ * 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)
+		{
+			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);
+
+		if (suspendOnAssertEnabled) suspendTask(0);
+	}
+
+	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)
+	{
+		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);
+
+	if (suspendOnAssertEnabled) suspendTask(0);
+}
+
+/**
+ * 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, NULL, &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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Victor.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Victor.cpp
new file mode 100644
index 0000000..c1cfb71
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Victor.cpp
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * 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"
+ */
+void Victor::InitVictor() {
+	SetBounds(2.027, 1.525, 1.507, 1.49, 1.026);
+
+	SetPeriodMultiplier(kPeriodMultiplier_2X);
+	SetRaw(m_centerPwm);
+	SetZeroLatch();
+
+	HALReport(HALUsageReporting::kResourceType_Victor, GetChannel());
+}
+
+/**
+ * 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)
+{
+	InitVictor();
+}
+
+Victor::~Victor()
+{
+}
+
+/**
+ * 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(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()
+{
+	return GetSpeed();
+}
+
+/**
+ * Common interface for disabling a motor.
+ */
+void Victor::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 Victor::PIDWrite(float output)
+{
+	Set(output);
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/VictorSP.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/VictorSP.cpp
new file mode 100644
index 0000000..39cdda6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/VictorSP.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "NetworkCommunication/UsageReporting.h"
+
+/**
+ * Common initialization code called by all constructors.
+ *
+ * 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"
+ */
+void VictorSP::InitVictorSP() {
+	SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+	SetPeriodMultiplier(kPeriodMultiplier_1X);
+	SetRaw(m_centerPwm);
+	SetZeroLatch();
+
+	HALReport(HALUsageReporting::kResourceType_Talon, GetChannel());
+}
+
+/**
+ * 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)
+{
+	InitVictorSP();
+}
+
+VictorSP::~VictorSP()
+{
+}
+
+/**
+ * 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(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()
+{
+	return GetSpeed();
+}
+
+/**
+ * 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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/AxisCamera.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/AxisCamera.cpp
new file mode 100644
index 0000000..47658d0
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/AxisCamera.cpp
@@ -0,0 +1,645 @@
+/*----------------------------------------------------------------------------*/
+/* 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_cameraSocket(-1)
+		, m_freshImage(false)
+		, m_brightness(50)
+		, m_whiteBalance(kWhiteBalance_Automatic)
+		, m_colorLevel(50)
+		, m_exposureControl(kExposureControl_Automatic)
+		, m_exposurePriority(50)
+		, m_maxFPS(0)
+		, m_resolution(kResolution_640x480)
+		, m_compression(50)
+		, m_rotation(kRotation_0)
+		, m_parametersDirty(true)
+		, m_streamDirty(true)
+		, m_done(false)
+{
+	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<std::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()
+{
+	HSLImage *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<std::mutex> lock(m_imageDataMutex);
+	if (destImage == NULL)
+		wpi_setWPIErrorWithContext(NullParameter, "destImage must not be NULL");
+
+	if (m_imageData.size() == 0)
+		return 0; // if no source image
+
+	if (destImageBufferSize < m_imageData.size()) // if current destination buffer too small
+	{
+		if (*destImage != NULL) delete [] *destImage;
+		destImageBufferSize = m_imageData.size() + kImageBufferAllocationIncrement;
+		*destImage = new char[destImageBufferSize];
+		if (*destImage == NULL) return 0;
+	}
+	// copy this image into destination buffer
+	if (*destImage == NULL)
+	{
+		wpi_setWPIErrorWithContext(NullParameter, "*destImage must not be NULL");
+	}
+	
+	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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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<std::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 = NULL;
+	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 (NULL != strstr(trailingPtr, "\r\n\r\n"))
+			{
+				--counter;
+			}
+			if (++trailingCounter >= 4)
+			{
+				trailingPtr++;
+			}
+		}
+		counter = 1;
+		char *contentLength = strstr(initialReadBuffer, "Content-Length: ");
+		if (contentLength == NULL)
+		{
+			wpi_setWPIErrorWithContext(IncompatibleMode,
+					"No content-length token found in packet");
+			close(m_cameraSocket);
+			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 == NULL)
+			{
+				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<std::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 = 0;
+	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", 0, &address) == -1)
+	{
+		if (setError) wpi_setErrnoErrorWithContext("Failed to create the camera socket");
+		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");
+		close(camSocket);
+		return -1;
+	}
+
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/BaeUtilities.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/BaeUtilities.cpp
new file mode 100644
index 0000000..8804411
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/BaeUtilities.cpp
@@ -0,0 +1,385 @@
+/*----------------------------------------------------------------------------*/
+/* 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"
+
+/**
+ *   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);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+")) != NULL)	  {
+	    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+")) != NULL)	{
+	  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+")) != NULL)	{
+	  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 != NULL) {
+    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(NULL, 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;
+	int stringSize = 80;		// max size of one line in file 
+	char inputStr[stringSize];
+	int lineCount=0;
+	  
+	if (lineNumber < 0)
+		  return (-1);
+
+	if ((infile = fopen (inputFile, "r")) == NULL) {
+	    printf ("Fatal error opening file %s\n",inputFile);
+	    return (0);
+	}
+
+  while (!feof(infile)) {
+    if (fgets (inputStr, stringSize, infile) != NULL) {
+      // 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
+  if (lineCount) {
+    stripString(inputStr);
+    strcpy(outputString, inputStr);
+    return(lineCount);
+  } 
+  else {
+    return(-1);
+  }
+}
+
+/** Ignore empty string 
+ * @param string to check if empty
+ **/
+int emptyString(char *string)
+{
+  int i,len;
+
+  if(string == NULL)
+    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 == NULL)
+    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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/BinaryImage.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/BinaryImage.cpp
new file mode 100644
index 0000000..b6b0ced
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/BinaryImage.cpp
@@ -0,0 +1,222 @@
+/*----------------------------------------------------------------------------*/
+/* 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;
+
+
+BinaryImage::BinaryImage() : MonoImage()
+{
+}
+
+BinaryImage::~BinaryImage()
+{
+}
+
+/**
+ * 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()
+{
+	vector<ParticleAnalysisReport>* 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)
+{
+	BinaryImage *result = new BinaryImage();
+	int success = imaqSizeFilter(result->GetImaqImage(), m_imaqImage, connectivity8, erosions, IMAQ_KEEP_LARGE, NULL);
+	wpi_setImaqErrorWithContext(success, "Error in RemoveSmallObjects");
+	return result;
+}
+
+BinaryImage *BinaryImage::RemoveLargeObjects(bool connectivity8, int erosions)
+{
+	BinaryImage *result = new BinaryImage();
+	int success = imaqSizeFilter(result->GetImaqImage(), m_imaqImage, connectivity8, erosions, IMAQ_KEEP_SMALL, NULL);
+	wpi_setImaqErrorWithContext(success, "Error in RemoveLargeObjects");
+	return result;
+}
+
+BinaryImage *BinaryImage::ConvexHull(bool connectivity8)
+{
+	BinaryImage *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)
+{
+	BinaryImage *result = new BinaryImage();
+	int numParticles;
+	ParticleFilterOptions2 filterOptions = {0, 0, 0, 1};
+	int success = imaqParticleFilter4(result->GetImaqImage(), m_imaqImage, criteria, criteriaCount, &filterOptions, NULL, &numParticles);
+	wpi_setImaqErrorWithContext(success, "Error in particle filter operation");
+	return result;
+}
+
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/ColorImage.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/ColorImage.cpp
new file mode 100644
index 0000000..aa72da3
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/ColorImage.cpp
@@ -0,0 +1,465 @@
+/*----------------------------------------------------------------------------*/
+/* 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)
+{
+}
+
+ColorImage::~ColorImage()
+{
+}
+
+/**
+ * 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)
+{
+	BinaryImage *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)
+{
+	MonoImage *result = new MonoImage();
+	if (m_imaqImage == NULL)
+		wpi_setWPIError(NullParameter);
+	int success = imaqExtractColorPlanes(m_imaqImage, 
+										 mode, 
+										 (planeNumber == 1) ? result->GetImaqImage() : NULL, 
+										 (planeNumber == 2) ? result->GetImaqImage() : NULL, 
+										 (planeNumber == 3) ? result->GetImaqImage() : NULL);
+	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() : NULL, 
+									     (planeNumber == 2) ? plane->GetImaqImage() : NULL, 
+									     (planeNumber == 3) ? plane->GetImaqImage() : NULL);
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/FrcError.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/FrcError.cpp
new file mode 100644
index 0000000..109dea6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/FrcError.cpp
@@ -0,0 +1,1227 @@
+/*----------------------------------------------------------------------------*/
+/* 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_NULL_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_NULL";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_NULL";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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/HSLImage.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/HSLImage.cpp
new file mode 100644
index 0000000..1a66949
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/HSLImage.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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, NULL, NULL);
+	wpi_setImaqErrorWithContext(success, "Imaq ReadFile error");
+}
+
+HSLImage::~HSLImage()
+{
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/ImageBase.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/ImageBase.cpp
new file mode 100644
index 0000000..ba549b6
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/ImageBase.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* 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, NULL);
+	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, NULL, &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, NULL);
+	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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/MonoImage.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/MonoImage.cpp
new file mode 100644
index 0000000..17efe20
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/MonoImage.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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)
+{
+}
+
+MonoImage::~MonoImage()
+{
+}
+
+/**
+ * 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);
+	vector<EllipseMatch> *ellipses = new vector<EllipseMatch>;
+	if (e == NULL)
+	{
+		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, NULL,
+			NULL, NULL);
+	return ellipses;
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/RGBImage.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/RGBImage.cpp
new file mode 100644
index 0000000..a34212e
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/RGBImage.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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, NULL, NULL);
+	wpi_setImaqErrorWithContext(success, "Imaq ReadFile error");
+}
+
+RGBImage::~RGBImage()
+{
+}
diff --git a/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/Threshold.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/Threshold.cpp
new file mode 100644
index 0000000..1d81b38
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/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/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/VisionAPI.cpp b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/VisionAPI.cpp
new file mode 100644
index 0000000..7ac3ac9
--- /dev/null
+++ b/aos/externals/allwpilib/wpilibc/wpilibC++Devices/src/Vision/VisionAPI.cpp
@@ -0,0 +1,665 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+/*   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 NULL.
+*/
+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 NULL.
+* 
+* @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 != NULL )     {
+    	success = imaqDispose(disposalPtr);
+        if (!success) {returnValue = 0;}
+        disposalPtr = va_arg( disposalPtrList, void* );
+    }
+    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 NULL. 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 NULL
+ * 
+ * @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, NULL, NULL);
+ }
+
+
+ /**
+ * @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 NULL. 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 = NULL;
+	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 NULL. 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 NULL; }	
+
+	/* make a mask from the ROI */
+	Image* pMask = frcCreateImage(IMAQ_IMAGE_U8);
+	success = imaqROIToMask(pMask, pRoi, fillValue, NULL, NULL);
+	if ( !success )	{ 
+		GetLastVisionError(); 
+		frcDispose(__FUNCTION__, pRoi, NULL); 
+		return NULL; 
+	}	
+	
+	/* get a histogram report */
+	HistogramReport* pHr = NULL;
+	pHr = imaqHistogram(image, numClasses, min, max, pMask); 
+	
+	/* clean up */
+	frcDispose(__FUNCTION__, pRoi, pMask, NULL); 
+	
+	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 NULL 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 NULL.  
+* To get extended error information, call imaqGetLastError(). 
+*/
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode)
+{	
+	return frcColorHistogram(image, numClasses, mode, NULL);
+}
+
+ColorHistogramReport* frcColorHistogram(const Image* image, int numClasses, ColorMode mode, Image* mask)
+{
+	return imaqColorHistogram2((Image*)image, numClasses, mode, NULL, 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 NULL.
+* 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 NULL.
+* 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, NULL);
+}
+
+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 NULL 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, NULL);  }
+
+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 NULL 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 NULL 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 NULL 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 NULL 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 NULL 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 NULL 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 NULL 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 NULL 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 NULL 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, NULL, NULL);
+}
+
+
+
+
+
+
+
+