Squashed 'third_party/Phoenix-frc-lib/' content from commit 666d176

Change-Id: Ibaca2fc8ffb1177e786576cc1e4cc9f7a8c98f13
git-subtree-dir: third_party/Phoenix-frc-lib
git-subtree-split: 666d176a08151793044ab74e0005f13d3732ed96
diff --git a/libraries/driver/include/ctre/phoenix/CANifierControlFrame.h b/libraries/driver/include/ctre/phoenix/CANifierControlFrame.h
new file mode 100644
index 0000000..e5adbf8
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CANifierControlFrame.h
@@ -0,0 +1,13 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+
+/** Enumerated type for status frame types. */
+enum CANifierControlFrame {
+	CANifier_Control_1_General = 0x03040000,
+	CANifier_Control_2_PwmOutput = 0x03040040,
+};
+
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/CANifierFaults.h b/libraries/driver/include/ctre/phoenix/CANifierFaults.h
new file mode 100644
index 0000000..c663dc9
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CANifierFaults.h
@@ -0,0 +1,24 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+
+struct CANifierFaults {
+	//!< True iff any of the above flags are true.
+	bool HasAnyFault() const {
+		return false;
+	}
+	int ToBitfield() const {
+		int retval = 0;
+		return retval;
+	}
+	CANifierFaults(int bits) {
+		(void)bits;
+	}
+	CANifierFaults() {
+	}
+};
+
+} // phoenix
+} // ctre
+
diff --git a/libraries/driver/include/ctre/phoenix/CANifierStatusFrame.h b/libraries/driver/include/ctre/phoenix/CANifierStatusFrame.h
new file mode 100644
index 0000000..240fc88
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CANifierStatusFrame.h
@@ -0,0 +1,18 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+
+/** Enumerated type for status frame types. */
+enum CANifierStatusFrame {
+	CANifierStatusFrame_Status_1_General = 0x041400,
+	CANifierStatusFrame_Status_2_General = 0x041440,
+	CANifierStatusFrame_Status_3_PwmInputs0 = 0x041480,
+	CANifierStatusFrame_Status_4_PwmInputs1 = 0x0414C0,
+	CANifierStatusFrame_Status_5_PwmInputs2 = 0x041500,
+	CANifierStatusFrame_Status_6_PwmInputs3 = 0x041540,
+	CANifierStatusFrame_Status_8_Misc = 0x0415C0,
+};
+
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/CANifierStickyFaults.h b/libraries/driver/include/ctre/phoenix/CANifierStickyFaults.h
new file mode 100644
index 0000000..5246208
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CANifierStickyFaults.h
@@ -0,0 +1,23 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+
+struct CANifierStickyFaults {
+	//!< True iff any of the above flags are true.
+	bool HasAnyFault() const {
+		return false;
+	}
+	int ToBitfield() const {
+		int retval = 0;
+		return retval;
+	}
+	CANifierStickyFaults(int bits) {
+		(void)bits;
+	}
+	CANifierStickyFaults() {
+	}
+};
+
+} // phoenix
+} // ctre
diff --git a/libraries/driver/include/ctre/phoenix/CANifierVelocityMeasPeriod.h b/libraries/driver/include/ctre/phoenix/CANifierVelocityMeasPeriod.h
new file mode 100644
index 0000000..46fb2c5
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CANifierVelocityMeasPeriod.h
@@ -0,0 +1,18 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+
+enum CANifierVelocityMeasPeriod {
+	Period_1Ms = 1,
+	Period_2Ms = 2,
+	Period_5Ms = 5,
+	Period_10Ms = 10,
+	Period_20Ms = 20,
+	Period_25Ms = 25,
+	Period_50Ms = 50,
+	Period_100Ms = 100,
+};
+
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/CCI/CANifier_CCI.h b/libraries/driver/include/ctre/phoenix/CCI/CANifier_CCI.h
new file mode 100644
index 0000000..6228a0d
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CCI/CANifier_CCI.h
@@ -0,0 +1,54 @@
+#pragma once
+
+#include "ctre/phoenix/ErrorCode.h"
+#include <set>
+
+namespace CANifier_CCI{
+	enum GeneralPin{
+	QUAD_IDX = 0,
+	QUAD_B = 1,
+	QUAD_A = 2,
+	LIMR = 3,
+	LIMF = 4,
+	SDA = 5,
+	SCL = 6,
+	SPI_CS = 7,
+	SPI_MISO_PWM2P = 8,
+	SPI_MOSI_PWM1P = 9,
+	SPI_CLK_PWM0P = 10,
+	};
+}
+
+extern "C"{
+	void *c_CANifier_Create1(int deviceNumber);
+	ctre::phoenix::ErrorCode c_CANifier_GetDescription(void *handle, char * toFill, int toFillByteSz, int * numBytesFilled);
+	ctre::phoenix::ErrorCode c_CANifier_SetLEDOutput(void *handle,  uint32_t  dutyCycle,  uint32_t  ledChannel);
+	ctre::phoenix::ErrorCode c_CANifier_SetGeneralOutputs(void *handle,  uint32_t  outputsBits,  uint32_t  isOutputBits);
+	ctre::phoenix::ErrorCode c_CANifier_SetGeneralOutput(void *handle,  uint32_t  outputPin,  bool  outputValue,  bool  outputEnable);
+	ctre::phoenix::ErrorCode c_CANifier_SetPWMOutput(void *handle,  uint32_t  pwmChannel,  uint32_t  dutyCycle);
+	ctre::phoenix::ErrorCode c_CANifier_EnablePWMOutput(void *handle, uint32_t pwmChannel, bool bEnable);
+	ctre::phoenix::ErrorCode c_CANifier_GetGeneralInputs(void *handle, bool allPins[], uint32_t capacity);
+	ctre::phoenix::ErrorCode c_CANifier_GetGeneralInput(void *handle, uint32_t inputPin, bool * measuredInput);
+	ctre::phoenix::ErrorCode c_CANifier_GetPWMInput(void *handle,  uint32_t  pwmChannel,  double dutyCycleAndPeriod [2]);
+	ctre::phoenix::ErrorCode c_CANifier_GetLastError(void *handle);
+	ctre::phoenix::ErrorCode c_CANifier_GetBusVoltage(void *handle, double * batteryVoltage);
+	ctre::phoenix::ErrorCode c_CANifier_GetQuadraturePosition(void *handle, int * pos);
+	ctre::phoenix::ErrorCode c_CANifier_SetQuadraturePosition(void *handle, int pos, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_GetQuadratureVelocity(void *handle, int * vel);
+	ctre::phoenix::ErrorCode c_CANifier_GetQuadratureSensor(void *handle, int * pos, int * vel);
+	ctre::phoenix::ErrorCode c_CANifier_ConfigVelocityMeasurementPeriod(void *handle, int period, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_ConfigVelocityMeasurementWindow(void *handle, int window, int timeoutMs);
+	void c_CANifier_SetLastError(void *handle, int error);
+	ctre::phoenix::ErrorCode c_CANifier_ConfigSetParameter(void *handle, int param, double value, int subValue, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_ConfigGetParameter(void *handle, int param, double *value, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_ConfigSetCustomParam(void *handle, int newValue, int paramIndex, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_ConfigGetCustomParam(void *handle, int *readValue, int paramIndex, int timoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_GetFaults(void *handle, int * param) ;
+	ctre::phoenix::ErrorCode c_CANifier_GetStickyFaults(void *handle, int * param) ;
+	ctre::phoenix::ErrorCode c_CANifier_ClearStickyFaults(void *handle, int timeoutMs) ;
+	ctre::phoenix::ErrorCode c_CANifier_GetFirmwareVersion(void *handle, int *firmwareVers);
+	ctre::phoenix::ErrorCode c_CANifier_HasResetOccurred(void *handle, bool * hasReset);
+	ctre::phoenix::ErrorCode c_CANifier_SetStatusFramePeriod(void *handle, int frame, int periodMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_GetStatusFramePeriod(void *handle, int frame, int *periodMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_CANifier_SetControlFramePeriod(void *handle, int frame,	int periodMs) ;
+}
diff --git a/libraries/driver/include/ctre/phoenix/CCI/Logger_CCI.h b/libraries/driver/include/ctre/phoenix/CCI/Logger_CCI.h
new file mode 100644
index 0000000..14a6c0e
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CCI/Logger_CCI.h
@@ -0,0 +1,11 @@
+#pragma once
+
+#include "ctre/phoenix/ErrorCode.h"
+#include <string>
+
+extern "C" {
+	void c_Logger_Close();
+	void c_Logger_Open(int language, bool logDriverStation);
+	ctre::phoenix::ErrorCode c_Logger_Log(ctre::phoenix::ErrorCode code, const char* origin, int hierarchy, const char *stacktrace);
+	void c_Logger_Description(ctre::phoenix::ErrorCode code, std::string & shortDescripToFill, std::string & longDescripToFill);
+}
diff --git a/libraries/driver/include/ctre/phoenix/CCI/MotController_CCI.h b/libraries/driver/include/ctre/phoenix/CCI/MotController_CCI.h
new file mode 100644
index 0000000..a66f9bd
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CCI/MotController_CCI.h
@@ -0,0 +1,132 @@
+#include "ctre/phoenix/ErrorCode.h"
+
+extern "C"{
+	void* c_MotController_Create1(int baseArbId);
+
+	ctre::phoenix::ErrorCode c_MotController_GetDeviceNumber(void *handle, int *deviceNumber);
+	ctre::phoenix::ErrorCode c_MotController_GetDescription(void *handle, char * toFill, int toFillByteSz, int * numBytesFilled);
+	ctre::phoenix::ErrorCode c_MotController_SetDemand(void *handle, int mode, int demand0, int demand1);
+	ctre::phoenix::ErrorCode c_MotController_Set_4(void *handle, int mode, double demand0, double demand1, int demand1Type);
+	void c_MotController_SetNeutralMode(void *handle, int neutralMode);
+	void c_MotController_SetSensorPhase(void *handle, bool PhaseSensor);
+	void c_MotController_SetInverted(void *handle, bool invert);
+	ctre::phoenix::ErrorCode c_MotController_ConfigOpenLoopRamp(void *handle, double secondsFromNeutralToFull, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigClosedLoopRamp(void *handle, double secondsFromNeutralToFull, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigPeakOutputForward(void *handle, double percentOut, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigPeakOutputReverse(void *handle, double percentOut, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigNominalOutputForward(void *handle, double percentOut, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigNominalOutputReverse(void *handle, double percentOut, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigNeutralDeadband(void *handle, double percentDeadband, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigVoltageCompSaturation(void *handle, double voltage, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigVoltageMeasurementFilter(void *handle, int filterWindowSamples, int timeoutMs);
+	void c_MotController_EnableVoltageCompensation(void *handle, bool enable);
+	ctre::phoenix::ErrorCode c_MotController_GetBusVoltage(void *handle, double *voltage);
+	ctre::phoenix::ErrorCode c_MotController_GetMotorOutputPercent(void *handle, double *percentOutput);
+	ctre::phoenix::ErrorCode c_MotController_GetOutputCurrent(void *handle, double *current);
+	ctre::phoenix::ErrorCode c_MotController_GetTemperature(void *handle, double *temperature);
+	ctre::phoenix::ErrorCode c_MotController_ConfigSelectedFeedbackSensor(void *handle, int feedbackDevice, int pidIdx, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigSelectedFeedbackCoefficient(void *handle, double coefficient, int pidIdx, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigRemoteFeedbackFilter(void *handle, int deviceID, int remoteSensorSource, int remoteOrdinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigSensorTerm(void *handle, int sensorTerm, int feedbackDevice, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetSelectedSensorPosition(void *handle, int *param, int pidIdx);
+	ctre::phoenix::ErrorCode c_MotController_GetSelectedSensorVelocity(void *handle, int *param, int pidIdx);
+	ctre::phoenix::ErrorCode c_MotController_SetSelectedSensorPosition(void *handle, int sensorPos, int pidIdx,int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_SetControlFramePeriod(void *handle, int frame, int periodMs);
+	ctre::phoenix::ErrorCode c_MotController_SetStatusFramePeriod(void *handle, int frame, int periodMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetStatusFramePeriod(void *handle, int frame, int *periodMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigVelocityMeasurementPeriod(void *handle, int period, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigVelocityMeasurementWindow(void *handle, int windowSize, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigForwardLimitSwitchSource(void *handle, int type, int normalOpenOrClose, int deviceID, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigReverseLimitSwitchSource(void *handle, int type, int normalOpenOrClose, int deviceID, int timeoutMs);
+	void c_MotController_OverrideLimitSwitchesEnable(void *handle, bool enable);
+	ctre::phoenix::ErrorCode c_MotController_ConfigForwardSoftLimitThreshold(void *handle, int forwardSensorLimit, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigReverseSoftLimitThreshold(void *handle, int reverseSensorLimit, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigForwardSoftLimitEnable(void *handle, bool enable, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigReverseSoftLimitEnable(void *handle, bool enable, int timeoutMs);
+	void c_MotController_OverrideSoftLimitsEnable(void *handle, bool enable);
+	ctre::phoenix::ErrorCode c_MotController_Config_kP(void *handle, int slotIdx, double value, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_Config_kI(void *handle, int slotIdx, double value, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_Config_kD(void *handle, int slotIdx, double value, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_Config_kF(void *handle, int slotIdx, double value, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_Config_IntegralZone(void *handle, int slotIdx, double izone, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigAllowableClosedloopError(void *handle, int slotIdx, int allowableClosedLoopError, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigMaxIntegralAccumulator(void *handle, int slotIdx, double iaccum, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigClosedLoopPeakOutput(void *handle, int slotIdx, double percentOut, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigClosedLoopPeriod(void *handle, int slotIdx, int loopTimeMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_SetIntegralAccumulator(void *handle, double iaccum, int pidIdx, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetClosedLoopError(void *handle, int *closedLoopError, int pidIdx);
+	ctre::phoenix::ErrorCode c_MotController_GetIntegralAccumulator(void *handle, double *iaccum, int pidIdx);
+	ctre::phoenix::ErrorCode c_MotController_GetErrorDerivative(void *handle, double *derror, int pidIdx);
+	ctre::phoenix::ErrorCode c_MotController_SelectProfileSlot(void *handle, int slotIdx, int pidIdx);
+	ctre::phoenix::ErrorCode c_MotController_GetActiveTrajectoryPosition(void *handle, int *param);
+	ctre::phoenix::ErrorCode c_MotController_GetActiveTrajectoryVelocity(void *handle, int *param);
+	ctre::phoenix::ErrorCode c_MotController_GetActiveTrajectoryHeading(void *handle, double *param);
+	ctre::phoenix::ErrorCode c_MotController_GetActiveTrajectoryAll(void *handle, int * vel, int * pos, double *heading);
+	ctre::phoenix::ErrorCode c_MotController_ConfigMotionCruiseVelocity(void *handle, int sensorUnitsPer100ms, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigMotionAcceleration(void *handle, int sensorUnitsPer100msPerSec, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ClearMotionProfileTrajectories(void *handle);
+	ctre::phoenix::ErrorCode c_MotController_GetMotionProfileTopLevelBufferCount(void *handle, int * value);
+	ctre::phoenix::ErrorCode c_MotController_PushMotionProfileTrajectory(void *handle, double position,
+			double velocity, double headingDeg, int profileSlotSelect, bool isLastPoint, bool zeroPos);
+ctre::phoenix::ErrorCode c_MotController_PushMotionProfileTrajectory_2(
+		void *handle, double position, double velocity, double headingDeg,
+		int profileSlotSelect0, int profileSlotSelect1, bool isLastPoint, bool zeroPos, int durationMs);
+	ctre::phoenix::ErrorCode c_MotController_IsMotionProfileTopLevelBufferFull(void *handle, bool * value);
+	ctre::phoenix::ErrorCode c_MotController_ProcessMotionProfileBuffer(void *handle);
+	ctre::phoenix::ErrorCode c_MotController_GetMotionProfileStatus(void *handle,
+			int *topBufferRem, int *topBufferCnt, int *btmBufferCnt,
+			bool *hasUnderrun, bool *isUnderrun, bool *activePointValid,
+			bool *isLast, int *profileSlotSelect, int *outputEnable);
+	ctre::phoenix::ErrorCode c_MotController_GetMotionProfileStatus_2(void *handle,
+			int *topBufferRem, int *topBufferCnt, int *btmBufferCnt,
+			bool *hasUnderrun, bool *isUnderrun, bool *activePointValid,
+			bool *isLast, int *profileSlotSelect, int *outputEnable, int *timeDurMs,
+			int *profileSlotSelect1);
+	ctre::phoenix::ErrorCode c_MotController_ClearMotionProfileHasUnderrun(void *handle,
+			int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ChangeMotionControlFramePeriod(void *handle,
+			int periodMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigMotionProfileTrajectoryPeriod(
+			void *handle, int durationMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetLastError(void *handle);
+	ctre::phoenix::ErrorCode c_MotController_GetFirmwareVersion(void *handle, int *);
+	ctre::phoenix::ErrorCode c_MotController_HasResetOccurred(void *handle,bool *);
+	ctre::phoenix::ErrorCode c_MotController_ConfigSetCustomParam(void *handle, int newValue, int paramIndex, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigGetCustomParam(void *handle, int *readValue, int paramIndex, int timoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigSetParameter(void *handle, int param, double value, int subValue, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigGetParameter(void *handle, int param, double *value, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigPeakCurrentLimit(void *handle, int amps, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigPeakCurrentDuration(void *handle, int milliseconds, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_ConfigContinuousCurrentLimit(void *handle, int amps, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_EnableCurrentLimit(void *handle, bool enable);
+	ctre::phoenix::ErrorCode c_MotController_SetLastError(void *handle, int error);
+	ctre::phoenix::ErrorCode c_MotController_GetAnalogIn(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_SetAnalogPosition(void *handle,int newPosition, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetAnalogInRaw(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetAnalogInVel(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetQuadraturePosition(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_SetQuadraturePosition(void *handle,int newPosition, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetQuadratureVelocity(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetPulseWidthPosition(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_SetPulseWidthPosition(void *handle,int newPosition, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_GetPulseWidthVelocity(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetPulseWidthRiseToFallUs(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetPulseWidthRiseToRiseUs(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetPinStateQuadA(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetPinStateQuadB(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetPinStateQuadIdx(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_IsFwdLimitSwitchClosed(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_IsRevLimitSwitchClosed(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetFaults(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_GetStickyFaults(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_MotController_ClearStickyFaults(void *handle, int timeoutMs);
+	ctre::phoenix::ErrorCode c_MotController_SelectDemandType(void *handle, bool enable);
+	ctre::phoenix::ErrorCode c_MotController_SetMPEOutput(void *handle, int MpeOutput);
+	ctre::phoenix::ErrorCode c_MotController_EnableHeadingHold(void *handle, bool enable);
+	ctre::phoenix::ErrorCode c_MotController_GetAnalogInAll(void *handle, int * withOv, int * raw, int * vel);
+	ctre::phoenix::ErrorCode c_MotController_GetQuadratureSensor(void *handle, int * pos, int * vel);
+	ctre::phoenix::ErrorCode c_MotController_GetPulseWidthAll(void *handle, int * pos, int * vel, int * riseToRiseUs, int * riseToFallUs);
+	ctre::phoenix::ErrorCode c_MotController_GetQuadPinStates(void *handle, int * quadA, int * quadB, int * quadIdx);
+	ctre::phoenix::ErrorCode c_MotController_GetLimitSwitchState(void *handle, int * isFwdClosed, int * isRevClosed);
+	ctre::phoenix::ErrorCode c_MotController_GetClosedLoopTarget(void *handle, int * value, int pidIdx);
+}
diff --git a/libraries/driver/include/ctre/phoenix/CCI/PigeonIMU_CCI.h b/libraries/driver/include/ctre/phoenix/CCI/PigeonIMU_CCI.h
new file mode 100644
index 0000000..f95b6ae
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/CCI/PigeonIMU_CCI.h
@@ -0,0 +1,84 @@
+/*
+ *  Software License Agreement
+ *
+ * Copyright (C) Cross The Road Electronics.  All rights
+ * reserved.
+ * 
+ * Cross The Road Electronics (CTRE) licenses to you the right to 
+ * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
+ * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
+ * 
+ * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
+ * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
+ * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
+ * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL, 
+ * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
+ * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
+ * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
+ * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
+ * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
+ * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
+ */
+ 
+ #pragma once
+ 
+#include "ctre/phoenix/ErrorCode.h"
+ #include <map>
+ 
+ static std::map<void *, bool> pigeonPresent;
+ 
+ extern "C"{
+	void *c_PigeonIMU_Create2(int talonDeviceID);
+	void *c_PigeonIMU_Create1(int deviceNumber);
+	// void c_PigeonIMU_Destroy(void *handle);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetDescription(void *handle, char * toFill, int toFillByteSz, int * numBytesFilled);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigSetParameter(void *handle, int param, double paramValue, int subValue, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigGetParameter(void *handle, int param, double *value, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigSetCustomParam(void *handle, int newValue, int paramIndex, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigGetCustomParam(void *handle, int *readValue, int paramIndex, int timoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetYaw(void *handle, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_AddYaw(void *handle, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetYawToCompass(void *handle, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetFusedHeading(void *handle, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_AddFusedHeading(void *handle, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetFusedHeadingToCompass(void *handle, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetAccumZAngle(void *handle, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigTemperatureCompensationEnable(void *handle, int bTempCompEnable, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetCompassDeclination(void *handle, double angleDegOffset, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetCompassAngle(void *handle, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_EnterCalibrationMode(void *handle, int calMode, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetGeneralStatus(void *handle, int *state, int *currentMode, int *calibrationError, int *bCalIsBooting, double *tempC, int *upTimeSec, int *noMotionBiasCount, int *tempCompensationCount, int *lastError);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetLastError(void *handle);
+	ctre::phoenix::ErrorCode c_PigeonIMU_Get6dQuaternion(void *handle, double wxyz[4]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetYawPitchRoll(void *handle, double ypr[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetAccumGyro(void *handle, double xyz_deg[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetAbsoluteCompassHeading(void *handle, double *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetCompassHeading(void *handle, double *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetCompassFieldStrength(void *handle, double *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetTemp(void *handle, double *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetState(void *handle, int *state);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetUpTime(void *handle, int *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetRawMagnetometer(void *handle, short rm_xyz[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetBiasedMagnetometer(void *handle, short bm_xyz[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetBiasedAccelerometer(void *handle, short ba_xyz[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetRawGyro(void *handle, double xyz_dps[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetAccelerometerAngles(void *handle, double tiltAngles[3]);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetFusedHeading2(void *handle, int *bIsFusing, int *bIsValid, double *value, int *lastError);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetFusedHeading1(void *handle, double *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetResetCount(void *handle, int *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetResetFlags(void *handle, int *value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetFirmwareVersion(void *handle, int * firmwareVers);
+	ctre::phoenix::ErrorCode c_PigeonIMU_HasResetOccurred(void *handle, bool * hasReset);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetLastError(void *handle, int value);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigSetCustomParam(void *handle, int newValue, int paramIndex, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigGetCustomParam(void *handle, int *readValue, int paramIndex, int timoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigSetParameter(void *handle, int param, double value, int subValue, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ConfigGetParameter(void *handle, int param, double *value, int ordinal, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetFaults(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetStickyFaults(void *handle, int * param);
+	ctre::phoenix::ErrorCode c_PigeonIMU_ClearStickyFaults(void *handle, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetStatusFramePeriod(void *handle, int frame, int periodMs, int timeoutMs);
+	ctre::phoenix::ErrorCode c_PigeonIMU_GetStatusFramePeriod(void *handle, int frame, int *periodMs, int timeoutMs) ;
+	ctre::phoenix::ErrorCode c_PigeonIMU_SetControlFramePeriod(void *handle, int frame, int periodMs) ;
+}
diff --git a/libraries/driver/include/ctre/phoenix/ErrorCode.h b/libraries/driver/include/ctre/phoenix/ErrorCode.h
new file mode 100644
index 0000000..889f436
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/ErrorCode.h
@@ -0,0 +1,86 @@
+#pragma once
+#include <stdint.h>
+
+namespace ctre {
+namespace phoenix {
+
+enum ErrorCode
+: int32_t
+{
+	OK = 0, 
+	OKAY = 0,		//!< No Error - Function executed as expected
+
+	//CAN-Related
+	CAN_MSG_STALE = 1,
+	CAN_TX_FULL = -1,
+	TxFailed = -1,				//!< Could not transmit the CAN frame.
+	InvalidParamValue = -2, 	//!< Caller passed an invalid param
+	CAN_INVALID_PARAM = -2,
+	RxTimeout = -3,	//!< CAN frame has not been received within specified period of time.
+	CAN_MSG_NOT_FOUND = -3,
+	TxTimeout = -4,				//!< Not used.
+	CAN_NO_MORE_TX_JOBS = -4,
+	UnexpectedArbId = -5,		//!< Specified CAN Id is invalid.
+	CAN_NO_SESSIONS_AVAIL = -5,
+	BufferFull = +6,//!< Caller attempted to insert data into a buffer that is full.
+	CAN_OVERFLOW = -6,
+	SensorNotPresent = -7,		//!< Sensor is not present
+	FirmwareTooOld = -8,
+	CouldNotChangePeriod = -9,
+
+
+	//General
+	GeneralError = -100,		//!< User Specified General Error
+	GENERAL_ERROR = -100,
+
+	//Signal
+	SIG_NOT_UPDATED = -200,
+	SigNotUpdated = -200,	//!< Have not received an value response for signal.
+	NotAllPIDValuesUpdated = -201,
+
+	//Gadgeteer Port Error Codes
+	//These include errors between ports and modules
+	GEN_PORT_ERROR = -300,
+	PORT_MODULE_TYPE_MISMATCH = -301,
+
+	//Gadgeteer Module Error Codes
+	//These apply only to the module units themselves
+	GEN_MODULE_ERROR = -400,
+	MODULE_NOT_INIT_SET_ERROR = -401,
+	MODULE_NOT_INIT_GET_ERROR = -402,
+
+	//API
+	WheelRadiusTooSmall = -500,
+	TicksPerRevZero = -501,
+	DistanceBetweenWheelsTooSmall = -502,
+	GainsAreNotSet = -503,
+
+	//Higher Level
+	IncompatibleMode = -600,
+	InvalidHandle = -601,		//!< Handle does not match stored map of handles
+	
+	//Firmware Versions
+	FeatureRequiresHigherFirm = -700,
+	TalonFeatureRequiresHigherFirm = -701,
+
+	//CAN Related
+	PulseWidthSensorNotPresent = 10,	//!< Special Code for "isSensorPresent"
+
+	//General
+	GeneralWarning = 100,
+	FeatureNotSupported = 101, // feature not implement in the API or firmware
+	NotImplemented = 102, // feature not implement in the API
+	FirmVersionCouldNotBeRetrieved = 103,
+	FeaturesNotAvailableYet = 104, // feature will be release in an upcoming release
+	ControlModeNotValid = 105, // Current control mode of motor controller not valid for this call
+
+	ControlModeNotSupportedYet = 106,
+	CascadedPIDNotSupporteYet= 107,
+	AuxiliaryPIDNotSupportedYet= 107,
+	RemoteSensorsNotSupportedYet= 108,
+	MotProfFirmThreshold= 109,
+	MotProfFirmThreshold2 = 110,
+};
+
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/CANBusAddressable.h b/libraries/driver/include/ctre/phoenix/LowLevel/CANBusAddressable.h
new file mode 100644
index 0000000..407bd24
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/CANBusAddressable.h
@@ -0,0 +1,20 @@
+#pragma once
+#include <stdint.h>
+/**
+ * Simple address holder.  This will be removed TBD.
+ */
+class CANBusAddressable {
+
+public:
+	CANBusAddressable(uint8_t deviceNumber) {
+		_deviceNum = deviceNumber;
+	}
+
+	uint8_t GetDeviceNumber() {
+		return _deviceNum;
+	}
+protected:
+private:
+	uint32_t _deviceNum;
+};
+
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/CANifier_LowLevel.h b/libraries/driver/include/ctre/phoenix/LowLevel/CANifier_LowLevel.h
new file mode 100644
index 0000000..f8a5622
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/CANifier_LowLevel.h
@@ -0,0 +1,109 @@
+/*
+ *  Software License Agreement
+ *
+ * Copyright (C) Cross The Road Electronics.  All rights
+ * reserved.
+ * 
+ * Cross The Road Electronics (CTRE) licenses to you the right to 
+ * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
+ * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
+ * 
+ * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
+ * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
+ * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
+ * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL, 
+ * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
+ * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
+ * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
+ * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
+ * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
+ * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
+ */
+
+#pragma once
+
+#include "Device_LowLevel.h"
+#include "ctre/phoenix/ErrorCode.h"
+#include "ctre/phoenix/paramEnum.h"
+#include "ctre/phoenix/CANifierControlFrame.h"
+#include "ctre/phoenix/CANifierFaults.h"
+#include "ctre/phoenix/CANifierStatusFrame.h"
+#include "ctre/phoenix/CANifierStickyFaults.h"
+#include "ctre/phoenix/CANifierVelocityMeasPeriod.h"
+#include <FRC_NetworkCommunication/CANSessionMux.h>  //CAN Comm
+#include <map>
+
+/** 
+ * CANifier Class.
+ * Class supports communicating over CANbus.
+ */
+class LowLevelCANifier : public Device_LowLevel {
+
+public:
+	enum GeneralPin{
+		QUAD_IDX = 0,
+		QUAD_B = 1,
+		QUAD_A = 2,
+		LIMR = 3,
+		LIMF = 4,
+		SDA = 5,
+		SCL = 6,
+		SPI_CS = 7,
+		SPI_MISO_PWM2P = 8,
+		SPI_MOSI_PWM1P = 9,
+		SPI_CLK_PWM0P = 10,
+	};
+
+	explicit LowLevelCANifier(int deviceNumber = 0);
+
+	ctre::phoenix::ErrorCode SetLEDOutput( int  dutyCycle,  int  ledChannel);
+	ctre::phoenix::ErrorCode SetGeneralOutputs( int  outputsBits,  int  isOutputBits);
+	ctre::phoenix::ErrorCode SetGeneralOutput(GeneralPin outputPin, bool bOutputValue, bool bOutputEnable);
+	ctre::phoenix::ErrorCode SetPWMOutput( int  pwmChannel,  int  dutyCycle);
+	ctre::phoenix::ErrorCode EnablePWMOutput( int  pwmChannel,  bool  bEnable);
+	ctre::phoenix::ErrorCode GetGeneralInputs(bool allPins[], uint32_t capacity);
+	ctre::phoenix::ErrorCode GetGeneralInput(GeneralPin inputPin, bool * measuredInput);
+	ctre::phoenix::ErrorCode GetPWMInput( int  pwmChannel,  double dutyCycleAndPeriod[2]);
+	ctre::phoenix::ErrorCode GetLastError();
+	ctre::phoenix::ErrorCode GetBatteryVoltage(double * batteryVoltage);
+	ctre::phoenix::ErrorCode SetLastError(ctre::phoenix::ErrorCode error);
+	ctre::phoenix::ErrorCode GetQuadraturePosition(int * pos);
+	ctre::phoenix::ErrorCode SetQuadraturePosition(int newPosition, int timeoutMs);
+	ctre::phoenix::ErrorCode GetQuadratureVelocity(int * vel);
+	ctre::phoenix::ErrorCode GetQuadratureSensor(int * pos, int * vel);
+	ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(
+			ctre::phoenix::CANifierVelocityMeasPeriod period, int timeoutMs);
+	ctre::phoenix::ErrorCode ConfigVelocityMeasurementWindow(int windowSize, int timeoutMs);
+
+	ctre::phoenix::ErrorCode GetFaults(ctre::phoenix::CANifierFaults & toFill);
+	ctre::phoenix::ErrorCode GetStickyFaults(ctre::phoenix::CANifierStickyFaults & toFill) ;
+	ctre::phoenix::ErrorCode ClearStickyFaults(int timeoutMs) ;
+	ctre::phoenix::ErrorCode SetStatusFramePeriod(ctre::phoenix::CANifierStatusFrame frame, int periodMs, int timeoutMs) ;
+	ctre::phoenix::ErrorCode GetStatusFramePeriod(ctre::phoenix::CANifierStatusFrame frame,
+			int & periodMs, int timeoutMs) ;
+	ctre::phoenix::ErrorCode SetControlFramePeriod(ctre::phoenix::CANifierControlFrame frame,
+			int periodMs);
+
+	const static int kMinFirmwareVersionMajor = 0;
+	const static int kMinFirmwareVersionMinor = 40;
+
+private:
+
+	static const int kDefaultControlPeriodMs = 20;
+	static const int kDefaultPwmOutputPeriodMs = 20;
+
+	bool _SendingPwmOutput = false;
+
+    uint32_t _regInput = 0; //!< Decoded inputs
+    uint32_t _regLat = 0; //!< Decoded output latch
+    uint32_t _regIsOutput = 0; //!< Decoded data direction register
+
+	ctre::phoenix::ErrorCode _lastError = ctre::phoenix::OKAY;
+
+	void CheckFirmVers(int minMajor = kMinFirmwareVersionMajor, int minMinor = kMinFirmwareVersionMinor, 
+							ctre::phoenix::ErrorCode failCode = ctre::phoenix::ErrorCode::FirmwareTooOld);
+	void EnsurePwmOutputFrameIsTransmitting();
+	void EnableFirmStatusFrame(bool enable);
+};
+
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/CTRE_Native_CAN.h b/libraries/driver/include/ctre/phoenix/LowLevel/CTRE_Native_CAN.h
new file mode 100644
index 0000000..207e6c9
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/CTRE_Native_CAN.h
@@ -0,0 +1,7 @@
+#pragma once
+
+#include <FRC_NetworkCommunication/CANSessionMux.h>  //CAN Comm
+
+int CTRE_Native_CAN_GetSendBuffer(int arbId, uint64_t & data);
+int CTRE_Native_CAN_Receive(int arbId, uint64_t & data, int & len, bool allowStale = true);
+int CTRE_Native_CAN_Send(int arbId, uint64_t data, int len, int periodMs);
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/Device_LowLevel.h b/libraries/driver/include/ctre/phoenix/LowLevel/Device_LowLevel.h
new file mode 100644
index 0000000..a20b551
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/Device_LowLevel.h
@@ -0,0 +1,122 @@
+#pragma once
+
+#include <map>
+#include "ctre/phoenix/ErrorCode.h"
+#include "ctre/phoenix/paramEnum.h"
+#include "ctre/phoenix/LowLevel/ResetStats.h"
+#include <FRC_NetworkCommunication/CANSessionMux.h>  // tCANStreamMessage
+
+class Device_LowLevel {
+
+protected:
+	int32_t _baseArbId;
+	/** child class has to provide a way to enable/disable firm status */
+	virtual void EnableFirmStatusFrame(bool enable) = 0;
+	virtual ctre::phoenix::ErrorCode SetLastError(ctre::phoenix::ErrorCode enable) = 0;
+
+	/**
+	 * Change the periodMs of a TALON's status frame.  See kStatusFrame_* enums for
+	 * what's available.
+	 */
+	ctre::phoenix::ErrorCode SetStatusFramePeriod_(int32_t statusArbID, int32_t periodMs,
+			int32_t timeoutMs);
+	ctre::phoenix::ErrorCode GetStatusFramePeriod_(int32_t statusArbID, int32_t &periodMs,
+			int32_t timeoutMs);
+
+	int32_t GetStartupStatus();
+
+	void CheckFirmVers(int minMajor, int minMinor,
+			ctre::phoenix::ErrorCode failCode =
+					ctre::phoenix::ErrorCode::FirmwareTooOld);
+
+	ctre::phoenix::ErrorCode ConfigSetParameter(ctre::phoenix::ParamEnum paramEnum, int32_t value,
+			uint8_t subValue, int32_t ordinal, int32_t timeoutMs);
+
+	ctre::phoenix::ErrorCode ConfigGetParameter(ctre::phoenix::ParamEnum paramEnum, int32_t valueToSend,
+			int32_t & valueReceived, int32_t & subValue, int32_t ordinal,
+			int32_t timeoutMs);
+
+	ctre::phoenix::ErrorCode ConfigGetParameter(ctre::phoenix::ParamEnum paramEnum, int32_t &value,
+			int32_t ordinal, int32_t timeoutMs);
+
+	/** child class should call this once to set the description */
+	void SetDescription(const std::string & description);
+private:
+	std::string _description;
+	int32_t _deviceNumber;
+
+	int32_t _arbIdStartupFrame;
+	int32_t _arbIdFrameApiStatus;
+
+	uint64_t _cache = 0;
+	int32_t _len = 0;
+
+	uint32_t _arbIdParamRequest;
+	uint32_t _arbIdParamResp;
+	uint32_t _arbIdParamSet;
+	int32_t kParamArbIdMask;
+
+	uint32_t _can_h = 0;
+	int32_t _can_stat = 0;
+	struct tCANStreamMessage _msgBuff[20];
+	static const uint32_t kMsgCapacity = 20;
+
+	ResetStats _resetStats;
+	int32_t _firmVers = -1; /* invalid */
+
+	std::map<uint32_t, int32_t> _sigs_Value;
+	std::map<uint32_t, int32_t> _sigs_SubValue;
+	std::map<uint32_t, int32_t> _sigs_Ordinal;
+
+	const int32_t kFullMessageIDMask = 0x1fffffff;
+	const double FLOAT_TO_FXP_10_22 = (double) 0x400000;
+	const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625f;
+	const double FLOAT_TO_FXP_0_8 = (double) 0x100;
+	const double FXP_TO_FLOAT_0_8 = 0.00390625f;
+
+	int _failedVersionChecks = 0;
+	void OpenSessionIfNeedBe();
+	void ProcessStreamMessages();
+
+
+	ctre::phoenix::ErrorCode RequestParam(ctre::phoenix::ParamEnum paramEnum, int32_t value, uint8_t subValue,
+			int32_t ordinal);
+
+	ctre::phoenix::ErrorCode PollForParamResponse(ctre::phoenix::ParamEnum paramEnum, int32_t & value, int32_t & subValue, int32_t & ordinal);
+
+public:
+
+	Device_LowLevel(int32_t baseArbId, int32_t arbIdStartupFrame,
+			int32_t paramReqId, int32_t paramRespId, int32_t paramSetId,
+			int32_t arbIdFrameApiStatus);
+	Device_LowLevel(const Device_LowLevel &) = delete;
+	virtual ~Device_LowLevel() {}
+
+	int GetDeviceNumber();
+	ctre::phoenix::ErrorCode GetDeviceNumber(int & deviceNumber);
+	int32_t GetFirmStatus();
+
+	ctre::phoenix::ErrorCode GetResetCount(int & param);
+	ctre::phoenix::ErrorCode GetResetFlags(int &param);
+	/** return -1 if not available, return 0xXXYY format if available */
+	ctre::phoenix::ErrorCode GetFirmwareVersion(int &param);
+	int GetFirmwareVersion();
+	/**
+	 * @return true iff a reset has occurred since last call.
+	 */
+	ctre::phoenix::ErrorCode HasResetOccurred(bool & param);
+	bool HasResetOccurred();
+
+	ctre::phoenix::ErrorCode ConfigSetParameter(ctre::phoenix::ParamEnum paramEnum, double value,
+			uint8_t subValue, int32_t ordinal, int32_t timeoutMs);
+
+	ctre::phoenix::ErrorCode ConfigGetParameter(ctre::phoenix::ParamEnum paramEnum, double &value,
+			int32_t ordinal, int32_t timeoutMs);
+
+	ctre::phoenix::ErrorCode ConfigSetCustomParam(int value, int paramIndex, int timeoutMs);
+	ctre::phoenix::ErrorCode ConfigGetCustomParam(int & value, int paramIndex, int timeoutMs);
+
+	const std::string & ToString() const;
+
+	void GetDescription(char * toFill, int toFillByteSz, int & numBytesFilled);
+};
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/Logger_LowLevel.h b/libraries/driver/include/ctre/phoenix/LowLevel/Logger_LowLevel.h
new file mode 100644
index 0000000..552c1f2
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/Logger_LowLevel.h
@@ -0,0 +1,60 @@
+#pragma once
+#include "ctre/phoenix/ErrorCode.h"
+#include "ctre/phoenix/paramEnum.h"
+#include <string.h>
+#include <iostream>
+#include <fstream>
+#include <map>
+#include <sys/stat.h>
+#include <vector>
+#include <dirent.h>
+#include <mutex>
+#include <thread>
+
+/* forward prototype */
+namespace ctre {
+namespace phoenix {
+namespace logger {
+class TimestampMsgMap;
+}
+}
+}
+
+class LoggerDriver {
+public:
+	void Looping();
+	void Open(int language, bool logDriverStation);
+	void Close();
+
+	static const int kHierarchyInternal = 0;
+	static const int kHierarchyCCI = 1;
+	static const int kHierarchyJava = 2;
+	static const int kHierarchyAPI = 3;
+
+
+	ctre::phoenix::ErrorCode Log(ctre::phoenix::ErrorCode code, const std::string & origin, int hierarchy, const char *stacktrace);
+	void GetDescription(ctre::phoenix::ErrorCode code, std::string & shrtError, std::string & longError);
+
+	static LoggerDriver & GetInstance();
+private:
+	LoggerDriver();
+	~LoggerDriver();
+	static unsigned long GetDirSize(DIR *t);
+	static std::vector<std::string> OrderedFiles(DIR *directory);
+	
+	ctre::phoenix::logger::TimestampMsgMap * _msgMap;
+
+//	unsigned long startOfSeconds = 0;
+//	//std::map<std::string, unsigned long> timeStamps;
+//	bool writing = false;
+//	bool errorF = false;
+//	bool threadStarted = false;
+//	bool closeThread = false;
+//	std::string buf = "";
+//	std::mutex thisMutex;
+//	std::thread t;
+//	FILE *file = NULL;
+
+	static LoggerDriver *_instance;
+	
+};
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/MotControllerWithBuffer_LowLevel.h b/libraries/driver/include/ctre/phoenix/LowLevel/MotControllerWithBuffer_LowLevel.h
new file mode 100644
index 0000000..221cb3e
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/MotControllerWithBuffer_LowLevel.h
@@ -0,0 +1,112 @@
+#pragma once
+
+#include "ctre/phoenix/LowLevel/MotController_LowLevel.h"
+#include "ctre/phoenix/Motion/TrajectoryPoint.h"
+#include "ctre/phoenix/Motion/MotionProfileStatus.h"
+#include <string>
+#include <stdint.h>
+#include <mutex>
+
+struct _Control_6_MotProfAddTrajPoint_t;
+
+namespace ctre {
+namespace phoenix {
+namespace platform {
+namespace can {
+
+template<typename T> class txTask;
+//class txTask;
+}
+}
+}
+}
+
+
+namespace ctre {
+namespace phoenix {
+namespace motion {
+namespace can {
+class txJob_t;
+}
+}
+}
+}
+
+namespace ctre {
+namespace phoenix {
+namespace motion {
+class TrajectoryBuffer;
+}
+}
+}
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+namespace lowlevel {
+
+class MotControllerWithBuffer_LowLevel: public MotController_LowLevel {
+
+public:
+	MotControllerWithBuffer_LowLevel(int baseArbId);
+	virtual ctre::phoenix::ErrorCode ClearMotionProfileTrajectories();
+	virtual ctre::phoenix::ErrorCode GetMotionProfileTopLevelBufferCount(int & count);
+	virtual ctre::phoenix::ErrorCode PushMotionProfileTrajectory(double position, double velocity, double headingDeg, int profileSlotSelect0, int profileSlotSelect1, bool isLastPoint, bool zeroPos, int durationMs);
+	virtual ctre::phoenix::ErrorCode IsMotionProfileTopLevelBufferFull(bool & param);
+	virtual ctre::phoenix::ErrorCode ProcessMotionProfileBuffer();
+	virtual ctre::phoenix::ErrorCode GetMotionProfileStatus(int &topBufferRem,
+			int &topBufferCnt,
+			int &btmBufferCnt,
+			bool &hasUnderrun,
+			bool &isUnderrun,
+			bool &activePointValid,
+			bool &isLast,
+			int &profileSlotSelect0,
+			int &outputEnable,
+			int &timeDurMs,
+			int &profileSlotSelect1);
+	virtual ctre::phoenix::ErrorCode ClearMotionProfileHasUnderrun(int timeoutMs);
+	virtual ctre::phoenix::ErrorCode ChangeMotionControlFramePeriod(int periodMs);
+	virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryPeriod(int durationMs, int timeoutMs);
+private:
+
+#if 1
+	/**
+	 * To keep buffers from getting out of control, place a cap on the top level buffer.  Calling
+	 * application can stream addition points as they are fed to Talon. Approx memory footprint is
+	 * this capacity X 8 bytes.
+	 */
+
+	/** Buffer for mot prof top data. */
+	ctre::phoenix::motion::TrajectoryBuffer * _motProfTopBuffer;
+	/** Flow control for streaming trajectories. */
+	int32_t _motProfFlowControl = -1;
+
+	/** The mut mot prof. */
+	std::mutex _mutMotProf; // use this std::unique_lock<std::mutex> lck (_mutMotProf);
+
+	/** Frame Period of the motion profile control6 frame. */
+	uint _control6PeriodMs = kDefaultControl6PeriodMs;
+
+	/**
+	 * @return the tx task that transmits Control6 (motion profile control).
+	 *         If it's not scheduled, then schedule it.  This is part
+	 *         of making the lazy-framing that only peforms MotionProf framing
+	 *         when needed to save bandwidth.
+	 */
+	void GetControl6(ctre::phoenix::platform::can::txTask<uint64_t> & toFill);
+	/**
+	 * Caller is either pushing a new motion profile point, or is
+	 * calling the Process buffer routine.  In either case check our
+	 * flow control to see if we need to start sending control6.
+	 */
+	void ReactToMotionProfileCall();
+
+#endif
+};
+
+} // LowLevel
+} // MotorControl
+} // Phoenix
+} // CTRE
+
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/MotController_LowLevel.h b/libraries/driver/include/ctre/phoenix/LowLevel/MotController_LowLevel.h
new file mode 100644
index 0000000..542c151
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/MotController_LowLevel.h
@@ -0,0 +1,222 @@
+#pragma once
+
+#include "ctre/phoenix/ErrorCode.h"
+#include "ctre/phoenix/paramEnum.h"
+#include "ctre/phoenix/LowLevel/Device_LowLevel.h"
+#include "ctre/phoenix/MotorControl/FeedbackDevice.h"
+#include "ctre/phoenix/MotorControl/ControlFrame.h"
+#include "ctre/phoenix/MotorControl/SensorTerm.h"
+#include "ctre/phoenix/MotorControl/RemoteSensorSource.h"
+#include "ctre/phoenix/MotorControl/Faults.h"
+#include "ctre/phoenix/MotorControl/StickyFaults.h"
+#include "ctre/phoenix/MotorControl/NeutralMode.h"
+#include "ctre/phoenix/MotorControl/ControlMode.h"
+#include "ctre/phoenix/MotorControl/LimitSwitchType.h"
+#include "ctre/phoenix/MotorControl/StatusFrame.h"
+#include "ctre/phoenix/MotorControl/VelocityMeasPeriod.h"
+#include <string>
+#include <stdint.h>
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+namespace lowlevel {
+
+class MotController_LowLevel: public Device_LowLevel {
+
+protected:
+	const uint32_t STATUS_01 = 0x041400;
+	const uint32_t STATUS_02 = 0x041440;
+	const uint32_t STATUS_03 = 0x041480;
+	const uint32_t STATUS_04 = 0x0414C0;
+	const uint32_t STATUS_05 = 0x041500;
+	const uint32_t STATUS_06 = 0x041540;
+	const uint32_t STATUS_07 = 0x041580;
+	const uint32_t STATUS_08 = 0x0415C0;
+	const uint32_t STATUS_09 = 0x041600;
+	const uint32_t STATUS_10 = 0x041640;
+	const uint32_t STATUS_11 = 0x041680;
+	const uint32_t STATUS_12 = 0x0416C0;
+	const uint32_t STATUS_13 = 0x041700;
+	const uint32_t STATUS_14 = 0x041740;
+	const uint32_t STATUS_15 = 0x041780;
+
+	const uint32_t CONTROL_1 = 0x040000;
+	//const uint32_t CONTROL_2 = 0x040040;
+	const uint32_t CONTROL_3 = 0x040080;
+	const uint32_t CONTROL_5 = 0x040100;
+	const uint32_t CONTROL_6 = 0x040140;
+
+	const double FLOAT_TO_FXP_10_22 = (double) 0x400000;
+	const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625f;
+
+	const double FLOAT_TO_FXP_0_8 = (double) 0x100;
+	const double FXP_TO_FLOAT_0_8 = 0.00390625f;
+
+	/* Motion Profile Set Output */
+	// Motor output is neutral, Motion Profile Executer is not running.
+	const int kMotionProf_Disabled = 0;
+	// Motor output is updated from Motion Profile Executer, MPE will
+	// process the buffered points.
+	const int kMotionProf_Enable = 1;
+	// Motor output is updated from Motion Profile Executer, MPE will
+	// stay processing current trajectory point.
+	const int kMotionProf_Hold = 2;
+
+	const int kDefaultControl6PeriodMs = 10;
+
+	void EnableFirmStatusFrame(bool enable);
+	ErrorCode SetLastError(ErrorCode errorCode);
+	ErrorCode SetLastError(int errorCode);
+
+	ErrorCode ConfigSingleLimitSwitchSource(
+			LimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose,
+			int deviceIDIfApplicable, int timeoutMs, bool isForward);
+public:
+	MotController_LowLevel(int baseArbId);
+
+	ErrorCode SetDemand(ctre::phoenix::motorcontrol::ControlMode mode, int demand0, int demand1);
+	ErrorCode Set(ctre::phoenix::motorcontrol::ControlMode mode, double demand0, double demand1, int demand1Type);
+	void SelectDemandType(bool enable);
+	void SetMPEOutput(int MpeOutput);
+	void EnableHeadingHold(bool enable);
+	void SetNeutralMode(ctre::phoenix::motorcontrol::NeutralMode neutralMode);
+	void SetSensorPhase(bool PhaseSensor);
+	void SetInverted(bool invert);
+
+	ErrorCode ConfigOpenLoopRamp(double secondsFromNeutralToFull, int timeoutMs);
+	ErrorCode ConfigClosedLoopRamp(double secondsFromNeutralToFull,
+			int timeoutMs);
+	ErrorCode ConfigPeakOutputForward(double percentOut, int timeoutMs);
+	ErrorCode ConfigPeakOutputReverse(double percentOut, int timeoutMs);
+	ErrorCode ConfigNominalOutputForward(double percentOut, int timeoutMs);
+	ErrorCode ConfigNominalOutputReverse(double percentOut, int timeoutMs);
+	ErrorCode ConfigNeutralDeadband(double percentDeadband,
+			int timeoutMs);
+	ErrorCode ConfigVoltageCompSaturation(double voltage, int timeoutMs);
+	ErrorCode ConfigVoltageMeasurementFilter(int filterWindowSamples,
+			int timeoutMs);
+	void EnableVoltageCompensation(bool enable);
+	ErrorCode GetBusVoltage(double & param);
+	ErrorCode GetMotorOutputPercent(double & param);
+	ErrorCode GetOutputCurrent(double & param);
+	ErrorCode GetTemperature(double & param);
+	ErrorCode ConfigSelectedFeedbackSensor(ctre::phoenix::motorcontrol::FeedbackDevice feedbackDevice,
+			int pidIdx, int timeoutMs);
+	ErrorCode ConfigSelectedFeedbackCoefficient(double coefficient, int pidIdx, int timeoutMs);
+	ErrorCode ConfigRemoteFeedbackFilter(int deviceID,
+			RemoteSensorSource remoteSensorSource, int remoteOrdinal, int timeoutMs);
+	ErrorCode ConfigSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs);
+	ErrorCode GetSelectedSensorPosition(int & param, int pidIdx);
+	ErrorCode GetSelectedSensorVelocity(int & param, int pidIdx);
+	ErrorCode SetSelectedSensorPosition(int sensorPos, int pidIdx, int timeoutMs);
+	ErrorCode SetControlFramePeriod(
+			ctre::phoenix::motorcontrol::ControlFrame frame, int periodMs);
+	ErrorCode SetStatusFramePeriod(
+			ctre::phoenix::motorcontrol::StatusFrame frame, int periodMs,
+			int timeoutMs);
+	ErrorCode SetStatusFramePeriod(
+			ctre::phoenix::motorcontrol::StatusFrameEnhanced frame,
+			int periodMs, int timeoutMs);
+	ErrorCode GetStatusFramePeriod(
+			ctre::phoenix::motorcontrol::StatusFrame frame, int & periodMs,
+			int timeoutMs);
+	ErrorCode GetStatusFramePeriod(
+			ctre::phoenix::motorcontrol::StatusFrameEnhanced frame,
+			int & periodMs, int timeoutMs);
+	ErrorCode ConfigVelocityMeasurementPeriod(
+			ctre::phoenix::motorcontrol::VelocityMeasPeriod period,
+			int timeoutMs);
+	ErrorCode ConfigVelocityMeasurementWindow(int windowSize, int timeoutMs);
+	ErrorCode ConfigForwardLimitSwitchSource(
+			ctre::phoenix::motorcontrol::LimitSwitchSource type,
+			ctre::phoenix::motorcontrol::LimitSwitchNormal normalOpenOrClose,
+			int deviceIDIfApplicable, int timeoutMs);
+	ErrorCode ConfigReverseLimitSwitchSource(
+			ctre::phoenix::motorcontrol::LimitSwitchSource type,
+			ctre::phoenix::motorcontrol::LimitSwitchNormal normalOpenOrClose,
+			int deviceIDIfApplicable, int timeoutMs);
+	void OverrideLimitSwitchesEnable(bool enable);
+	ErrorCode ConfigForwardSoftLimitThreshold(int forwardSensorLimit, int timeoutMs);
+	ErrorCode ConfigReverseSoftLimitThreshold(int reverseSensorLimit, int timeoutMs);
+	ErrorCode ConfigForwardSoftLimitEnable(bool enable, int timeoutMs);
+	ErrorCode ConfigReverseSoftLimitEnable(bool enable, int timeoutMs);
+	void OverrideSoftLimitsEnable(bool enable);
+	ErrorCode ConfigPeakCurrentLimit(int amps, int timeoutMs);
+	ErrorCode ConfigPeakCurrentDuration(int milliseconds, int timeoutMs);
+	ErrorCode ConfigContinuousCurrentLimit(int amps, int timeoutMs);
+	void EnableCurrentLimit(bool enable);
+	ErrorCode Config_kP(int slotIdx, double value, int timeoutMs);
+	ErrorCode Config_kI(int slotIdx, double value, int timeoutMs);
+	ErrorCode Config_kD(int slotIdx, double value, int timeoutMs);
+	ErrorCode Config_kF(int slotIdx, double value, int timeoutMs);
+	ErrorCode Config_IntegralZone(int slotIdx, int izone, int timeoutMs);
+	ErrorCode ConfigAllowableClosedloopError(int slotIdx,
+			int allowableCloseLoopError, int timeoutMs);
+	ErrorCode ConfigMaxIntegralAccumulator(int slotIdx, double iaccum,
+			int timeoutMs);
+	ErrorCode ConfigClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs);
+	ErrorCode ConfigClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs);
+	ErrorCode SetIntegralAccumulator(double iaccum, int pidIdx, int timeoutMs);
+	ErrorCode GetClosedLoopError(int & error, int pidIdx);
+	ErrorCode GetIntegralAccumulator(double & iaccum, int pidIdx);
+	ErrorCode GetErrorDerivative(double & derivError, int pidIdx);
+	ErrorCode SelectProfileSlot(int slotIdx, int pidIdx);
+
+	ErrorCode GetFaults(ctre::phoenix::motorcontrol::Faults & toFill);
+	ErrorCode GetStickyFaults(ctre::phoenix::motorcontrol::StickyFaults& toFill);
+	ErrorCode ClearStickyFaults(int timeoutMs);
+
+	ErrorCode GetAnalogInWithOv(int & param);
+	ErrorCode GetAnalogInVel(int & param);
+	ErrorCode GetAnalogInAll(int & withOv, int & vRaw, int & vel);
+	ErrorCode GetQuadraturePosition(int & param);
+	ErrorCode GetQuadratureVelocity(int & param);
+	ErrorCode GetQuadratureSensor(int & pos, int & vel);
+	ErrorCode GetPulseWidthPosition(int & param);
+	ErrorCode GetPulseWidthVelocity(int & param);
+	ErrorCode GetPulseWidthRiseToFallUs(int & param);
+	ErrorCode GetPulseWidthRiseToRiseUs(int & param);
+	ErrorCode GetPulseWidthAll(int & pos, int & vel, int & riseToRiseUs, int & riseToFallUs);
+	ErrorCode GetPinStateQuadA(int & param);
+	ErrorCode GetPinStateQuadB(int & param);
+	ErrorCode GetPinStateQuadIdx(int & param);
+	ErrorCode GetQuadPinStates(int & quadA, int & quadB, int & quadIdx);
+	ErrorCode IsFwdLimitSwitchClosed(int & param);
+	ErrorCode IsRevLimitSwitchClosed(int & param);
+	ErrorCode GetLimitSwitchState(int & isFwdClosed, int & isRevClosed);
+	ErrorCode GetLastError();
+
+	ErrorCode ConfigMotionCruiseVelocity(int sensorUnitsPer100ms, int timeoutMs);
+	ErrorCode ConfigMotionAcceleration(int sensorUnitsPer100msPerSec, int timeoutMs);
+
+	ErrorCode GetClosedLoopTarget(int & value, int pidIdx);
+	ErrorCode GetActiveTrajectoryPosition(int & sensorUnits);
+	ErrorCode GetActiveTrajectoryVelocity(int & sensorUnitsPer100ms);
+	ErrorCode GetActiveTrajectoryHeading(double & turnUnits);
+	ErrorCode GetActiveTrajectoryAll(int & vel, int & pos, double & heading);
+
+	ErrorCode SetAnalogPosition(int newPosition, int timeoutMs);
+	ErrorCode SetQuadraturePosition(int newPosition, int timeoutMs);
+	ErrorCode SetPulseWidthPosition(int newPosition, int timeoutMs);
+
+	const static int kMinFirmwareVersionMajor = 3;
+	const static int kMinFirmwareVersionMinor = 0;
+
+private:
+
+	uint64_t _cache = 0;
+	int32_t _len = 0;
+	ErrorCode _lastError = (ErrorCode)0;
+	int32_t _setPoint = 0;
+	ControlMode _appliedMode = ControlMode::Disabled;
+	void CheckFirmVers(int minMajor = kMinFirmwareVersionMajor, int minMinor = kMinFirmwareVersionMinor, 
+			ErrorCode code = ErrorCode::FirmwareTooOld);
+	int _usingAdvancedFeatures = 0;
+
+};
+
+}
+}
+}
+}
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/PigeonIMU_LowLevel.h b/libraries/driver/include/ctre/phoenix/LowLevel/PigeonIMU_LowLevel.h
new file mode 100644
index 0000000..9f6a3c6
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/PigeonIMU_LowLevel.h
@@ -0,0 +1,273 @@
+/*
+ *  Software License Agreement
+ *
+ * Copyright (C) Cross The Road Electronics.  All rights
+ * reserved.
+ * 
+ * Cross The Road Electronics (CTRE) licenses to you the right to 
+ * use, publish, and distribute copies of CRF (Cross The Road) firmware files (*.crf) and Software
+ * API Libraries ONLY when in use with Cross The Road Electronics hardware products.
+ * 
+ * THE SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT
+ * WARRANTY OF ANY KIND, EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT
+ * LIMITATION, ANY WARRANTY OF MERCHANTABILITY, FITNESS FOR A
+ * PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT SHALL
+ * CROSS THE ROAD ELECTRONICS BE LIABLE FOR ANY INCIDENTAL, SPECIAL, 
+ * INDIRECT OR CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF
+ * PROCUREMENT OF SUBSTITUTE GOODS, TECHNOLOGY OR SERVICES, ANY CLAIMS
+ * BY THIRD PARTIES (INCLUDING BUT NOT LIMITED TO ANY DEFENSE
+ * THEREOF), ANY CLAIMS FOR INDEMNITY OR CONTRIBUTION, OR OTHER
+ * SIMILAR COSTS, WHETHER ASSERTED ON THE BASIS OF CONTRACT, TORT
+ * (INCLUDING NEGLIGENCE), BREACH OF WARRANTY, OR OTHERWISE
+ */
+
+#pragma once
+
+#include "Device_LowLevel.h"
+#include "ctre/phoenix/Sensors/PigeonIMU_ControlFrame.h"
+#include "ctre/phoenix/Sensors/PigeonIMU_Faults.h"
+#include "ctre/phoenix/Sensors/PigeonIMU_StatusFrame.h"
+#include "ctre/phoenix/Sensors/PigeonIMU_StickyFaults.h"
+#include <string>
+
+/** 
+ * Pigeon IMU Class.
+ * Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).
+ */
+class LowLevelPigeonImu : public Device_LowLevel {
+public:
+	/** Data object for holding fusion information. */
+	struct FusionStatus {
+		double heading;
+		bool bIsValid;
+		bool bIsFusing;
+		std::string description;
+		/**
+		 * Same as GetLastError()
+		 */
+		int lastError;
+	};
+	/** Various calibration modes supported by Pigeon. */
+	enum CalibrationMode {
+		BootTareGyroAccel = 0,
+		Temperature = 1,
+		Magnetometer12Pt = 2,
+		Magnetometer360 = 3,
+		Accelerometer = 5,
+	};
+	/** Overall state of the Pigeon. */
+	enum PigeonState {
+		NoComm,
+		Initializing,
+		Ready,
+		UserCalibration,
+	};
+	/**
+	 * Data object for status on current calibration and general status.
+	 *
+	 * Pigeon has many calibration modes supported for a variety of uses.
+	 * The modes generally collects and saves persistently information that makes
+	 * the Pigeon signals more accurate.  This includes collecting temperature, gyro, accelerometer,
+	 * and compass information.
+	 *
+	 * For FRC use-cases, typically compass and temperature calibration is not required.
+	 *
+	 * Additionally when motion driver software in the Pigeon boots, it will perform a fast boot calibration
+	 * to initially bias gyro and setup accelerometer.
+	 *
+	 * These modes can be enabled with the EnterCalibration mode.
+	 *
+	 * When a calibration mode is entered, caller can expect...
+	 *
+	 *  - PigeonState to reset to Initializing and bCalIsBooting is set to true.  Pigeon LEDs will blink the boot pattern.
+	 *  	This is similar to the normal boot cal, however it can an additional ~30 seconds since calibration generally
+	 *  	requires more information.
+	 *  	currentMode will reflect the user's selected calibration mode.
+	 *
+	 *  - PigeonState will eventually settle to UserCalibration and Pigeon LEDs will show cal specific blink patterns.
+	 *  	bCalIsBooting is now false.
+	 *
+	 *  - Follow the instructions in the Pigeon User Manual to meet the calibration specific requirements.
+	 * 		When finished calibrationError will update with the result.
+	 * 		Pigeon will solid-fill LEDs with red (for failure) or green (for success) for ~5 seconds.
+	 * 		Pigeon then perform boot-cal to cleanly apply the newly saved calibration data.
+	 */
+	struct GeneralStatus {
+		/**
+		 * The current state of the motion driver.  This reflects if the sensor signals are accurate.
+		 * Most calibration modes will force Pigeon to reinit the motion driver.
+		 */
+		LowLevelPigeonImu::PigeonState state;
+		/**
+		 * The currently applied calibration mode if state is in UserCalibration or if bCalIsBooting is true.
+		 * Otherwise it holds the last selected calibration mode (when calibrationError was updated).
+		 */
+		LowLevelPigeonImu::CalibrationMode currentMode;
+		/**
+		 * The error code for the last calibration mode.
+		 * Zero represents a successful cal (with solid green LEDs at end of cal)
+		 * and nonzero is a failed calibration (with solid red LEDs at end of cal).
+		 * Different calibration
+		 */
+		int calibrationError;
+		/**
+		 * After caller requests a calibration mode, pigeon will perform a boot-cal before
+		 * entering the requested mode.  During this period, this flag is set to true.
+		 */
+		bool bCalIsBooting;
+		/**
+		 * general string description of current status
+		 */
+		std::string description;
+		/**
+		 * Temperature in Celsius
+		 */
+		double tempC;
+		/**
+		 * Number of seconds Pigeon has been up (since boot).
+		 * This register is reset on power boot or processor reset.
+		 * Register is capped at 255 seconds with no wrap around.
+		 */
+		int upTimeSec;
+		/**
+		 * Number of times the Pigeon has automatically rebiased the gyro.
+		 * This counter overflows from 15 -> 0 with no cap.
+		 */
+		int noMotionBiasCount;
+		/**
+		 * Number of times the Pigeon has temperature compensated the various signals.
+		 * This counter overflows from 15 -> 0 with no cap.
+		 */
+		int tempCompensationCount;
+		/**
+		 * Same as GetLastError()
+		 */
+		int lastError;
+	};
+
+	static LowLevelPigeonImu * CreatePigeon(int deviceNumber, bool talon);
+
+	LowLevelPigeonImu(const LowLevelPigeonImu &) = delete;
+	~LowLevelPigeonImu();
+
+
+	ctre::phoenix::ErrorCode SetLastError(ctre::phoenix::ErrorCode error);
+
+	ctre::phoenix::ErrorCode SetYaw(double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode AddYaw(double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode SetYawToCompass(int timeoutMs);
+
+	ctre::phoenix::ErrorCode SetFusedHeading(double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode AddFusedHeading(double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode SetFusedHeadingToCompass(int timeoutMs);
+	ctre::phoenix::ErrorCode SetAccumZAngle(double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode ConfigTemperatureCompensationEnable(bool bTempCompEnable, int timeoutMs);
+	ctre::phoenix::ErrorCode SetCompassDeclination(double angleDegOffset, int timeoutMs);
+	ctre::phoenix::ErrorCode SetCompassAngle(double angleDeg, int timeoutMs);
+
+	ctre::phoenix::ErrorCode EnterCalibrationMode(CalibrationMode calMode, int timeoutMs);
+	ctre::phoenix::ErrorCode GetGeneralStatus(LowLevelPigeonImu::GeneralStatus & StatusToFill);
+	ctre::phoenix::ErrorCode GetGeneralStatus(int &state, int &currentMode, int &calibrationError, int &bCalIsBooting, double &tempC, int &upTimeSec, int &noMotionBiasCount, int &tempCompensationCount, int &lastError);
+	ctre::phoenix::ErrorCode GetLastError();
+	ctre::phoenix::ErrorCode Get6dQuaternion(double wxyz[4]);
+	ctre::phoenix::ErrorCode GetYawPitchRoll(double ypr[3]);
+	ctre::phoenix::ErrorCode GetAccumGyro(double xyz_deg[3]);
+	ctre::phoenix::ErrorCode GetAbsoluteCompassHeading(double &value);
+	ctre::phoenix::ErrorCode GetCompassHeading(double &value);
+	ctre::phoenix::ErrorCode GetCompassFieldStrength(double &value);
+	ctre::phoenix::ErrorCode GetTemp(double &value);
+	PigeonState GetState();
+	ctre::phoenix::ErrorCode GetState(int &state);
+	ctre::phoenix::ErrorCode GetUpTime(int &value);
+	ctre::phoenix::ErrorCode GetRawMagnetometer(short rm_xyz[3]);
+
+	ctre::phoenix::ErrorCode GetBiasedMagnetometer(short bm_xyz[3]);
+	ctre::phoenix::ErrorCode GetBiasedAccelerometer(short ba_xyz[3]);
+	ctre::phoenix::ErrorCode GetRawGyro(double xyz_dps[3]);
+	ctre::phoenix::ErrorCode GetAccelerometerAngles(double tiltAngles[3]);
+
+	ctre::phoenix::ErrorCode GetFusedHeading(FusionStatus & status, double &value);
+	ctre::phoenix::ErrorCode GetFusedHeading(int &bIsFusing, int &bIsValid,
+			double &value, int &lastError);
+	ctre::phoenix::ErrorCode GetFusedHeading(double &value);
+
+	ctre::phoenix::ErrorCode SetStatusFramePeriod(
+			ctre::phoenix::sensors::PigeonIMU_StatusFrame frame, int periodMs,
+			int timeoutMs);
+	ctre::phoenix::ErrorCode GetStatusFramePeriod(
+			ctre::phoenix::sensors::PigeonIMU_StatusFrame frame, int & periodMs,
+			int timeoutMs);
+	ctre::phoenix::ErrorCode SetControlFramePeriod(
+			ctre::phoenix::sensors::PigeonIMU_ControlFrame frame, int periodMs);
+	ctre::phoenix::ErrorCode GetFaults(
+			ctre::phoenix::sensors::PigeonIMU_Faults & toFill);
+	ctre::phoenix::ErrorCode GetStickyFaults(
+			ctre::phoenix::sensors::PigeonIMU_StickyFaults & toFill);
+	ctre::phoenix::ErrorCode ClearStickyFaults(int timeoutMs);
+
+	static std::string ToString(LowLevelPigeonImu::PigeonState state);
+	static std::string ToString(CalibrationMode cm);
+
+	const static int kMinFirmwareVersionMajor = 0;
+	const static int kMinFirmwareVersionMinor = 40;
+
+protected:
+	virtual void EnableFirmStatusFrame(bool enable);
+private:
+
+	LowLevelPigeonImu(int32_t baseArbId,
+			int32_t arbIdStartupFrame,
+			int32_t paramReqId,
+			int32_t paramRespId,
+			int32_t paramSetId,
+			int32_t arbIdFrameApiStatus,
+			const std::string & description);
+
+	/** firmware state reported over CAN */
+	enum MotionDriverState {
+		Init0 = 0,
+		WaitForPowerOff = 1,
+		ConfigAg = 2,
+		SelfTestAg = 3,
+		StartDMP = 4,
+		ConfigCompass_0 = 5,
+		ConfigCompass_1 = 6,
+		ConfigCompass_2 = 7,
+		ConfigCompass_3 = 8,
+		ConfigCompass_4 = 9,
+		ConfigCompass_5 = 10,
+		SelfTestCompass = 11,
+		WaitForGyroStable = 12,
+		AdditionalAccelAdjust = 13,
+		Idle = 14,
+		Calibration = 15,
+		LedInstrum = 16,
+		Error = 31,
+	};
+	/** sub command for the various Set param enums */
+	enum TareType {
+		SetValue = 0x00, AddOffset = 0x01, MatchCompass = 0x02, SetOffset = 0xFF,
+	};
+
+	/** Portion of the arbID for all status and control frames. */
+	ctre::phoenix::ErrorCode _lastError = ctre::phoenix::OKAY;
+	uint64_t _cache = 0;
+	uint32_t _len = 0;
+
+	void CheckFirmVers(int minMajor = kMinFirmwareVersionMajor, int minMinor = kMinFirmwareVersionMinor);
+	ctre::phoenix::ErrorCode ConfigSetWrapper(ctre::phoenix::ParamEnum paramEnum, TareType tareType, double angleDeg, int timeoutMs);
+	ctre::phoenix::ErrorCode ConfigSetWrapper(ctre::phoenix::ParamEnum paramEnum, double value, int timeoutMs);
+	ctre::phoenix::ErrorCode ReceiveCAN(int arbId);
+	ctre::phoenix::ErrorCode ReceiveCAN(int arbId, bool allowStale);
+	ctre::phoenix::ErrorCode GetTwoParam16(int arbId, short words[2]);
+	ctre::phoenix::ErrorCode GetThreeParam16(int arbId, short words[3]);
+	ctre::phoenix::ErrorCode GetThreeParam16(int arbId, double signals[3], double scalar);
+	int GetThreeFloatAngles(int arbId, double signals[3], double scalar);
+	ctre::phoenix::ErrorCode GetThreeBoundedAngles(int arbId, double boundedAngles[3]);
+	ctre::phoenix::ErrorCode GetFourParam16(int arbId, double params[4], double scalar);
+	ctre::phoenix::ErrorCode GetThreeParam20(int arbId, double param[3], double scalar);
+
+	LowLevelPigeonImu::PigeonState GetState(int errCode, const uint64_t & statusFrame);
+	double GetTemp(const uint64_t & statusFrame);
+};
+
diff --git a/libraries/driver/include/ctre/phoenix/LowLevel/ResetStats.h b/libraries/driver/include/ctre/phoenix/LowLevel/ResetStats.h
new file mode 100644
index 0000000..70912cc
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/LowLevel/ResetStats.h
@@ -0,0 +1,17 @@
+#pragma once
+
+#include <stdint.h>
+
+struct ResetStats
+{
+	int32_t resetCount;
+	int32_t resetFlags;
+	int32_t firmVers;
+	bool hasReset;
+	ResetStats() {
+		resetCount = 0;
+		resetFlags = 0;
+		firmVers = 0;
+		hasReset = false;
+	}
+};
diff --git a/libraries/driver/include/ctre/phoenix/Motion/MotionProfileStatus.h b/libraries/driver/include/ctre/phoenix/Motion/MotionProfileStatus.h
new file mode 100644
index 0000000..55b1fba
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Motion/MotionProfileStatus.h
@@ -0,0 +1,72 @@
+#pragma once
+
+#include "ctre/phoenix/Motion/SetValueMotionProfile.h"
+#include "ctre/phoenix/Motion/TrajectoryPoint.h"
+
+namespace ctre {
+namespace phoenix {
+namespace motion {
+
+/**
+ * Motion Profile Status
+ * This is simply a data transer object.
+ */
+struct MotionProfileStatus {
+	/**
+	 * The available empty slots in the trajectory buffer.
+	 *
+	 * The robot API holds a "top buffer" of trajectory points, so your applicaion
+	 * can dump several points at once.  The API will then stream them into the Talon's
+	 * low-level buffer, allowing the Talon to act on them.
+	 */
+	int topBufferRem;
+	/**
+	 * The number of points in the top trajectory buffer.
+	 */
+	int topBufferCnt;
+	/**
+	 * The number of points in the low level Talon buffer.
+	 */
+	int btmBufferCnt;
+	/**
+	 * Set if isUnderrun ever gets set.
+	 * Only is cleared by clearMotionProfileHasUnderrun() to ensure
+	 * robot logic can react or instrument it.
+	 * @see clearMotionProfileHasUnderrun()
+	 */
+	bool hasUnderrun;
+	/**
+	 * This is set if Talon needs to shift a point from its buffer into
+	 * the active trajectory point however the buffer is empty. This gets cleared
+	 * automatically when is resolved.
+	 */
+	bool isUnderrun;
+	/**
+	 * True if the active trajectory point has not empty, false otherwise.
+	 * The members in activePoint are only valid if this signal is set.
+	 */
+	bool activePointValid;
+
+	bool isLast;
+
+	/** Selected slot for PID Loop 0 */
+	int profileSlotSelect0;
+
+	/** Selected slot for PID Loop 0 */
+	int profileSlotSelect1;
+
+	/**
+	 * The current output mode of the motion profile executer (disabled, enabled, or hold).
+	 * When changing the set() value in MP mode, it's important to check this signal to
+	 * confirm the change takes effect before interacting with the top buffer.
+	 */
+	ctre::phoenix::motion::SetValueMotionProfile outputEnable;
+
+	/** The applied duration of the active trajectory point */
+	int timeDurMs;
+};
+
+} // namespace motion
+} // namespace phoenix
+} // namespace ctre
+
diff --git a/libraries/driver/include/ctre/phoenix/Motion/SetValueMotionProfile.h b/libraries/driver/include/ctre/phoenix/Motion/SetValueMotionProfile.h
new file mode 100644
index 0000000..77d4ea2
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Motion/SetValueMotionProfile.h
@@ -0,0 +1,13 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motion {
+
+enum SetValueMotionProfile {
+	Disable = 0, Enable = 1, Hold = 2,
+};
+
+} // namespace motion
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/Motion/TrajectoryPoint.h b/libraries/driver/include/ctre/phoenix/Motion/TrajectoryPoint.h
new file mode 100644
index 0000000..66a5e59
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Motion/TrajectoryPoint.h
@@ -0,0 +1,79 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motion {
+
+/**
+ * Duration to apply to a particular trajectory pt.
+ * This time unit is ADDED to the existing base time set by
+ * ConfigMotionProfileTrajectoryPeriod().
+ */
+enum TrajectoryDuration {
+	TrajectoryDuration_0ms = 0,
+	TrajectoryDuration_5ms = 5,
+	TrajectoryDuration_10ms = 10,
+	TrajectoryDuration_20ms = 20,
+	TrajectoryDuration_30ms = 30,
+	TrajectoryDuration_40ms = 40,
+	TrajectoryDuration_50ms = 50,
+	TrajectoryDuration_100ms = 100,
+};
+
+/**
+ * Motion Profile Trajectory Point
+ * This is simply a data transfer object.
+ */
+struct TrajectoryPoint {
+	double position; //!< The position to servo to.
+	double velocity; //!< The velocity to feed-forward.
+	double headingDeg; //!< Not used.  Use auxiliaryPos instead. @see auxiliaryPos
+
+	double auxiliaryPos;  //!< The position for auxiliary PID to target.
+
+	/**
+	 * Which slot to get PIDF gains.
+	 * PID is used for position servo.
+	 * F is used as the Kv constant for velocity feed-forward.
+	 * Typically this is hard-coded
+	 * to a particular slot, but you are free to gain schedule if need be.
+	 * gain schedule if need be.
+	 * Choose from [0,3].
+	 */
+	uint32_t profileSlotSelect0;
+
+	/**
+	 * Which slot to get PIDF gains for auxiliary PID.
+	 * This only has impact during MotionProfileArc Control mode.
+	 * Choose from [0,1].
+	 */
+	uint32_t profileSlotSelect1;
+	/**
+	 * Set to true to signal Talon that this is the final point, so do not
+	 * attempt to pop another trajectory point from out of the Talon buffer.
+	 * Instead continue processing this way point.  Typically the velocity
+	 * member variable should be zero so that the motor doesn't spin indefinitely.
+	 */
+	bool isLastPoint;
+	/**
+	 * Set to true to signal Talon to zero the selected sensor.
+	 * When generating MPs, one simple method is to make the first target position zero,
+	 * and the final target position the target distance from the current position.
+	 * Then when you fire the MP, the current position gets set to zero.
+	 * If this is the intent, you can set zeroPos on the first trajectory point.
+	 *
+	 * Otherwise you can leave this false for all points, and offset the positions
+	 * of all trajectory points so they are correct.
+	 */
+	bool zeroPos;
+
+	/**
+	 * Duration to apply this trajectory pt.
+	 * This time unit is ADDED to the existing base time set by
+	 * ConfigMotionProfileTrajectoryPeriod().
+	 */
+	TrajectoryDuration timeDur;
+};
+} // namespace motion
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/ControlFrame.h b/libraries/driver/include/ctre/phoenix/MotorControl/ControlFrame.h
new file mode 100644
index 0000000..683805a
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/ControlFrame.h
@@ -0,0 +1,29 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+//{
+enum ControlFrame {
+	Control_3_General = 0x040080,
+	Control_4_Advanced = 0x0400C0,
+	Control_6_MotProfAddTrajPoint = 0x040140,
+};
+
+enum ControlFrameEnhanced {
+	Control_3_General_ = 0x040080,
+	Control_4_Advanced_ = 0x0400c0,
+	Control_5_FeedbackOutputOverride_ = 0x040100,
+	Control_6_MotProfAddTrajPoint_ = 0x040140,
+};
+class ControlFrameRoutines {
+	static ControlFrameEnhanced Promote(ControlFrame controlFrame) {
+		return (ControlFrameEnhanced) controlFrame;
+	}
+};
+
+}
+}
+}
+
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/ControlMode.h b/libraries/driver/include/ctre/phoenix/MotorControl/ControlMode.h
new file mode 100644
index 0000000..b30d132
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/ControlMode.h
@@ -0,0 +1,22 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum class ControlMode {
+	PercentOutput = 0,
+	Position = 1,
+	Velocity = 2,
+	Current = 3,
+	Follower = 5,
+	MotionProfile = 6,
+	MotionMagic = 7,
+	MotionProfileArc = 10,
+
+	Disabled = 15,
+};
+
+}
+}
+}
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/DemandType.h b/libraries/driver/include/ctre/phoenix/MotorControl/DemandType.h
new file mode 100644
index 0000000..71ef507
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/DemandType.h
@@ -0,0 +1,29 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+/**
+ * How to interpret a demand value.
+ */
+enum DemandType {
+	/**
+	 * Ignore the demand value and apply neutral/no-change.
+	 */
+	DemandType_Neutral = 0,
+	/**
+	 * When closed-looping, set the target of the aux PID loop to the demand value.
+	 *
+	 * When following, follow the processed output of the combined 
+	 * primary/aux PID output.  The demand value is ignored.
+	 */
+	DemandType_AuxPID = 1, //!< Target value of PID loop 1.  When f
+	/**
+	 * When closed-looping, add this arbitrarily to the closed-loop output.
+	 */
+	DemandType_ArbitraryFeedForward = 2, //!< Simply add to the output
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/Faults.h b/libraries/driver/include/ctre/phoenix/MotorControl/Faults.h
new file mode 100644
index 0000000..0b262c2
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/Faults.h
@@ -0,0 +1,95 @@
+#pragma once
+#include <sstream>
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+struct Faults {
+	bool UnderVoltage;
+	bool ForwardLimitSwitch;
+	bool ReverseLimitSwitch;
+	bool ForwardSoftLimit;
+	bool ReverseSoftLimit;
+	bool HardwareFailure;
+	bool ResetDuringEn;
+	bool SensorOverflow;
+	bool SensorOutOfPhase;
+	bool HardwareESDReset;
+	bool RemoteLossOfSignal;
+	//!< True iff any of the above flags are true.
+	bool HasAnyFault() const {
+		return 	UnderVoltage |
+				ForwardLimitSwitch |
+				ReverseLimitSwitch |
+				ForwardSoftLimit |
+				ReverseSoftLimit |
+				HardwareFailure |
+				ResetDuringEn |
+				SensorOverflow |
+				SensorOutOfPhase |
+				HardwareESDReset |
+				RemoteLossOfSignal;
+	}
+	int ToBitfield() const {
+		int retval = 0;
+		int mask = 1;
+		retval |= UnderVoltage ? mask : 0; mask <<= 1;
+		retval |= ForwardLimitSwitch ? mask : 0; mask <<= 1;
+		retval |= ReverseLimitSwitch ? mask : 0; mask <<= 1;
+		retval |= ForwardSoftLimit ? mask : 0; mask <<= 1;
+		retval |= ReverseSoftLimit ? mask : 0; mask <<= 1;
+		retval |= HardwareFailure ? mask : 0; mask <<= 1;
+		retval |= ResetDuringEn ? mask : 0; mask <<= 1;
+		retval |= SensorOverflow ? mask : 0; mask <<= 1;
+		retval |= SensorOutOfPhase ? mask : 0; mask <<= 1;
+		retval |= HardwareESDReset ? mask : 0; mask <<= 1;
+		retval |= RemoteLossOfSignal ? mask : 0; mask <<= 1;
+		return retval;
+	}
+	Faults(int bits) {
+		int mask = 1;
+		UnderVoltage = (bits & mask) ? true : false; mask <<= 1;
+		ForwardLimitSwitch = (bits & mask) ? true : false; mask <<= 1;
+		ReverseLimitSwitch = (bits & mask) ? true : false; mask <<= 1;
+		ForwardSoftLimit = (bits & mask) ? true : false; mask <<= 1;
+		ReverseSoftLimit = (bits & mask) ? true : false; mask <<= 1;
+		HardwareFailure = (bits & mask) ? true : false; mask <<= 1;
+		ResetDuringEn = (bits & mask) ? true : false; mask <<= 1;
+		SensorOverflow = (bits & mask) ? true : false; mask <<= 1;
+		SensorOutOfPhase = (bits & mask) ? true : false; mask <<= 1;
+		HardwareESDReset = (bits & mask) ? true : false; mask <<= 1;
+		RemoteLossOfSignal = (bits & mask) ? true : false; mask <<= 1;
+	}
+	Faults() {
+		UnderVoltage = false;
+		ForwardLimitSwitch = false;
+		ReverseLimitSwitch = false;
+		ForwardSoftLimit = false;
+		ReverseSoftLimit = false;
+		HardwareFailure =false;
+		ResetDuringEn = false;
+		SensorOverflow = false;
+		SensorOutOfPhase = false;
+		HardwareESDReset = false;
+		RemoteLossOfSignal = false;
+	}
+	std::string ToString() {
+		std::stringstream work;
+		work << " UnderVoltage:" << (UnderVoltage ? "1" : "0");
+		work << " ForwardLimitSwitch:" << (ForwardLimitSwitch ? "1" : "0");
+		work << " ReverseLimitSwitch:" << (ReverseLimitSwitch ? "1" : "0");
+		work << " ForwardSoftLimit:" << (ForwardSoftLimit ? "1" : "0");
+		work << " ReverseSoftLimit:" << (ReverseSoftLimit ? "1" : "0");
+		work << " HardwareFailure:" << (HardwareFailure ? "1" : "0");
+		work << " ResetDuringEn:" << (ResetDuringEn ? "1" : "0");
+		work << " SensorOverflow:" << (SensorOverflow ? "1" : "0");
+		work << " SensorOutOfPhase:" << (SensorOutOfPhase ? "1" : "0");
+		work << " HardwareESDReset:" << (HardwareESDReset ? "1" : "0");
+		work << " RemoteLossOfSignal:" << (RemoteLossOfSignal ? "1" : "0");
+		return work.str();
+	}
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/FeedbackDevice.h b/libraries/driver/include/ctre/phoenix/MotorControl/FeedbackDevice.h
new file mode 100644
index 0000000..4262196
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/FeedbackDevice.h
@@ -0,0 +1,46 @@
+#pragma once
+
+#include "ctre/phoenix/ErrorCode.h"
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+/** Motor controller with gadgeteer connector. */
+enum FeedbackDevice {
+	None = -1,
+
+	QuadEncoder = 0,
+	//1
+	Analog = 2,
+	//3
+	Tachometer = 4,
+	PulseWidthEncodedPosition = 8,
+
+	SensorSum = 9,
+	SensorDifference = 10,
+	RemoteSensor0 = 11,
+	RemoteSensor1 = 12,
+	//13
+	//14
+	SoftwareEmulatedSensor  = 15,
+
+	CTRE_MagEncoder_Absolute = PulseWidthEncodedPosition,
+	CTRE_MagEncoder_Relative = QuadEncoder,
+};
+
+enum RemoteFeedbackDevice  {
+	RemoteFeedbackDevice_None = -1,
+
+	RemoteFeedbackDevice_SensorSum = 9,
+	RemoteFeedbackDevice_SensorDifference = 10,
+	RemoteFeedbackDevice_RemoteSensor0 = 11,
+	RemoteFeedbackDevice_RemoteSensor1 = 12,
+	//13
+	//14
+	RemoteFeedbackDevice_SoftwareEmulatedSensor = 15,
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/FollowerType.h b/libraries/driver/include/ctre/phoenix/MotorControl/FollowerType.h
new file mode 100644
index 0000000..221355f
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/FollowerType.h
@@ -0,0 +1,14 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum FollowerType {
+	FollowerType_PercentOutput = 0,
+	FollowerType_AuxOutput1,
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/LimitSwitchType.h b/libraries/driver/include/ctre/phoenix/MotorControl/LimitSwitchType.h
new file mode 100644
index 0000000..8bd2722
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/LimitSwitchType.h
@@ -0,0 +1,35 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum LimitSwitchSource {
+	LimitSwitchSource_FeedbackConnector = 0, /* default */
+	LimitSwitchSource_RemoteTalonSRX = 1,
+	LimitSwitchSource_RemoteCANifier = 2,
+	LimitSwitchSource_Deactivated = 3,
+};
+
+enum RemoteLimitSwitchSource {
+	RemoteLimitSwitchSource_RemoteTalonSRX = 1,
+	RemoteLimitSwitchSource_RemoteCANifier = 2,
+	RemoteLimitSwitchSource_Deactivated = 3,
+};
+
+enum LimitSwitchNormal {
+	LimitSwitchNormal_NormallyOpen = 0,
+	LimitSwitchNormal_NormallyClosed = 1,
+	LimitSwitchNormal_Disabled = 2
+};
+
+class LimitSwitchRoutines {
+public:
+	static LimitSwitchSource Promote(
+			RemoteLimitSwitchSource limitSwitchSource) {
+		return (LimitSwitchSource) limitSwitchSource;
+	}
+};
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/NeutralMode.h b/libraries/driver/include/ctre/phoenix/MotorControl/NeutralMode.h
new file mode 100644
index 0000000..7f40b0c
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/NeutralMode.h
@@ -0,0 +1,18 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum NeutralMode {
+	/** Use the NeutralMode that is set by the jumper wire on the CAN device */
+	EEPROMSetting = 0,
+	/** Stop the motor's rotation by applying a force. */
+    Coast = 1,
+    /** Stop the motor's rotation by applying a force. */
+    Brake = 2,
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/RemoteSensorSource.h b/libraries/driver/include/ctre/phoenix/MotorControl/RemoteSensorSource.h
new file mode 100644
index 0000000..9d2ff77
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/RemoteSensorSource.h
@@ -0,0 +1,25 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum class RemoteSensorSource {
+	RemoteSensorSource_Off,
+	RemoteSensorSource_TalonSRX_SelectedSensor,
+	RemoteSensorSource_Pigeon_Yaw,
+	RemoteSensorSource_Pigeon_Pitch,
+	RemoteSensorSource_Pigeon_Roll,
+	RemoteSensorSource_CANifier_Quadrature,
+	RemoteSensorSource_CANifier_PWMInput0,
+	RemoteSensorSource_CANifier_PWMInput1,
+	RemoteSensorSource_CANifier_PWMInput2,
+	RemoteSensorSource_CANifier_PWMInput3,
+	RemoteSensorSource_GadgeteerPigeon_Yaw,
+	RemoteSensorSource_GadgeteerPigeon_Pitch,
+	RemoteSensorSource_GadgeteerPigeon_Roll,
+};
+
+}
+}
+}
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/SensorTerm.h b/libraries/driver/include/ctre/phoenix/MotorControl/SensorTerm.h
new file mode 100644
index 0000000..7e9a744
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/SensorTerm.h
@@ -0,0 +1,16 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum class SensorTerm {
+	SensorTerm_Sum0,
+	SensorTerm_Sum1,
+	SensorTerm_Diff0,
+	SensorTerm_Diff1,
+};
+
+}
+}
+}
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/StatusFrame.h b/libraries/driver/include/ctre/phoenix/MotorControl/StatusFrame.h
new file mode 100644
index 0000000..f9a1890
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/StatusFrame.h
@@ -0,0 +1,64 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum StatusFrameEnhanced {
+	Status_1_General = 0x1400,
+	Status_2_Feedback0 = 0x1440,
+	Status_4_AinTempVbat = 0x14C0,
+	Status_6_Misc = 0x1540,
+	Status_7_CommStatus = 0x1580,
+	Status_9_MotProfBuffer = 0x1600,
+	/**
+	 * Old name for Status 10 Frame.
+	 * Use Status_10_Targets instead.
+	 */
+	Status_10_MotionMagic = 0x1640,
+	/**
+	 * Correct name for Status 10 Frame.
+	 * Functionally equivalent to Status_10_MotionMagic
+	 */
+	Status_10_Targets = 0x1640,
+	Status_12_Feedback1 = 0x16C0,
+	Status_13_Base_PIDF0 = 0x1700,
+	Status_14_Turn_PIDF1 = 0x1740,
+	Status_15_FirmareApiStatus = 0x1780,
+
+	Status_3_Quadrature = 0x1480,
+	Status_8_PulseWidth = 0x15C0,
+	Status_11_UartGadgeteer = 0x1680,
+};
+
+enum StatusFrame {
+	Status_1_General_ = 0x1400,
+	Status_2_Feedback0_ = 0x1440,
+	Status_4_AinTempVbat_ = 0x14C0,
+	Status_6_Misc_ = 0x1540,
+	Status_7_CommStatus_ = 0x1580,
+	Status_9_MotProfBuffer_ = 0x1600,
+	/**
+	 * Old name for Status 10 Frame.
+	 * Use Status_10_Targets instead.
+	 */
+	Status_10_MotionMagic_ = 0x1640,
+	/**
+	 * Correct name for Status 10 Frame.
+	 * Functionally equivalent to Status_10_MotionMagic
+	 */
+	Status_10_Targets_ = 0x1640,
+	Status_12_Feedback1_ = 0x16C0,
+	Status_13_Base_PIDF0_ = 0x1700,
+	Status_14_Turn_PIDF1_ = 0x1740,
+	Status_15_FirmareApiStatus_ = 0x1780,
+};
+class StatusFrameRoutines {
+public:
+	StatusFrameEnhanced Promote(StatusFrame statusFrame) {
+		return (StatusFrameEnhanced) statusFrame;
+	}
+};
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/StickyFaults.h b/libraries/driver/include/ctre/phoenix/MotorControl/StickyFaults.h
new file mode 100644
index 0000000..f5d7992
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/StickyFaults.h
@@ -0,0 +1,90 @@
+#pragma once
+#include <sstream>
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+struct StickyFaults {
+	bool UnderVoltage;
+	bool ForwardLimitSwitch;
+	bool ReverseLimitSwitch;
+	bool ForwardSoftLimit;
+	bool ReverseSoftLimit;
+	bool ResetDuringEn;
+	bool SensorOverflow;
+	bool SensorOutOfPhase;
+	bool HardwareESDReset;
+	bool RemoteLossOfSignal;
+
+	//!< True iff any of the above flags are true.
+	bool HasAnyFault() const {
+		return 	UnderVoltage |
+				ForwardLimitSwitch |
+				ReverseLimitSwitch |
+				ForwardSoftLimit |
+				ReverseSoftLimit |
+				ResetDuringEn |
+				SensorOverflow |
+				SensorOutOfPhase |
+				HardwareESDReset |
+				RemoteLossOfSignal;
+	}
+	int ToBitfield() const {
+		int retval = 0;
+		int mask = 1;
+		retval |= UnderVoltage ? mask : 0; mask <<= 1;
+		retval |= ForwardLimitSwitch ? mask : 0; mask <<= 1;
+		retval |= ReverseLimitSwitch ? mask : 0; mask <<= 1;
+		retval |= ForwardSoftLimit ? mask : 0; mask <<= 1;
+		retval |= ReverseSoftLimit ? mask : 0; mask <<= 1;
+		retval |= ResetDuringEn ? mask : 0; mask <<= 1;
+		retval |= SensorOverflow ? mask : 0; mask <<= 1;
+		retval |= SensorOutOfPhase ? mask : 0; mask <<= 1;
+		retval |= HardwareESDReset ? mask : 0; mask <<= 1;
+		retval |= RemoteLossOfSignal ? mask : 0; mask <<= 1;
+		return retval;
+	}
+	StickyFaults(int bits) {
+		int mask = 1;
+		UnderVoltage = (bits & mask) ? true : false; mask <<= 1;
+		ForwardLimitSwitch = (bits & mask) ? true : false; mask <<= 1;
+		ReverseLimitSwitch = (bits & mask) ? true : false; mask <<= 1;
+		ForwardSoftLimit = (bits & mask) ? true : false; mask <<= 1;
+		ReverseSoftLimit = (bits & mask) ? true : false; mask <<= 1;
+		ResetDuringEn = (bits & mask) ? true : false; mask <<= 1;
+		SensorOverflow = (bits & mask) ? true : false; mask <<= 1;
+		SensorOutOfPhase = (bits & mask) ? true : false; mask <<= 1;
+		HardwareESDReset = (bits & mask) ? true : false; mask <<= 1;
+		RemoteLossOfSignal = (bits & mask) ? true : false; mask <<= 1;
+	}
+	StickyFaults() {
+		UnderVoltage = false;
+		ForwardLimitSwitch = false;
+		ReverseLimitSwitch = false;
+		ForwardSoftLimit = false;
+		ReverseSoftLimit = false;
+		ResetDuringEn = false;
+		SensorOverflow = false;
+		SensorOutOfPhase = false;
+		HardwareESDReset = false;
+		RemoteLossOfSignal = false;
+	}
+	std::string ToString() {
+		std::stringstream work;
+		work << " UnderVoltage:" << (UnderVoltage ? "1" : "0");
+		work << " ForwardLimitSwitch:" << (ForwardLimitSwitch ? "1" : "0");
+		work << " ReverseLimitSwitch:" << (ReverseLimitSwitch ? "1" : "0");
+		work << " ForwardSoftLimit:" << (ForwardSoftLimit ? "1" : "0");
+		work << " ReverseSoftLimit:" << (ReverseSoftLimit ? "1" : "0");
+		work << " ResetDuringEn:" << (ResetDuringEn ? "1" : "0");
+		work << " SensorOverflow:" << (SensorOverflow ? "1" : "0");
+		work << " SensorOutOfPhase:" << (SensorOutOfPhase ? "1" : "0");
+		work << " HardwareESDReset:" << (HardwareESDReset ? "1" : "0");
+		work << " RemoteLossOfSignal:" << (RemoteLossOfSignal ? "1" : "0");
+		return work.str();
+	}
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/MotorControl/VelocityMeasPeriod.h b/libraries/driver/include/ctre/phoenix/MotorControl/VelocityMeasPeriod.h
new file mode 100644
index 0000000..38cee64
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/MotorControl/VelocityMeasPeriod.h
@@ -0,0 +1,20 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace motorcontrol {
+
+enum VelocityMeasPeriod {
+	Period_1Ms = 1,
+	Period_2Ms = 2,
+	Period_5Ms = 5,
+	Period_10Ms = 10,
+	Period_20Ms = 20,
+	Period_25Ms = 25,
+	Period_50Ms = 50,
+	Period_100Ms = 100,
+};
+
+} // namespace motorcontrol
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_ControlFrame.h b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_ControlFrame.h
new file mode 100644
index 0000000..79d79cc
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_ControlFrame.h
@@ -0,0 +1,14 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace sensors {
+
+/** Enumerated type for status frame types. */
+enum PigeonIMU_ControlFrame {
+	PigeonIMU_CondStatus_Control_1 = 0x00042800,
+};
+
+} // namespace sensors
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_Faults.h b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_Faults.h
new file mode 100644
index 0000000..e9d37b0
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_Faults.h
@@ -0,0 +1,26 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace sensors {
+
+struct PigeonIMU_Faults {
+	//!< True iff any of the above flags are true.
+	bool HasAnyFault() const {
+		return false;
+	}
+	int ToBitfield() const {
+		int retval = 0;
+		return retval;
+	}
+	PigeonIMU_Faults(int bits) {
+		(void)bits;
+	}
+	PigeonIMU_Faults() {
+	}
+};
+
+} // sensors
+} // phoenix
+} // ctre
+
diff --git a/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_StatusFrame.h b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_StatusFrame.h
new file mode 100644
index 0000000..c381511
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_StatusFrame.h
@@ -0,0 +1,24 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace sensors {
+
+/** Enumerated type for status frame types. */
+enum PigeonIMU_StatusFrame {
+	PigeonIMU_CondStatus_1_General = 0x042000,
+	PigeonIMU_CondStatus_9_SixDeg_YPR = 0x042200,
+	PigeonIMU_CondStatus_6_SensorFusion = 0x042140,
+	PigeonIMU_CondStatus_11_GyroAccum = 0x042280,
+	PigeonIMU_CondStatus_2_GeneralCompass = 0x042040,
+	PigeonIMU_CondStatus_3_GeneralAccel = 0x042080,
+	PigeonIMU_CondStatus_10_SixDeg_Quat = 0x042240,
+	PigeonIMU_RawStatus_4_Mag = 0x041CC0,
+	PigeonIMU_BiasedStatus_2_Gyro = 0x041C40,
+	PigeonIMU_BiasedStatus_4_Mag = 0x041CC0,
+	PigeonIMU_BiasedStatus_6_Accel = 0x41D40,
+};
+
+} // namespace sensors
+} // namespace phoenix
+} // namespace ctre
diff --git a/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_StickyFaults.h b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_StickyFaults.h
new file mode 100644
index 0000000..5142a72
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/Sensors/PigeonIMU_StickyFaults.h
@@ -0,0 +1,25 @@
+#pragma once
+
+namespace ctre {
+namespace phoenix {
+namespace sensors {
+
+struct PigeonIMU_StickyFaults {
+	//!< True iff any of the above flags are true.
+	bool HasAnyFault() const {
+		return false;
+	}
+	int ToBitfield() const {
+		int retval = 0;
+		return retval;
+	}
+	PigeonIMU_StickyFaults(int bits) {
+		(void)bits;
+	}
+	PigeonIMU_StickyFaults() {
+	}
+};
+
+} // sensors
+} // phoenix
+} // ctre
diff --git a/libraries/driver/include/ctre/phoenix/core/GadgeteerUartClient.h b/libraries/driver/include/ctre/phoenix/core/GadgeteerUartClient.h
new file mode 100644
index 0000000..2308b61
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/core/GadgeteerUartClient.h
@@ -0,0 +1,69 @@
+#ifndef GadgeteerUartClient_h_
+#define GadgeteerUartClient_h_
+#include <stdint.h>
+#include <string>
+
+class IGadgeteerUartClient
+{
+public:
+	IGadgeteerUartClient() {}
+    virtual ~IGadgeteerUartClient() {}
+
+	enum GadgeteerProxyType
+	{
+		General = 0,
+		Pigeon = 1,
+		PC_HERO = 2,
+	};
+	enum GadgeteerConnection
+	{
+		NotConnected = 0,
+		Connecting = 1,
+		Connected = 2,
+	};
+	struct GadgeteerUartStatus {
+		GadgeteerProxyType type;
+		GadgeteerConnection conn;
+		uint32_t bitrate;
+		uint32_t resetCount;
+	};
+
+    virtual int GetGadgeteerStatus(GadgeteerUartStatus & status) = 0;
+
+    static std::string ToString(IGadgeteerUartClient::GadgeteerProxyType gpt) {
+    	std::string retval;
+		switch(gpt) {
+			case General: retval = "General"; break;
+			case Pigeon : retval = "Pigeon"; break;
+			case PC_HERO: retval = "PC_HERO"; break;
+		}
+		return retval;
+    }
+    static std::string ToString(IGadgeteerUartClient::GadgeteerConnection gc) {
+    	std::string retval;
+		switch(gc) {
+			case NotConnected: retval = "NotConnected"; break;
+			case Connecting : retval = "Connecting"; break;
+			case Connected: retval = "Connected"; break;
+		}
+		return retval;
+    }
+
+protected:
+	enum GadgeteerState
+	{
+		GadState_WaitChirp1 = 0,
+		GadState_WaitBLInfo = 1,
+		GadState_WaitBitrateResp = 2,
+		GadState_WaitSwitchDelay = 3,
+		GadState_WaitChirp2 = 4,
+		GadState_Connected_Idle = 5,
+		GadState_Connected_ReqChirp = 6,
+		GadState_Connected_RespChirp = 7,
+		GadState_Connected_ReqCanBus = 8,
+		GadState_Connected_RespCanBus = 9,
+		GadState_Connected_RespIsoThenChirp = 10,
+		GadState_Connected_RespIsoThenCanBus = 11,
+	};
+};
+#endif
diff --git a/libraries/driver/include/ctre/phoenix/defs/signalTypes.h b/libraries/driver/include/ctre/phoenix/defs/signalTypes.h
new file mode 100644
index 0000000..4a90319
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/defs/signalTypes.h
@@ -0,0 +1,87 @@
+#ifndef signalTypes__h_
+#define signalTypes__h_
+
+enum{
+	modeDutyCycleControl = 0,	//!< Demand is signed 16bit 0.16fixedPt. 7FFF is fullfor.  8000 is fullRev.
+	modePosControl = 1,			//!< Demand 24bit position.
+	modeSpeedControl = 2,		//!< Demand is 24 bit speed.
+	modeCurrentControl = 3,		//!< Demand is 24 bit current.
+	modeSlaveFollower = 5,		//!< Demand is the can node to follow.
+	modeMotionProfile = 6,		//!< Demand is unused,could be used in future. Control6 has everything we want.
+	modeMotionMagic = 7,		//!< Reserved
+	motionMagicArc = 8,
+	//9
+	motionProfileArc = 10,
+	//11
+	//12
+	//13
+#ifdef SUPPORT_ONE_SHOT_CONTROL_MODE
+	modeOneShot = 14,
+#endif
+	modeNoDrive = 15,
+};
+
+typedef enum _feedbackDevice_t{
+	kQuadEncoder = 0,
+	//1
+	kAnalog = 2,
+	//3
+	Tachometer= 4,
+	kPulseWidthEncodedPosition = 8,
+	
+	kSensorSum = 9,
+	kSensorDifference = 10,
+	kRemoteSensor0 = 11,
+	kRemoteSensor1 = 12,
+	//13
+	//14
+	kSoftwarEmulatedSensor=15,
+}feedbackDevice_t;
+
+typedef enum _MotProf_OutputType_t {
+	MotProf_OutputType_Disabled = 0,
+	MotProf_OutputType_Enabled,
+	MotProf_OutputType_Hold,
+	MotProf_OutputType_Invalid,
+}MotProf_OutputType_t;
+
+/**
+ * Saved to limitSwitchForward_Source/limitSwitchReverse_Source
+ */
+typedef enum _LimitSwitchSource_t {
+	LSS_Local=0,
+	LSS_RemoteTalon=1,
+	LSS_RemoteCanif=2,
+	LSS_Deactivated=3,
+}LimitSwitchSource_t;
+
+/**
+ * Saved to limitSwitchForward_normClosedAndDis / limitSwitchReverse_normClosedAndDis
+ */
+typedef enum _LimitSwitchNormClosedAndDis_t {
+	LSNCD_NormallyOpen=0,
+	LSNCD_NormallyClosed=1,
+	LSNCD_NormallyDisabled=2,
+}LimitSwitchNormClosedAndDis_t;
+
+typedef enum _RemoteSensorSource_t {
+	RSS_Off,
+	RSS_RemoteTalonSelSensor,
+	RSS_RemotePigeon_Yaw,
+	RSS_RemotePigeon_Pitch,
+	RSS_RemotePigeon_Roll,
+	RSS_RemoteCanif_Quad,
+	RSS_RemoteCanif_PWM0,
+	RSS_RemoteCanif_PWM1,
+	RSS_RemoteCanif_PWM2,
+	RSS_RemoteCanif_PWM3,
+} RemoteSensorSource_t;
+
+typedef enum _SensorTermOrdinal_t {
+	SensorTermOrdinal_Sum0 = 0,
+	SensorTermOrdinal_Sum1 = 0,
+	SensorTermOrdinal_Diff0 = 0,
+	SensorTermOrdinal_Diff1 = 0,
+}SensorTermOrdinal_t;
+
+#endif // signalTypes__h_
diff --git a/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_CANifierJNI.h b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_CANifierJNI.h
new file mode 100644
index 0000000..deeac53
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_CANifierJNI.h
@@ -0,0 +1,245 @@
+/* DO NOT EDIT THIS FILE - it is machine generated */
+#include <jni.h>
+/* Header for class com_ctre_phoenix_CANifierJNI */
+
+#ifndef _Included_com_ctre_phoenix_CANifierJNI
+#define _Included_com_ctre_phoenix_CANifierJNI
+#ifdef __cplusplus
+extern "C" {
+#endif
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_new_CANifier
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1new_1CANifier
+  (JNIEnv *, jclass, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetLEDOutput
+ * Signature: (JII)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetLEDOutput
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetGeneralOutputs
+ * Signature: (JII)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetGeneralOutputs
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetGeneralOutput
+ * Signature: (JIZZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetGeneralOutput
+  (JNIEnv *, jclass, jlong, jint, jboolean, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetPWMOutput
+ * Signature: (JII)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetPWMOutput
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_EnablePWMOutput
+ * Signature: (JIZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1EnablePWMOutput
+  (JNIEnv *, jclass, jlong, jint, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetGeneralInputs
+ * Signature: (J[Z)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetGeneralInputs
+  (JNIEnv *, jclass, jlong, jbooleanArray);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetGeneralInput
+ * Signature: (JI)Z
+ */
+JNIEXPORT jboolean JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetGeneralInput
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetPWMInput
+ * Signature: (JI[D)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetPWMInput
+  (JNIEnv *, jclass, jlong, jint, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetLastError
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetLastError
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetBatteryVoltage
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetBatteryVoltage
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetQuadraturePosition
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetQuadraturePosition
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetQuadraturePosition
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetQuadraturePosition
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetQuadratureVelocity
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetQuadratureVelocity
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ConfigVelocityMeasurementPeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ConfigVelocityMeasurementPeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ConfigVelocityMeasurementWindow
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ConfigVelocityMeasurementWindow
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ConfigSetCustomParam
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ConfigSetCustomParam
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ConfigGetCustomParam
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ConfigGetCustomParam
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ConfigSetParameter
+ * Signature: (JIDIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ConfigSetParameter
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ConfigGetParameter
+ * Signature: (JIII)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ConfigGetParameter
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetStatusFramePeriod
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetStatusFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetStatusFramePeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetStatusFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_SetControlFramePeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1SetControlFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetFirmwareVersion
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetFirmwareVersion
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_HasResetOccurred
+ * Signature: (J)Z
+ */
+JNIEXPORT jboolean JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1HasResetOccurred
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetFaults
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetFaults
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetStickyFaults
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetStickyFaults
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_ClearStickyFaults
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1ClearStickyFaults
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CANifierJNI
+ * Method:    JNI_GetBusVoltage
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_CANifierJNI_JNI_1GetBusVoltage
+  (JNIEnv *, jclass, jlong);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
diff --git a/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_CTRLoggerJNI.h b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_CTRLoggerJNI.h
new file mode 100644
index 0000000..b4b7ca2
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_CTRLoggerJNI.h
@@ -0,0 +1,53 @@
+/* DO NOT EDIT THIS FILE - it is machine generated */
+#include <jni.h>
+/* Header for class com_ctre_phoenix_CTRLoggerJNI */
+
+#ifndef _Included_com_ctre_phoenix_CTRLoggerJNI
+#define _Included_com_ctre_phoenix_CTRLoggerJNI
+#ifdef __cplusplus
+extern "C" {
+#endif
+/*
+ * Class:     com_ctre_phoenix_CTRLoggerJNI
+ * Method:    JNI_Logger_Close
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CTRLoggerJNI_JNI_1Logger_1Close
+  (JNIEnv *, jclass);
+
+/*
+ * Class:     com_ctre_phoenix_CTRLoggerJNI
+ * Method:    JNI_Logger_Log
+ * Signature: (ILjava/lang/String;Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_CTRLoggerJNI_JNI_1Logger_1Log
+  (JNIEnv *, jclass, jint, jstring, jstring);
+
+/*
+ * Class:     com_ctre_phoenix_CTRLoggerJNI
+ * Method:    JNI_Logger_Open
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_CTRLoggerJNI_JNI_1Logger_1Open
+  (JNIEnv *, jclass, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CTRLoggerJNI
+ * Method:    JNI_Logger_GetShort
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL Java_com_ctre_phoenix_CTRLoggerJNI_JNI_1Logger_1GetShort
+  (JNIEnv *, jclass, jint);
+
+/*
+ * Class:     com_ctre_phoenix_CTRLoggerJNI
+ * Method:    JNI_Logger_GetLong
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL Java_com_ctre_phoenix_CTRLoggerJNI_JNI_1Logger_1GetLong
+  (JNIEnv *, jclass, jint);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
diff --git a/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_MotorControl_CAN_MotControllerJNI.h b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_MotorControl_CAN_MotControllerJNI.h
new file mode 100644
index 0000000..a282095
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_MotorControl_CAN_MotControllerJNI.h
@@ -0,0 +1,844 @@
+/* DO NOT EDIT THIS FILE - it is machine generated */
+#include <jni.h>
+/* Header for class com_ctre_phoenix_motorcontrol_can_MotControllerJNI */
+
+#ifndef _Included_com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+#define _Included_com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+#ifdef __cplusplus
+extern "C" {
+#endif
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Create
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Create
+  (JNIEnv *, jclass, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetDeviceNumber
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetDeviceNumber
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetDemand
+ * Signature: (JIII)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetDemand
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Set_4
+ * Signature: (JIDDI)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Set_14
+  (JNIEnv *, jclass, jlong, jint, jdouble, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetNeutralMode
+ * Signature: (JI)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetNeutralMode
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetSensorPhase
+ * Signature: (JZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetSensorPhase
+  (JNIEnv *, jclass, jlong, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetInverted
+ * Signature: (JZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetInverted
+  (JNIEnv *, jclass, jlong, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigOpenLoopRamp
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigOpenLoopRamp
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigClosedLoopRamp
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigClosedLoopRamp
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigPeakOutputForward
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigPeakOutputForward
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigPeakOutputReverse
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigPeakOutputReverse
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigNominalOutputForward
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigNominalOutputForward
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigNominalOutputReverse
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigNominalOutputReverse
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigNeutralDeadband
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigNeutralDeadband
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigVoltageCompSaturation
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigVoltageCompSaturation
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigVoltageMeasurementFilter
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigVoltageMeasurementFilter
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    EnableVoltageCompensation
+ * Signature: (JZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_EnableVoltageCompensation
+  (JNIEnv *, jclass, jlong, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetBusVoltage
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetBusVoltage
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetMotorOutputPercent
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetMotorOutputPercent
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetOutputCurrent
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetOutputCurrent
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetTemperature
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetTemperature
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigRemoteFeedbackFilter
+ * Signature: (JIIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigRemoteFeedbackFilter
+  (JNIEnv *, jclass, jlong, jint, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigSelectedFeedbackSensor
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigSelectedFeedbackSensor
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigSelectedFeedbackCoefficient
+ * Signature: (JDII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigSelectedFeedbackCoefficient
+  (JNIEnv *, jclass, jlong, jdouble, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetSelectedSensorPosition
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetSelectedSensorPosition
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetSelectedSensorVelocity
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetSelectedSensorVelocity
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetSelectedSensorPosition
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetSelectedSensorPosition
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetControlFramePeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetControlFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetStatusFramePeriod
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetStatusFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetStatusFramePeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetStatusFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigVelocityMeasurementPeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigVelocityMeasurementPeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigVelocityMeasurementWindow
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigVelocityMeasurementWindow
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigForwardLimitSwitchSource
+ * Signature: (JIIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigForwardLimitSwitchSource
+  (JNIEnv *, jclass, jlong, jint, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigReverseLimitSwitchSource
+ * Signature: (JIIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigReverseLimitSwitchSource
+  (JNIEnv *, jclass, jlong, jint, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    EnableLimitSwitches
+ * Signature: (JZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_OverrideLimitSwitchesEnable
+  (JNIEnv *, jclass, jlong, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigForwardSoftLimit
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigForwardSoftLimitThreshold
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigReverseSoftLimit
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigReverseSoftLimitThreshold
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigForwardSoftLimitEnable
+  (JNIEnv *, jclass, jlong, jboolean, jint);
+
+
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigReverseSoftLimitEnable
+  (JNIEnv *, jclass, jlong, jboolean, jint);
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    EnableSoftLimits
+ * Signature: (JZ)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_OverrideSoftLimitsEnable
+  (JNIEnv *, jclass, jlong, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Config_kP
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Config_1kP
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Config_kI
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Config_1kI
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Config_kD
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Config_1kD
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Config_kF
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Config_1kF
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    Config_IntegralZone
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_Config_1IntegralZone
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigAllowableClosedloopError
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigAllowableClosedloopError
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigMaxIntegralAccumulator
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigMaxIntegralAccumulator
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigClosedLoopPeakOutput
+ * Signature: (JIDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigClosedLoopPeakOutput
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigClosedLoopPeriod
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigClosedLoopPeriod
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetIntegralAccumulator
+ * Signature: (JDII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetIntegralAccumulator
+  (JNIEnv *, jclass, jlong, jdouble, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetClosedLoopError
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetClosedLoopError
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetIntegralAccumulator
+ * Signature: (JI)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetIntegralAccumulator
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetErrorDerivative
+ * Signature: (JI)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetErrorDerivative
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SelectProfileSlot
+ * Signature: (JII)V
+ */
+JNIEXPORT void JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SelectProfileSlot
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetActiveTrajectoryPosition
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetActiveTrajectoryPosition
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetActiveTrajectoryVelocity
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetActiveTrajectoryVelocity
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetActiveTrajectoryHeading
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetActiveTrajectoryHeading
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigMotionCruiseVelocity
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigMotionCruiseVelocity
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigMotionAcceleration
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigMotionAcceleration
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ClearMotionProfileTrajectories
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ClearMotionProfileTrajectories
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetMotionProfileTopLevelBufferCount
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetMotionProfileTopLevelBufferCount
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    PushMotionProfileTrajectory
+ * Signature: (JDDDIZZ)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_PushMotionProfileTrajectory
+  (JNIEnv *, jclass, jlong, jdouble, jdouble, jdouble, jint, jboolean, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    PushMotionProfileTrajectory2
+ * Signature: (JDDDIZZ)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_PushMotionProfileTrajectory2
+  (JNIEnv *, jclass, jlong, jdouble, jdouble, jdouble, jint, jint, jboolean, jboolean, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    IsMotionProfileTopLevelBufferFull
+ * Signature: (J)Z
+ */
+JNIEXPORT jboolean JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_IsMotionProfileTopLevelBufferFull
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ProcessMotionProfileBuffer
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ProcessMotionProfileBuffer
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetMotionProfileStatus
+ * Signature: (J[I)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetMotionProfileStatus
+  (JNIEnv *, jclass, jlong, jintArray);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetMotionProfileStatus2
+ * Signature: (J[I)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetMotionProfileStatus2
+  (JNIEnv *, jclass, jlong, jintArray);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ClearMotionProfileHasUnderrun
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ClearMotionProfileHasUnderrun
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ChangeMotionControlFramePeriod
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ChangeMotionControlFramePeriod
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigMotionProfileTrajectoryPeriod
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigMotionProfileTrajectoryPeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetLastError
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetLastError
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetFirmwareVersion
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetFirmwareVersion
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    HasResetOccurred
+ * Signature: (J)Z
+ */
+JNIEXPORT jboolean JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_HasResetOccurred
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigSetCustomParam
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigSetCustomParam
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigGetCustomParam
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigGetCustomParam
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigSetParameter
+ * Signature: (JIDIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigSetParameter
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigGetParameter
+ * Signature: (JIII)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigGetParameter
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigPeakCurrentLimit
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigPeakCurrentLimit
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigPeakCurrentDuration
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigPeakCurrentDuration
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ConfigContinuousCurrentLimit
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ConfigContinuousCurrentLimit
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    EnableCurrentLimit
+ * Signature: (JZ)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_EnableCurrentLimit
+  (JNIEnv *, jclass, jlong, jboolean);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetAnalogIn
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetAnalogIn
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetAnalogPosition
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetAnalogPosition
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetAnalogInRaw
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetAnalogInRaw
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetAnalogInVel
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetAnalogInVel
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetQuadraturePosition
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetQuadraturePosition
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetQuadraturePosition
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetQuadraturePosition
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetQuadratureVelocity
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetQuadratureVelocity
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPulseWidthPosition
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPulseWidthPosition
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetPulseWidthPosition
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetPulseWidthPosition
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPulseWidthVelocity
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPulseWidthVelocity
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPulseWidthRiseToFallUs
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPulseWidthRiseToFallUs
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPulseWidthRiseToRiseUs
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPulseWidthRiseToRiseUs
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPinStateQuadA
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPinStateQuadA
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPinStateQuadB
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPinStateQuadB
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetPinStateQuadIdx
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetPinStateQuadIdx
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    IsFwdLimitSwitchClosed
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_IsFwdLimitSwitchClosed
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    IsRevLimitSwitchClosed
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_IsRevLimitSwitchClosed
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetFaults
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetFaults
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetStickyFaults
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetStickyFaults
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    ClearStickyFaults
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_ClearStickyFaults
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SelectDemandType
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SelectDemandType
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    SetMPEOutput
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_SetMPEOutput
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    EnableHeadingHold
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_EnableHeadingHold
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_motorcontrol_can_MotControllerJNI
+ * Method:    GetClosedLoopTarget
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_motorcontrol_can_MotControllerJNI_GetClosedLoopTarget
+  (JNIEnv *, jclass, jlong, jint);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
diff --git a/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_Sensors_PigeonImuJNI.h b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_Sensors_PigeonImuJNI.h
new file mode 100644
index 0000000..5ba0b5e
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/jni/com_ctre_phoenix_Sensors_PigeonImuJNI.h
@@ -0,0 +1,365 @@
+/* DO NOT EDIT THIS FILE - it is machine generated */
+#include <jni.h>
+/* Header for class com_ctre_phoenix_sensors_PigeonImuJNI */
+
+#ifndef _Included_com_ctre_phoenix_sensors_PigeonImuJNI
+#define _Included_com_ctre_phoenix_sensors_PigeonImuJNI
+#ifdef __cplusplus
+extern "C" {
+#endif
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_new_PigeonImu_Talon
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1new_1PigeonImu_1Talon
+  (JNIEnv *, jclass, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_new_PigeonImu
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1new_1PigeonImu
+  (JNIEnv *, jclass, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_ConfigSetCustomParam
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1ConfigSetCustomParam
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_ConfigGetCustomParam
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1ConfigGetCustomParam
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_ConfigSetParameter
+ * Signature: (JIDIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1ConfigSetParameter
+  (JNIEnv *, jclass, jlong, jint, jdouble, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_ConfigGetParameter
+ * Signature: (JIII)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1ConfigGetParameter
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetStatusFramePeriod
+ * Signature: (JIII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetStatusFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetYaw
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetYaw
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_AddYaw
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1AddYaw
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetYawToCompass
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetYawToCompass
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetFusedHeading
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetFusedHeading
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_AddFusedHeading
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1AddFusedHeading
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetFusedHeadingToCompass
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetFusedHeadingToCompass
+  (JNIEnv *, jclass, jlong, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetAccumZAngle
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetAccumZAngle
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_ConfigTemperatureCompensationEnable
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1ConfigTemperatureCompensationEnable
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetCompassDeclination
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetCompassDeclination
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetCompassAngle
+ * Signature: (JDI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetCompassAngle
+  (JNIEnv *, jclass, jlong, jdouble, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_EnterCalibrationMode
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1EnterCalibrationMode
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetGeneralStatus
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetGeneralStatus
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_Get6dQuaternion
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1Get6dQuaternion
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetYawPitchRoll
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetYawPitchRoll
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetAccumGyro
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetAccumGyro
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetAbsoluteCompassHeading
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetAbsoluteCompassHeading
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetCompassHeading
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetCompassHeading
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetCompassFieldStrength
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetCompassFieldStrength
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetTemp
+ * Signature: (J)D
+ */
+JNIEXPORT jdouble JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetTemp
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetUpTime
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetUpTime
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetRawMagnetometer
+ * Signature: (J[S)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetRawMagnetometer
+  (JNIEnv *, jclass, jlong, jshortArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetBiasedMagnetometer
+ * Signature: (J[S)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetBiasedMagnetometer
+  (JNIEnv *, jclass, jlong, jshortArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetBiasedAccelerometer
+ * Signature: (J[S)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetBiasedAccelerometer
+  (JNIEnv *, jclass, jlong, jshortArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetRawGyro
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetRawGyro
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetAccelerometerAngles
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetAccelerometerAngles
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetFusedHeading
+ * Signature: (J[D)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetFusedHeading
+  (JNIEnv *, jclass, jlong, jdoubleArray);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetState
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetState
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetResetCount
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetResetCount
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetResetFlags
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetResetFlags
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetFirmwareVersion
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetFirmwareVersion
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetLastError
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetLastError
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_HasResetOccurred
+ * Signature: (J)Z
+ */
+JNIEXPORT jboolean JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1HasResetOccurred
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetStatusFramePeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetStatusFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_SetControlFramePeriod
+ * Signature: (JII)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1SetControlFramePeriod
+  (JNIEnv *, jclass, jlong, jint, jint);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetFaults
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetFaults
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_GetStickyFaults
+ * Signature: (J)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1GetStickyFaults
+  (JNIEnv *, jclass, jlong);
+
+/*
+ * Class:     com_ctre_phoenix_sensors_PigeonImuJNI
+ * Method:    JNI_ClearStickyFaults
+ * Signature: (JI)I
+ */
+JNIEXPORT jint JNICALL Java_com_ctre_phoenix_sensors_PigeonImuJNI_JNI_1ClearStickyFaults
+  (JNIEnv *, jclass, jlong, jint);
+
+#ifdef __cplusplus
+}
+#endif
+#endif
diff --git a/libraries/driver/include/ctre/phoenix/paramEnum.h b/libraries/driver/include/ctre/phoenix/paramEnum.h
new file mode 100644
index 0000000..473f6a7
--- /dev/null
+++ b/libraries/driver/include/ctre/phoenix/paramEnum.h
@@ -0,0 +1,115 @@
+#pragma once
+#include <stdint.h>
+
+namespace ctre {
+namespace phoenix {
+
+/**
+ * Signal enumeration for generic signal access.
+ */
+enum ParamEnum
+	: uint32_t
+	{
+	eOnBoot_BrakeMode = 31,
+	eQuadFilterEn = 91,
+	eQuadIdxPolarity=108,
+	eClearPositionOnIdx = 100,
+    eMotionProfileHasUnderrunErr = 119,
+    eMotionProfileTrajectoryPointDurationMs = 120,
+	eClearPosOnLimitF = 144,
+	eClearPosOnLimitR = 145,
+
+	eStatusFramePeriod = 300,
+	eOpenloopRamp = 301,
+	eClosedloopRamp = 302,
+	eNeutralDeadband = 303,
+
+	ePeakPosOutput = 305,
+	eNominalPosOutput = 306,
+	ePeakNegOutput = 307,
+	eNominalNegOutput = 308,
+
+	eProfileParamSlot_P = 310,
+	eProfileParamSlot_I = 311,
+	eProfileParamSlot_D = 312,
+	eProfileParamSlot_F = 313,
+	eProfileParamSlot_IZone = 314,
+	eProfileParamSlot_AllowableErr = 315,
+    eProfileParamSlot_MaxIAccum = 316,
+    eProfileParamSlot_PeakOutput = 317,
+
+	eClearPositionOnLimitF = 320,
+	eClearPositionOnLimitR = 321,
+	eClearPositionOnQuadIdx = 322,
+
+	eSampleVelocityPeriod = 325,
+	eSampleVelocityWindow = 326,
+
+	eFeedbackSensorType = 330, // feedbackDevice_t
+	eSelectedSensorPosition = 331,
+	eFeedbackNotContinuous = 332,
+	eRemoteSensorSource = 333, // RemoteSensorSource_t
+	eRemoteSensorDeviceID = 334, // [0,62] DeviceID
+	eSensorTerm = 335, // feedbackDevice_t (ordinal is the register)
+	eRemoteSensorClosedLoopDisableNeutralOnLOS = 336,
+	ePIDLoopPolarity = 337,
+	ePIDLoopPeriod = 338,
+	eSelectedSensorCoefficient = 339,
+
+	eForwardSoftLimitThreshold = 340,
+	eReverseSoftLimitThreshold = 341,
+	eForwardSoftLimitEnable = 342,
+	eReverseSoftLimitEnable = 343,
+
+	eNominalBatteryVoltage = 350,
+	eBatteryVoltageFilterSize = 351,
+
+	eContinuousCurrentLimitAmps = 360,
+	ePeakCurrentLimitMs = 361,
+	ePeakCurrentLimitAmps = 362,
+
+	eClosedLoopIAccum = 370,
+
+	eCustomParam = 380,
+
+	eStickyFaults = 390,
+
+	eAnalogPosition = 400,
+	eQuadraturePosition = 401,
+	ePulseWidthPosition = 402,
+
+	eMotMag_Accel = 410,
+	eMotMag_VelCruise = 411,
+
+	eLimitSwitchSource = 421, // ordinal (fwd=0,reverse=1), @see LimitSwitchSource_t
+	eLimitSwitchNormClosedAndDis = 422, // ordinal (fwd=0,reverse=1). @see LimitSwitchNormClosedAndDis_t
+	eLimitSwitchDisableNeutralOnLOS = 423,
+	eLimitSwitchRemoteDevID = 424,
+	eSoftLimitDisableNeutralOnLOS = 425,
+
+	ePulseWidthPeriod_EdgesPerRot = 430,
+	ePulseWidthPeriod_FilterWindowSz = 431,
+
+	eYawOffset	=160,
+	eCompassOffset	= 161,
+	eBetaGain =	162,
+	eEnableCompassFusion =	163,
+	eGyroNoMotionCal =	164,
+	eEnterCalibration =	165,
+	eFusedHeadingOffset	= 166,
+	eStatusFrameRate	= 169,
+	eAccumZ	= 170,
+	eTempCompDisable	= 171,
+	eMotionMeas_tap_threshX = 172,
+	eMotionMeas_tap_threshY = 173,
+	eMotionMeas_tap_threshZ = 174,
+	eMotionMeas_tap_count = 175,
+	eMotionMeas_tap_time = 176,
+	eMotionMeas_tap_time_multi = 177,
+	eMotionMeas_shake_reject_thresh = 178,
+	eMotionMeas_shake_reject_time = 179,
+	eMotionMeas_shake_reject_timeout = 180,
+};
+
+}
+}