Squashed 'third_party/allwpilib_2016/' content from commit 7f61816
Change-Id: If9d9245880859cdf580f5d7f77045135d0521ce7
git-subtree-dir: third_party/allwpilib_2016
git-subtree-split: 7f618166ed253a24629934fcf89c3decb0528a3b
diff --git a/hal/build.gradle b/hal/build.gradle
new file mode 100644
index 0000000..d40903e
--- /dev/null
+++ b/hal/build.gradle
@@ -0,0 +1,47 @@
+// There are two hal libraries that are built
+// - Desktop which is used by simulation (gcc/msvc)
+// - Athena which is used by the roborio (arm)
+
+apply plugin: 'cpp'
+
+model {
+ components {
+ HALAthena(NativeLibrarySpec) {
+ targetPlatform 'arm'
+ tasks.withType(CppCompile) {
+ dependsOn addNiLibraryLinks
+ }
+ sources {
+ cpp {
+ source {
+ srcDirs = ["lib/Athena", "lib/Athena/FRC_FPGA_ChipObject", "lib/Shared"]
+ includes = ["**/*.cpp"]
+ }
+ exportedHeaders {
+ srcDirs = ["include", "lib/Athena", "lib/Athena/FRC_FPGA_ChipObject", "lib/Shared"]
+ }
+ }
+ }
+ }
+
+// HALDesktop(NativeLibrarySpec) {
+// binaries.all {
+// if (toolChain in Gcc){
+// cppCompiler.args "-std=c++1y"
+// }
+// }
+//
+// sources {
+// cpp {
+// source {
+// srcDirs = ["lib/Desktop", "lib/Shared"]
+// includes = ["**/*.cpp"]
+// }
+// exportedHeaders {
+// srcDirs = ["include", "lib/Desktop", "lib/Shared"]
+// }
+// }
+// }
+// }
+ }
+}
diff --git a/hal/include/HAL/Accelerometer.hpp b/hal/include/HAL/Accelerometer.hpp
new file mode 100644
index 0000000..103fb2a
--- /dev/null
+++ b/hal/include/HAL/Accelerometer.hpp
@@ -0,0 +1,15 @@
+#pragma once
+
+enum AccelerometerRange {
+ kRange_2G = 0,
+ kRange_4G = 1,
+ kRange_8G = 2,
+};
+
+extern "C" {
+ void setAccelerometerActive(bool);
+ void setAccelerometerRange(AccelerometerRange);
+ double getAccelerometerX();
+ double getAccelerometerY();
+ double getAccelerometerZ();
+}
diff --git a/hal/include/HAL/Analog.hpp b/hal/include/HAL/Analog.hpp
new file mode 100644
index 0000000..2aa5e43
--- /dev/null
+++ b/hal/include/HAL/Analog.hpp
@@ -0,0 +1,78 @@
+#pragma once
+
+#include <stdint.h>
+
+enum AnalogTriggerType
+{
+ kInWindow = 0,
+ kState = 1,
+ kRisingPulse = 2,
+ kFallingPulse = 3
+};
+
+extern "C"
+{
+ // Analog output functions
+ void* initializeAnalogOutputPort(void* port_pointer, int32_t *status);
+ void freeAnalogOutputPort(void* analog_port_pointer);
+ void setAnalogOutput(void* analog_port_pointer, double voltage, int32_t *status);
+ double getAnalogOutput(void* analog_port_pointer, int32_t *status);
+ bool checkAnalogOutputChannel(uint32_t pin);
+
+ // Analog input functions
+ void* initializeAnalogInputPort(void* port_pointer, int32_t *status);
+ void freeAnalogInputPort(void* analog_port_pointer);
+ bool checkAnalogModule(uint8_t module);
+ bool checkAnalogInputChannel(uint32_t pin);
+
+ void setAnalogSampleRate(double samplesPerSecond, int32_t *status);
+ float getAnalogSampleRate(int32_t *status);
+ void setAnalogAverageBits(void* analog_port_pointer, uint32_t bits, int32_t *status);
+ uint32_t getAnalogAverageBits(void* analog_port_pointer, int32_t *status);
+ void setAnalogOversampleBits(void* analog_port_pointer, uint32_t bits, int32_t *status);
+ uint32_t getAnalogOversampleBits(void* analog_port_pointer, int32_t *status);
+ int16_t getAnalogValue(void* analog_port_pointer, int32_t *status);
+ int32_t getAnalogAverageValue(void* analog_port_pointer, int32_t *status);
+ int32_t getAnalogVoltsToValue(void* analog_port_pointer, double voltage, int32_t *status);
+ float getAnalogVoltage(void* analog_port_pointer, int32_t *status);
+ float getAnalogAverageVoltage(void* analog_port_pointer, int32_t *status);
+ uint32_t getAnalogLSBWeight(void* analog_port_pointer, int32_t *status);
+ int32_t getAnalogOffset(void* analog_port_pointer, int32_t *status);
+
+ bool isAccumulatorChannel(void* analog_port_pointer, int32_t *status);
+ void initAccumulator(void* analog_port_pointer, int32_t *status);
+ void resetAccumulator(void* analog_port_pointer, int32_t *status);
+ void setAccumulatorCenter(void* analog_port_pointer, int32_t center, int32_t *status);
+ void setAccumulatorDeadband(void* analog_port_pointer, int32_t deadband, int32_t *status);
+ int64_t getAccumulatorValue(void* analog_port_pointer, int32_t *status);
+ uint32_t getAccumulatorCount(void* analog_port_pointer, int32_t *status);
+ void getAccumulatorOutput(void* analog_port_pointer, int64_t *value, uint32_t *count,
+ int32_t *status);
+
+ void* initializeAnalogTrigger(void* port_pointer, uint32_t *index, int32_t *status);
+ void cleanAnalogTrigger(void* analog_trigger_pointer, int32_t *status);
+ void setAnalogTriggerLimitsRaw(void* analog_trigger_pointer, int32_t lower, int32_t upper,
+ int32_t *status);
+ void setAnalogTriggerLimitsVoltage(void* analog_trigger_pointer, double lower, double upper,
+ int32_t *status);
+ void setAnalogTriggerAveraged(void* analog_trigger_pointer, bool useAveragedValue,
+ int32_t *status);
+ void setAnalogTriggerFiltered(void* analog_trigger_pointer, bool useFilteredValue,
+ int32_t *status);
+ bool getAnalogTriggerInWindow(void* analog_trigger_pointer, int32_t *status);
+ bool getAnalogTriggerTriggerState(void* analog_trigger_pointer, int32_t *status);
+ bool getAnalogTriggerOutput(void* analog_trigger_pointer, AnalogTriggerType type,
+ int32_t *status);
+
+ //// Float JNA Hack
+ // Float
+ int getAnalogSampleRateIntHack(int32_t *status);
+ int getAnalogVoltageIntHack(void* analog_port_pointer, int32_t *status);
+ int getAnalogAverageVoltageIntHack(void* analog_port_pointer, int32_t *status);
+
+ // Doubles
+ void setAnalogSampleRateIntHack(int samplesPerSecond, int32_t *status);
+ int32_t getAnalogVoltsToValueIntHack(void* analog_port_pointer, int voltage, int32_t *status);
+ void setAnalogTriggerLimitsVoltageIntHack(void* analog_trigger_pointer, int lower, int upper,
+ int32_t *status);
+}
diff --git a/hal/include/HAL/CAN.hpp b/hal/include/HAL/CAN.hpp
new file mode 100644
index 0000000..c10450b
--- /dev/null
+++ b/hal/include/HAL/CAN.hpp
@@ -0,0 +1,26 @@
+#pragma once
+
+#include <stdint.h>
+#include "FRC_NetworkCommunication/CANSessionMux.h"
+
+void canTxSend(uint32_t arbID, uint8_t length, int32_t period = CAN_SEND_PERIOD_NO_REPEAT);
+
+void canTxPackInt8 (uint32_t arbID, uint8_t offset, uint8_t value);
+void canTxPackInt16(uint32_t arbID, uint8_t offset, uint16_t value);
+void canTxPackInt32(uint32_t arbID, uint8_t offset, uint32_t value);
+void canTxPackFXP16(uint32_t arbID, uint8_t offset, double value);
+void canTxPackFXP32(uint32_t arbID, uint8_t offset, double value);
+
+uint8_t canTxUnpackInt8 (uint32_t arbID, uint8_t offset);
+uint32_t canTxUnpackInt32(uint32_t arbID, uint8_t offset);
+uint16_t canTxUnpackInt16(uint32_t arbID, uint8_t offset);
+double canTxUnpackFXP16(uint32_t arbID, uint8_t offset);
+double canTxUnpackFXP32(uint32_t arbID, uint8_t offset);
+
+bool canRxReceive(uint32_t arbID);
+
+uint8_t canRxUnpackInt8 (uint32_t arbID, uint8_t offset);
+uint16_t canRxUnpackInt16(uint32_t arbID, uint8_t offset);
+uint32_t canRxUnpackInt32(uint32_t arbID, uint8_t offset);
+double canRxUnpackFXP16(uint32_t arbID, uint8_t offset);
+double canRxUnpackFXP32(uint32_t arbID, uint8_t offset);
diff --git a/hal/include/HAL/CanTalonSRX.h b/hal/include/HAL/CanTalonSRX.h
new file mode 100644
index 0000000..4cbff71
--- /dev/null
+++ b/hal/include/HAL/CanTalonSRX.h
@@ -0,0 +1,421 @@
+/**
+ * @brief CAN TALON SRX driver.
+ *
+ * The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs
+ * with 10ms update rate for control (throttle or setpoint). However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate
+ * The getters for these unsolicited signals are auto generated at the bottom of this module.
+ *
+ * Likewise most control signals are sent periodically using the fire-and-forget CAN API.
+ * The setters for these unsolicited signals are auto generated at the bottom of this module.
+ *
+ * Signals that are not available in an unsolicited fashion are the Close Loop gains.
+ * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once
+ * or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are
+ * loaded in the TALON, they will persist through power cycles and mode changes.
+ *
+ * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from
+ * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.
+ *
+ * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely
+ * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.
+ * If this API is used, be mindful of the CAN utilization reported in the driver station.
+ *
+ * Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode).
+ * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).
+ * Use SetFeedbackDeviceSelect to select which sensor type you need. Once you do that you can use GetSensorPosition()
+ * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by default).
+ * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.
+ *
+ * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.
+ * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation
+ * for "in the pits" checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor
+ * data for processing, not just instrumentation. Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.
+ *
+ * Velocity is in position ticks / 100ms.
+ *
+ * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).
+ * This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).
+ *
+ * Pos and velocity close loops are calc'd as
+ * err = target - posOrVel.
+ * iErr += err;
+ * if( (IZone!=0) and abs(err) > IZone)
+ * ClearIaccum()
+ * output = P X err + I X iErr + D X dErr + F X target
+ * dErr = err - lastErr
+ * P, I,and D gains are always positive. F can be negative.
+ * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.
+ * Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.
+ *
+ * P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1
+ * ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.
+ *
+ * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)
+ * for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.
+ * Close loop and integral accumulator runs every 1ms.
+ *
+ * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)
+ * per change of 1 unit (ADC or encoder) per ms.
+ *
+ * I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of
+ * this value, the integrated error will auto-clear...
+ * if( (IZone!=0) and abs(err) > IZone)
+ * ClearIaccum()
+ * ...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.
+ *
+ * CloseLoopRampRate is in throttle units per 1ms. Set to zero to disable ramping.
+ * Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.
+ *
+ * auto generated using spreadsheet and WpiClassGen.csproj
+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967
+ */
+#ifndef CanTalonSRX_H_
+#define CanTalonSRX_H_
+#include "ctre/ctre.h" //BIT Defines + Typedefs
+#include "ctre/CtreCanNode.h"
+#include <FRC_NetworkCommunication/CANSessionMux.h> //CAN Comm
+#include <map>
+#include <atomic>
+class CanTalonSRX : public CtreCanNode
+{
+private:
+ // Use this for determining whether the default move constructor has been
+ // called; this prevents us from calling the destructor twice.
+ struct HasBeenMoved {
+ HasBeenMoved(HasBeenMoved&& other) {
+ other.moved = true;
+ moved = false;
+ }
+ HasBeenMoved() = default;
+ std::atomic<bool> moved{false};
+ operator bool() const { return moved; }
+ } m_hasBeenMoved;
+
+ //---------------------- Vars for opening a CAN stream if caller needs signals that require soliciting */
+ uint32_t _can_h; //!< Session handle for catching response params.
+ int32_t _can_stat; //!< Session handle status.
+ struct tCANStreamMessage _msgBuff[20];
+ static int const kMsgCapacity = 20;
+ typedef std::map<uint32_t, uint32_t> sigs_t;
+ sigs_t _sigs; //!< Catches signal updates that are solicited. Expect this to be very few.
+ void OpenSessionIfNeedBe();
+ void ProcessStreamMessages();
+ /**
+ * Send a one shot frame to set an arbitrary signal.
+ * Most signals are in the control frame so avoid using this API unless you have to.
+ * Use this api for...
+ * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically.
+ * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame.
+ * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.
+ */
+ CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits);
+ /**
+ * Checks cached CAN frames and updating solicited signals.
+ */
+ CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits);
+public:
+ static const int kDefaultControlPeriodMs = 10; //!< default control update rate is 10ms.
+ CanTalonSRX(int deviceNumber = 0,int controlPeriodMs = kDefaultControlPeriodMs);
+ ~CanTalonSRX();
+ void Set(double value);
+ /* mode select enumerations */
+ static const int kMode_DutyCycle = 0; //!< Demand is 11bit signed duty cycle [-1023,1023].
+ static const int kMode_PositionCloseLoop = 1; //!< Position PIDF.
+ static const int kMode_VelocityCloseLoop = 2; //!< Velocity PIDF.
+ static const int kMode_CurrentCloseLoop = 3; //!< Current close loop - not done.
+ static const int kMode_VoltCompen = 4; //!< Voltage Compensation Mode - not done. Demand is fixed pt target 8.8 volts.
+ static const int kMode_SlaveFollower = 5; //!< Demand is the 6 bit Device ID of the 'master' TALON SRX.
+ static const int kMode_NoDrive = 15; //!< Zero the output (honors brake/coast) regardless of demand. Might be useful if we need to change modes but can't atomically change all the signals we want in between.
+ /* limit switch enumerations */
+ static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1;
+ static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4;
+ static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5;
+ static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6;
+ static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7;
+ /* brake override enumerations */
+ static const int kBrakeOverride_UseDefaultsFromFlash = 0;
+ static const int kBrakeOverride_OverrideCoast = 1;
+ static const int kBrakeOverride_OverrideBrake = 2;
+ /* feedback device enumerations */
+ static const int kFeedbackDev_DigitalQuadEnc=0;
+ static const int kFeedbackDev_AnalogPot=2;
+ static const int kFeedbackDev_AnalogEncoder=3;
+ static const int kFeedbackDev_CountEveryRisingEdge=4;
+ static const int kFeedbackDev_CountEveryFallingEdge=5;
+ static const int kFeedbackDev_PosIsPulseWidth=8;
+ /* ProfileSlotSelect enumerations*/
+ static const int kProfileSlotSelect_Slot0 = 0;
+ static const int kProfileSlotSelect_Slot1 = 1;
+ /* status frame rate types */
+ static const int kStatusFrame_General = 0;
+ static const int kStatusFrame_Feedback = 1;
+ static const int kStatusFrame_Encoder = 2;
+ static const int kStatusFrame_AnalogTempVbat = 3;
+ static const int kStatusFrame_PulseWidthMeas = 4;
+ /**
+ * Signal enumeration for generic signal access.
+ * Although every signal is enumerated, only use this for traffic that must be solicited.
+ * Use the auto generated getters/setters at bottom of this header as much as possible.
+ */
+ typedef enum _param_t{
+ eProfileParamSlot0_P=1,
+ eProfileParamSlot0_I=2,
+ eProfileParamSlot0_D=3,
+ eProfileParamSlot0_F=4,
+ eProfileParamSlot0_IZone=5,
+ eProfileParamSlot0_CloseLoopRampRate=6,
+ eProfileParamSlot1_P=11,
+ eProfileParamSlot1_I=12,
+ eProfileParamSlot1_D=13,
+ eProfileParamSlot1_F=14,
+ eProfileParamSlot1_IZone=15,
+ eProfileParamSlot1_CloseLoopRampRate=16,
+ eProfileParamSoftLimitForThreshold=21,
+ eProfileParamSoftLimitRevThreshold=22,
+ eProfileParamSoftLimitForEnable=23,
+ eProfileParamSoftLimitRevEnable=24,
+ eOnBoot_BrakeMode=31,
+ eOnBoot_LimitSwitch_Forward_NormallyClosed=32,
+ eOnBoot_LimitSwitch_Reverse_NormallyClosed=33,
+ eOnBoot_LimitSwitch_Forward_Disable=34,
+ eOnBoot_LimitSwitch_Reverse_Disable=35,
+ eFault_OverTemp=41,
+ eFault_UnderVoltage=42,
+ eFault_ForLim=43,
+ eFault_RevLim=44,
+ eFault_HardwareFailure=45,
+ eFault_ForSoftLim=46,
+ eFault_RevSoftLim=47,
+ eStckyFault_OverTemp=48,
+ eStckyFault_UnderVoltage=49,
+ eStckyFault_ForLim=50,
+ eStckyFault_RevLim=51,
+ eStckyFault_ForSoftLim=52,
+ eStckyFault_RevSoftLim=53,
+ eAppliedThrottle=61,
+ eCloseLoopErr=62,
+ eFeedbackDeviceSelect=63,
+ eRevMotDuringCloseLoopEn=64,
+ eModeSelect=65,
+ eProfileSlotSelect=66,
+ eRampThrottle=67,
+ eRevFeedbackSensor=68,
+ eLimitSwitchEn=69,
+ eLimitSwitchClosedFor=70,
+ eLimitSwitchClosedRev=71,
+ eSensorPosition=73,
+ eSensorVelocity=74,
+ eCurrent=75,
+ eBrakeIsEnabled=76,
+ eEncPosition=77,
+ eEncVel=78,
+ eEncIndexRiseEvents=79,
+ eQuadApin=80,
+ eQuadBpin=81,
+ eQuadIdxpin=82,
+ eAnalogInWithOv=83,
+ eAnalogInVel=84,
+ eTemp=85,
+ eBatteryV=86,
+ eResetCount=87,
+ eResetFlags=88,
+ eFirmVers=89,
+ eSettingsChanged=90,
+ eQuadFilterEn=91,
+ ePidIaccum=93,
+ eStatus1FrameRate=94, // TALON_Status_1_General_10ms_t
+ eStatus2FrameRate=95, // TALON_Status_2_Feedback_20ms_t
+ eStatus3FrameRate=96, // TALON_Status_3_Enc_100ms_t
+ eStatus4FrameRate=97, // TALON_Status_4_AinTempVbat_100ms_t
+ eStatus6FrameRate=98, // TALON_Status_6_Eol_t
+ eStatus7FrameRate=99, // TALON_Status_7_Debug_200ms_t
+ eClearPositionOnIdx=100,
+ //reserved,
+ //reserved,
+ //reserved,
+ ePeakPosOutput=104,
+ eNominalPosOutput=105,
+ ePeakNegOutput=106,
+ eNominalNegOutput=107,
+ eQuadIdxPolarity=108,
+ eStatus8FrameRate=109, // TALON_Status_8_PulseWid_100ms_t
+ eAllowPosOverflow=110,
+ eProfileParamSlot0_AllowableClosedLoopErr=111,
+ eNumberPotTurns=112,
+ eNumberEncoderCPR=113,
+ ePwdPosition=114,
+ eAinPosition=115,
+ eProfileParamVcompRate=116,
+ eProfileParamSlot1_AllowableClosedLoopErr=117,
+ }param_t;
+ /*---------------------setters and getters that use the solicated param request/response-------------*//**
+ * Send a one shot frame to set an arbitrary signal.
+ * Most signals are in the control frame so avoid using this API unless you have to.
+ * Use this api for...
+ * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically.
+ * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame.
+ * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.
+ */
+ CTR_Code SetParam(param_t paramEnum, double value);
+ /**
+ * Asks TALON to immedietely respond with signal value. This API is only used for signals that are not sent periodically.
+ * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.
+ * @param param to request.
+ */
+ CTR_Code RequestParam(param_t paramEnum);
+ CTR_Code GetParamResponse(param_t paramEnum, double & value);
+ CTR_Code GetParamResponseInt32(param_t paramEnum, int & value);
+ /*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/
+ /*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/
+ /*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/
+ /*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/
+ CTR_Code SetPgain(unsigned slotIdx,double gain);
+ CTR_Code SetIgain(unsigned slotIdx,double gain);
+ CTR_Code SetDgain(unsigned slotIdx,double gain);
+ CTR_Code SetFgain(unsigned slotIdx,double gain);
+ CTR_Code SetIzone(unsigned slotIdx,int zone);
+ CTR_Code SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate);
+ CTR_Code SetVoltageCompensationRate(double voltagePerMs);
+ CTR_Code SetSensorPosition(int pos);
+ CTR_Code SetForwardSoftLimit(int forwardLimit);
+ CTR_Code SetReverseSoftLimit(int reverseLimit);
+ CTR_Code SetForwardSoftEnable(int enable);
+ CTR_Code SetReverseSoftEnable(int enable);
+ CTR_Code GetPgain(unsigned slotIdx,double & gain);
+ CTR_Code GetIgain(unsigned slotIdx,double & gain);
+ CTR_Code GetDgain(unsigned slotIdx,double & gain);
+ CTR_Code GetFgain(unsigned slotIdx,double & gain);
+ CTR_Code GetIzone(unsigned slotIdx,int & zone);
+ CTR_Code GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate);
+ CTR_Code GetVoltageCompensationRate(double & voltagePerMs);
+ CTR_Code GetForwardSoftLimit(int & forwardLimit);
+ CTR_Code GetReverseSoftLimit(int & reverseLimit);
+ CTR_Code GetForwardSoftEnable(int & enable);
+ CTR_Code GetReverseSoftEnable(int & enable);
+ /**
+ * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for what's available.
+ */
+ CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs);
+ /**
+ * Clear all sticky faults in TALON.
+ */
+ CTR_Code ClearStickyFaults();
+ /*------------------------ auto generated. This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/
+ /*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/
+ CTR_Code GetFault_OverTemp(int ¶m);
+ CTR_Code GetFault_UnderVoltage(int ¶m);
+ CTR_Code GetFault_ForLim(int ¶m);
+ CTR_Code GetFault_RevLim(int ¶m);
+ CTR_Code GetFault_HardwareFailure(int ¶m);
+ CTR_Code GetFault_ForSoftLim(int ¶m);
+ CTR_Code GetFault_RevSoftLim(int ¶m);
+ CTR_Code GetStckyFault_OverTemp(int ¶m);
+ CTR_Code GetStckyFault_UnderVoltage(int ¶m);
+ CTR_Code GetStckyFault_ForLim(int ¶m);
+ CTR_Code GetStckyFault_RevLim(int ¶m);
+ CTR_Code GetStckyFault_ForSoftLim(int ¶m);
+ CTR_Code GetStckyFault_RevSoftLim(int ¶m);
+ CTR_Code GetAppliedThrottle(int ¶m);
+ CTR_Code GetCloseLoopErr(int ¶m);
+ CTR_Code GetFeedbackDeviceSelect(int ¶m);
+ CTR_Code GetModeSelect(int ¶m);
+ CTR_Code GetLimitSwitchEn(int ¶m);
+ CTR_Code GetLimitSwitchClosedFor(int ¶m);
+ CTR_Code GetLimitSwitchClosedRev(int ¶m);
+ CTR_Code GetSensorPosition(int ¶m);
+ CTR_Code GetSensorVelocity(int ¶m);
+ CTR_Code GetCurrent(double ¶m);
+ CTR_Code GetBrakeIsEnabled(int ¶m);
+ CTR_Code GetEncPosition(int ¶m);
+ CTR_Code GetEncVel(int ¶m);
+ CTR_Code GetEncIndexRiseEvents(int ¶m);
+ CTR_Code GetQuadApin(int ¶m);
+ CTR_Code GetQuadBpin(int ¶m);
+ CTR_Code GetQuadIdxpin(int ¶m);
+ CTR_Code GetAnalogInWithOv(int ¶m);
+ CTR_Code GetAnalogInVel(int ¶m);
+ CTR_Code GetTemp(double ¶m);
+ CTR_Code GetBatteryV(double ¶m);
+ CTR_Code GetResetCount(int ¶m);
+ CTR_Code GetResetFlags(int ¶m);
+ CTR_Code GetFirmVers(int ¶m);
+ CTR_Code SetDemand(int param);
+ CTR_Code SetOverrideLimitSwitchEn(int param);
+ CTR_Code SetFeedbackDeviceSelect(int param);
+ CTR_Code SetRevMotDuringCloseLoopEn(int param);
+ CTR_Code SetOverrideBrakeType(int param);
+ CTR_Code SetModeSelect(int param);
+ CTR_Code SetModeSelect(int modeSelect,int demand);
+ CTR_Code SetProfileSlotSelect(int param);
+ CTR_Code SetRampThrottle(int param);
+ CTR_Code SetRevFeedbackSensor(int param);
+ CTR_Code GetPulseWidthPosition(int ¶m);
+ CTR_Code GetPulseWidthVelocity(int ¶m);
+ CTR_Code GetPulseWidthRiseToFallUs(int ¶m);
+ CTR_Code GetPulseWidthRiseToRiseUs(int ¶m);
+ CTR_Code IsPulseWidthSensorPresent(int ¶m);
+};
+extern "C" {
+ void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs);
+ void c_TalonSRX_Destroy(void *handle);
+ CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value);
+ CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum);
+ CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value);
+ CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value);
+ CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs);
+ CTR_Code c_TalonSRX_ClearStickyFaults(void *handle);
+ CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param);
+ CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetTemp(void *handle, double *param);
+ CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param);
+ CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param);
+ CTR_Code c_TalonSRX_SetDemand(void *handle, int param);
+ CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param);
+ CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param);
+ CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param);
+ CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param);
+ CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param);
+ CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand);
+ CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param);
+ CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param);
+ CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param);
+ CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param);
+ CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param);
+ CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param);
+}
+#endif
+
diff --git a/hal/include/HAL/Compressor.hpp b/hal/include/HAL/Compressor.hpp
new file mode 100644
index 0000000..465a63b
--- /dev/null
+++ b/hal/include/HAL/Compressor.hpp
@@ -0,0 +1,33 @@
+/**
+ * Compressor.h
+ * Methods for interacting with a compressor with the CAN PCM device
+ */
+
+#include <stdint.h>
+
+#ifndef __HAL_COMPRESSOR_H__
+#define __HAL_COMPRESSOR_H__
+
+extern "C" {
+ void *initializeCompressor(uint8_t module);
+ bool checkCompressorModule(uint8_t module);
+
+ bool getCompressor(void *pcm_pointer, int32_t *status);
+
+ void setClosedLoopControl(void *pcm_pointer, bool value, int32_t *status);
+ bool getClosedLoopControl(void *pcm_pointer, int32_t *status);
+
+ bool getPressureSwitch(void *pcm_pointer, int32_t *status);
+ float getCompressorCurrent(void *pcm_pointer, int32_t *status);
+
+ bool getCompressorCurrentTooHighFault(void *pcm_pointer, int32_t *status);
+ bool getCompressorCurrentTooHighStickyFault(void *pcm_pointer, int32_t *status);
+ bool getCompressorShortedStickyFault(void *pcm_pointer, int32_t *status);
+ bool getCompressorShortedFault(void *pcm_pointer, int32_t *status);
+ bool getCompressorNotConnectedStickyFault(void *pcm_pointer, int32_t *status);
+ bool getCompressorNotConnectedFault(void *pcm_pointer, int32_t *status);
+ void clearAllPCMStickyFaults(void *pcm_pointer, int32_t *status);
+}
+
+#endif
+
diff --git a/hal/include/HAL/Digital.hpp b/hal/include/HAL/Digital.hpp
new file mode 100644
index 0000000..64851f1
--- /dev/null
+++ b/hal/include/HAL/Digital.hpp
@@ -0,0 +1,139 @@
+#pragma once
+#include <stdint.h>
+
+#include "HAL/cpp/priority_mutex.h"
+
+enum Mode
+{
+ kTwoPulse = 0,
+ kSemiperiod = 1,
+ kPulseLength = 2,
+ kExternalDirection = 3
+};
+
+priority_recursive_mutex& spiGetSemaphore(uint8_t port);
+
+extern "C"
+{
+ void* initializeDigitalPort(void* port_pointer, int32_t *status);
+ void freeDigitalPort(void* digital_port_pointer);
+ bool checkPWMChannel(void* digital_port_pointer);
+ bool checkRelayChannel(void* digital_port_pointer);
+
+ void setPWM(void* digital_port_pointer, unsigned short value, int32_t *status);
+ bool allocatePWMChannel(void* digital_port_pointer, int32_t *status);
+ void freePWMChannel(void* digital_port_pointer, int32_t *status);
+ unsigned short getPWM(void* digital_port_pointer, int32_t *status);
+ void latchPWMZero(void* digital_port_pointer, int32_t *status);
+ void setPWMPeriodScale(void* digital_port_pointer, uint32_t squelchMask, int32_t *status);
+ void* allocatePWM(int32_t *status);
+ void freePWM(void* pwmGenerator, int32_t *status);
+ void setPWMRate(double rate, int32_t *status);
+ void setPWMDutyCycle(void* pwmGenerator, double dutyCycle, int32_t *status);
+ void setPWMOutputChannel(void* pwmGenerator, uint32_t pin, int32_t *status);
+
+ void setRelayForward(void* digital_port_pointer, bool on, int32_t *status);
+ void setRelayReverse(void* digital_port_pointer, bool on, int32_t *status);
+ bool getRelayForward(void* digital_port_pointer, int32_t *status);
+ bool getRelayReverse(void* digital_port_pointer, int32_t *status);
+
+ bool allocateDIO(void* digital_port_pointer, bool input, int32_t *status);
+ void freeDIO(void* digital_port_pointer, int32_t *status);
+ void setDIO(void* digital_port_pointer, short value, int32_t *status);
+ bool getDIO(void* digital_port_pointer, int32_t *status);
+ bool getDIODirection(void* digital_port_pointer, int32_t *status);
+ void pulse(void* digital_port_pointer, double pulseLength, int32_t *status);
+ bool isPulsing(void* digital_port_pointer, int32_t *status);
+ bool isAnyPulsing(int32_t *status);
+
+ void setFilterSelect(void* digital_port_pointer, int filter_index,
+ int32_t* status);
+ int getFilterSelect(void* digital_port_pointer, int32_t* status);
+
+ void setFilterPeriod(int filter_index, uint32_t value, int32_t* status);
+ uint32_t getFilterPeriod(int filter_index, int32_t* status);
+
+ void* initializeCounter(Mode mode, uint32_t *index, int32_t *status);
+ void freeCounter(void* counter_pointer, int32_t *status);
+ void setCounterAverageSize(void* counter_pointer, int32_t size, int32_t *status);
+ void setCounterUpSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status);
+ void setCounterUpSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge,
+ int32_t *status);
+ void clearCounterUpSource(void* counter_pointer, int32_t *status);
+ void setCounterDownSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status);
+ void setCounterDownSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge,
+ int32_t *status);
+ void clearCounterDownSource(void* counter_pointer, int32_t *status);
+ void setCounterUpDownMode(void* counter_pointer, int32_t *status);
+ void setCounterExternalDirectionMode(void* counter_pointer, int32_t *status);
+ void setCounterSemiPeriodMode(void* counter_pointer, bool highSemiPeriod, int32_t *status);
+ void setCounterPulseLengthMode(void* counter_pointer, double threshold, int32_t *status);
+ int32_t getCounterSamplesToAverage(void* counter_pointer, int32_t *status);
+ void setCounterSamplesToAverage(void* counter_pointer, int samplesToAverage, int32_t *status);
+ void resetCounter(void* counter_pointer, int32_t *status);
+ int32_t getCounter(void* counter_pointer, int32_t *status);
+ double getCounterPeriod(void* counter_pointer, int32_t *status);
+ void setCounterMaxPeriod(void* counter_pointer, double maxPeriod, int32_t *status);
+ void setCounterUpdateWhenEmpty(void* counter_pointer, bool enabled, int32_t *status);
+ bool getCounterStopped(void* counter_pointer, int32_t *status);
+ bool getCounterDirection(void* counter_pointer, int32_t *status);
+ void setCounterReverseDirection(void* counter_pointer, bool reverseDirection, int32_t *status);
+
+ void* initializeEncoder(uint8_t port_a_module, uint32_t port_a_pin, bool port_a_analog_trigger,
+ uint8_t port_b_module, uint32_t port_b_pin, bool port_b_analog_trigger,
+ bool reverseDirection, int32_t *index, int32_t *status); // TODO: fix routing
+ void freeEncoder(void* encoder_pointer, int32_t *status);
+ void resetEncoder(void* encoder_pointer, int32_t *status);
+ int32_t getEncoder(void* encoder_pointer, int32_t *status); // Raw value
+ double getEncoderPeriod(void* encoder_pointer, int32_t *status);
+ void setEncoderMaxPeriod(void* encoder_pointer, double maxPeriod, int32_t *status);
+ bool getEncoderStopped(void* encoder_pointer, int32_t *status);
+ bool getEncoderDirection(void* encoder_pointer, int32_t *status);
+ void setEncoderReverseDirection(void* encoder_pointer, bool reverseDirection, int32_t *status);
+ void setEncoderSamplesToAverage(void* encoder_pointer, uint32_t samplesToAverage,
+ int32_t *status);
+ uint32_t getEncoderSamplesToAverage(void* encoder_pointer, int32_t *status);
+ void setEncoderIndexSource(void *encoder_pointer, uint32_t pin, bool analogTrigger, bool activeHigh,
+ bool edgeSensitive, int32_t *status);
+
+ uint16_t getLoopTiming(int32_t *status);
+
+ void spiInitialize(uint8_t port, int32_t *status);
+ int32_t spiTransaction(uint8_t port, uint8_t *dataToSend, uint8_t *dataReceived, uint8_t size);
+ int32_t spiWrite(uint8_t port, uint8_t* dataToSend, uint8_t sendSize);
+ int32_t spiRead(uint8_t port, uint8_t *buffer, uint8_t count);
+ void spiClose(uint8_t port);
+ void spiSetSpeed(uint8_t port, uint32_t speed);
+ void spiSetOpts(uint8_t port, int msb_first, int sample_on_trailing, int clk_idle_high);
+ void spiSetChipSelectActiveHigh(uint8_t port, int32_t *status);
+ void spiSetChipSelectActiveLow(uint8_t port, int32_t *status);
+ int32_t spiGetHandle(uint8_t port);
+ void spiSetHandle(uint8_t port, int32_t handle);
+
+ void spiInitAccumulator(uint8_t port, uint32_t period, uint32_t cmd,
+ uint8_t xfer_size, uint32_t valid_mask,
+ uint32_t valid_value, uint8_t data_shift,
+ uint8_t data_size, bool is_signed, bool big_endian,
+ int32_t *status);
+ void spiFreeAccumulator(uint8_t port, int32_t *status);
+ void spiResetAccumulator(uint8_t port, int32_t *status);
+ void spiSetAccumulatorCenter(uint8_t port, int32_t center, int32_t *status);
+ void spiSetAccumulatorDeadband(uint8_t port, int32_t deadband, int32_t *status);
+ int32_t spiGetAccumulatorLastValue(uint8_t port, int32_t *status);
+ int64_t spiGetAccumulatorValue(uint8_t port, int32_t *status);
+ uint32_t spiGetAccumulatorCount(uint8_t port, int32_t *status);
+ double spiGetAccumulatorAverage(uint8_t port, int32_t *status);
+ void spiGetAccumulatorOutput(uint8_t port, int64_t *value, uint32_t *count,
+ int32_t *status);
+
+ void i2CInitialize(uint8_t port, int32_t *status);
+ int32_t i2CTransaction(uint8_t port, uint8_t deviceAddress, uint8_t *dataToSend, uint8_t sendSize, uint8_t *dataReceived, uint8_t receiveSize);
+ int32_t i2CWrite(uint8_t port, uint8_t deviceAddress, uint8_t *dataToSend, uint8_t sendSize);
+ int32_t i2CRead(uint8_t port, uint8_t deviceAddress, uint8_t *buffer, uint8_t count);
+ void i2CClose(uint8_t port);
+
+ //// Float JNA Hack
+ // double
+ void setPWMRateIntHack(int rate, int32_t *status);
+ void setPWMDutyCycleIntHack(void* pwmGenerator, int32_t dutyCycle, int32_t *status);
+}
diff --git a/hal/include/HAL/Errors.hpp b/hal/include/HAL/Errors.hpp
new file mode 100644
index 0000000..35ed961
--- /dev/null
+++ b/hal/include/HAL/Errors.hpp
@@ -0,0 +1,64 @@
+#pragma once
+
+#define CTR_RxTimeout_MESSAGE "CTRE CAN Recieve Timeout"
+#define CTR_TxTimeout_MESSAGE "CTRE CAN Transmit Timeout"
+#define CTR_InvalidParamValue_MESSAGE "CTRE CAN Invalid Parameter"
+#define CTR_UnexpectedArbId_MESSAGE "CTRE Unexpected Arbitration ID (CAN Node ID)"
+#define CTR_TxFailed_MESSAGE "CTRE CAN Transmit Error"
+#define CTR_SigNotUpdated_MESSAGE "CTRE CAN Signal Not Updated"
+
+#define NiFpga_Status_FifoTimeout_MESSAGE "NIFPGA: FIFO timeout error"
+#define NiFpga_Status_TransferAborted_MESSAGE "NIFPGA: Transfer aborted error"
+#define NiFpga_Status_MemoryFull_MESSAGE "NIFPGA: Memory Allocation failed, memory full"
+#define NiFpga_Status_SoftwareFault_MESSAGE "NIFPGA: Unexepected software error"
+#define NiFpga_Status_InvalidParameter_MESSAGE "NIFPGA: Invalid Parameter"
+#define NiFpga_Status_ResourceNotFound_MESSAGE "NIFPGA: Resource not found"
+#define NiFpga_Status_ResourceNotInitialized_MESSAGE "NIFPGA: Resource not initialized"
+#define NiFpga_Status_HardwareFault_MESSAGE "NIFPGA: Hardware Fault"
+#define NiFpga_Status_IrqTimeout_MESSAGE "NIFPGA: Interrupt timeout"
+
+#define ERR_CANSessionMux_InvalidBuffer_MESSAGE "CAN: Invalid Buffer"
+#define ERR_CANSessionMux_MessageNotFound_MESSAGE "CAN: Message not found"
+#define WARN_CANSessionMux_NoToken_MESSAGE "CAN: No token"
+#define ERR_CANSessionMux_NotAllowed_MESSAGE "CAN: Not allowed"
+#define ERR_CANSessionMux_NotInitialized_MESSAGE "CAN: Not initialized"
+
+#define SAMPLE_RATE_TOO_HIGH 1001
+#define SAMPLE_RATE_TOO_HIGH_MESSAGE "HAL: Analog module sample rate is too high"
+#define VOLTAGE_OUT_OF_RANGE 1002
+#define VOLTAGE_OUT_OF_RANGE_MESSAGE "HAL: Voltage to convert to raw value is out of range [0; 5]"
+#define LOOP_TIMING_ERROR 1004
+#define LOOP_TIMING_ERROR_MESSAGE "HAL: Digital module loop timing is not the expected value"
+#define SPI_WRITE_NO_MOSI 1012
+#define SPI_WRITE_NO_MOSI_MESSAGE "HAL: Cannot write to SPI port with no MOSI output"
+#define SPI_READ_NO_MISO 1013
+#define SPI_READ_NO_MISO_MESSAGE "HAL: Cannot read from SPI port with no MISO input"
+#define SPI_READ_NO_DATA 1014
+#define SPI_READ_NO_DATA_MESSAGE "HAL: No data available to read from SPI"
+#define INCOMPATIBLE_STATE 1015
+#define INCOMPATIBLE_STATE_MESSAGE "HAL: Incompatible State: The operation cannot be completed"
+#define NO_AVAILABLE_RESOURCES -1004
+#define NO_AVAILABLE_RESOURCES_MESSAGE "HAL: No available resources to allocate"
+#define NULL_PARAMETER -1005
+#define NULL_PARAMETER_MESSAGE "HAL: A pointer parameter to a method is NULL"
+#define ANALOG_TRIGGER_LIMIT_ORDER_ERROR -1010
+#define ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE "HAL: AnalogTrigger limits error. Lower limit > Upper Limit"
+#define ANALOG_TRIGGER_PULSE_OUTPUT_ERROR -1011
+#define ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE "HAL: Attempted to read AnalogTrigger pulse output."
+#define PARAMETER_OUT_OF_RANGE -1028
+#define PARAMETER_OUT_OF_RANGE_MESSAGE "HAL: A parameter is out of range."
+#define RESOURCE_IS_ALLOCATED -1029
+#define RESOURCE_IS_ALLOCATED_MESSAGE "HAL: Resource already allocated"
+
+#define VI_ERROR_SYSTEM_ERROR_MESSAGE "HAL - VISA: System Error";
+#define VI_ERROR_INV_OBJECT_MESSAGE "HAL - VISA: Invalid Object"
+#define VI_ERROR_RSRC_LOCKED_MESSAGE "HAL - VISA: Resource Locked"
+#define VI_ERROR_RSRC_NFOUND_MESSAGE "HAL - VISA: Resource Not Found"
+#define VI_ERROR_INV_RSRC_NAME_MESSAGE "HAL - VISA: Invalid Resource Name"
+#define VI_ERROR_QUEUE_OVERFLOW_MESSAGE "HAL - VISA: Queue Overflow"
+#define VI_ERROR_IO_MESSAGE "HAL - VISA: General IO Error"
+#define VI_ERROR_ASRL_PARITY_MESSAGE "HAL - VISA: Parity Error"
+#define VI_ERROR_ASRL_FRAMING_MESSAGE "HAL - VISA: Framing Error"
+#define VI_ERROR_ASRL_OVERRUN_MESSAGE "HAL - VISA: Buffer Overrun Error"
+#define VI_ERROR_RSRC_BUSY_MESSAGE "HAL - VISA: Resource Busy"
+#define VI_ERROR_INV_PARAMETER_MESSAGE "HAL - VISA: Invalid Parameter"
diff --git a/hal/include/HAL/HAL.hpp b/hal/include/HAL/HAL.hpp
new file mode 100644
index 0000000..f09a5d2
--- /dev/null
+++ b/hal/include/HAL/HAL.hpp
@@ -0,0 +1,268 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2013. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include <stdint.h>
+#include <cmath>
+
+#include "Accelerometer.hpp"
+#include "Analog.hpp"
+#include "Compressor.hpp"
+#include "Digital.hpp"
+#include "Solenoid.hpp"
+#include "Notifier.hpp"
+#include "Interrupts.hpp"
+#include "Errors.hpp"
+#include "PDP.hpp"
+#include "Power.hpp"
+#include "SerialPort.hpp"
+
+#include "Utilities.hpp"
+#include "Semaphore.hpp"
+#include "Task.hpp"
+
+#define HAL_IO_CONFIG_DATA_SIZE 32
+#define HAL_SYS_STATUS_DATA_SIZE 44
+#define HAL_USER_STATUS_DATA_SIZE (984 - HAL_IO_CONFIG_DATA_SIZE - HAL_SYS_STATUS_DATA_SIZE)
+
+#define HALFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Input 17
+#define HALFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Output 18
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Header 19
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Extra1 20
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Vertices1 21
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Extra2 22
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Vertices2 23
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Joystick 24
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Custom 25
+
+namespace HALUsageReporting
+{
+ enum tResourceType
+ {
+ kResourceType_Controller,
+ kResourceType_Module,
+ kResourceType_Language,
+ kResourceType_CANPlugin,
+ kResourceType_Accelerometer,
+ kResourceType_ADXL345,
+ kResourceType_AnalogChannel,
+ kResourceType_AnalogTrigger,
+ kResourceType_AnalogTriggerOutput,
+ kResourceType_CANJaguar,
+ kResourceType_Compressor,
+ kResourceType_Counter,
+ kResourceType_Dashboard,
+ kResourceType_DigitalInput,
+ kResourceType_DigitalOutput,
+ kResourceType_DriverStationCIO,
+ kResourceType_DriverStationEIO,
+ kResourceType_DriverStationLCD,
+ kResourceType_Encoder,
+ kResourceType_GearTooth,
+ kResourceType_Gyro,
+ kResourceType_I2C,
+ kResourceType_Framework,
+ kResourceType_Jaguar,
+ kResourceType_Joystick,
+ kResourceType_Kinect,
+ kResourceType_KinectStick,
+ kResourceType_PIDController,
+ kResourceType_Preferences,
+ kResourceType_PWM,
+ kResourceType_Relay,
+ kResourceType_RobotDrive,
+ kResourceType_SerialPort,
+ kResourceType_Servo,
+ kResourceType_Solenoid,
+ kResourceType_SPI,
+ kResourceType_Task,
+ kResourceType_Ultrasonic,
+ kResourceType_Victor,
+ kResourceType_Button,
+ kResourceType_Command,
+ kResourceType_AxisCamera,
+ kResourceType_PCVideoServer,
+ kResourceType_SmartDashboard,
+ kResourceType_Talon,
+ kResourceType_HiTechnicColorSensor,
+ kResourceType_HiTechnicAccel,
+ kResourceType_HiTechnicCompass,
+ kResourceType_SRF08,
+ kResourceType_AnalogOutput,
+ kResourceType_VictorSP,
+ kResourceType_TalonSRX,
+ kResourceType_CANTalonSRX,
+ kResourceType_ADXL362,
+ kResourceType_ADXRS450,
+ kResourceType_RevSPARK,
+ kResourceType_MindsensorsSD540,
+ kResourceType_DigitalFilter,
+ };
+
+ enum tInstances
+ {
+ kLanguage_LabVIEW = 1,
+ kLanguage_CPlusPlus = 2,
+ kLanguage_Java = 3,
+ kLanguage_Python = 4,
+
+ kCANPlugin_BlackJagBridge = 1,
+ kCANPlugin_2CAN = 2,
+
+ kFramework_Iterative = 1,
+ kFramework_Sample = 2,
+ kFramework_CommandControl = 3,
+
+ kRobotDrive_ArcadeStandard = 1,
+ kRobotDrive_ArcadeButtonSpin = 2,
+ kRobotDrive_ArcadeRatioCurve = 3,
+ kRobotDrive_Tank = 4,
+ kRobotDrive_MecanumPolar = 5,
+ kRobotDrive_MecanumCartesian = 6,
+
+ kDriverStationCIO_Analog = 1,
+ kDriverStationCIO_DigitalIn = 2,
+ kDriverStationCIO_DigitalOut = 3,
+
+ kDriverStationEIO_Acceleration = 1,
+ kDriverStationEIO_AnalogIn = 2,
+ kDriverStationEIO_AnalogOut = 3,
+ kDriverStationEIO_Button = 4,
+ kDriverStationEIO_LED = 5,
+ kDriverStationEIO_DigitalIn = 6,
+ kDriverStationEIO_DigitalOut = 7,
+ kDriverStationEIO_FixedDigitalOut = 8,
+ kDriverStationEIO_PWM = 9,
+ kDriverStationEIO_Encoder = 10,
+ kDriverStationEIO_TouchSlider = 11,
+
+ kADXL345_SPI = 1,
+ kADXL345_I2C = 2,
+
+ kCommand_Scheduler = 1,
+
+ kSmartDashboard_Instance = 1,
+ };
+}
+
+struct HALControlWord {
+ uint32_t enabled : 1;
+ uint32_t autonomous : 1;
+ uint32_t test :1;
+ uint32_t eStop : 1;
+ uint32_t fmsAttached:1;
+ uint32_t dsAttached:1;
+ uint32_t control_reserved : 26;
+};
+
+enum HALAllianceStationID {
+ kHALAllianceStationID_red1,
+ kHALAllianceStationID_red2,
+ kHALAllianceStationID_red3,
+ kHALAllianceStationID_blue1,
+ kHALAllianceStationID_blue2,
+ kHALAllianceStationID_blue3,
+};
+
+/* The maximum number of axes that will be stored in a single HALJoystickAxes
+ struct. This is used for allocating buffers, not bounds checking, since
+ there are usually less axes in practice. */
+static const size_t kMaxJoystickAxes = 12;
+static const size_t kMaxJoystickPOVs = 12;
+
+struct HALJoystickAxes {
+ uint16_t count;
+ int16_t axes[kMaxJoystickAxes];
+};
+
+struct HALJoystickPOVs {
+ uint16_t count;
+ int16_t povs[kMaxJoystickPOVs];
+};
+
+struct HALJoystickButtons {
+ uint32_t buttons;
+ uint8_t count;
+};
+
+struct HALJoystickDescriptor {
+ uint8_t isXbox;
+ uint8_t type;
+ char name[256];
+ uint8_t axisCount;
+ uint8_t axisTypes[kMaxJoystickAxes];
+ uint8_t buttonCount;
+ uint8_t povCount;
+};
+
+inline float intToFloat(int value)
+{
+ return (float)value;
+}
+
+inline int floatToInt(float value)
+{
+ return round(value);
+}
+
+extern "C"
+{
+ extern const uint32_t dio_kNumSystems;
+ extern const uint32_t solenoid_kNumDO7_0Elements;
+ extern const uint32_t interrupt_kNumSystems;
+ extern const uint32_t kSystemClockTicksPerMicrosecond;
+
+ void* getPort(uint8_t pin);
+ void* getPortWithModule(uint8_t module, uint8_t pin);
+ void freePort(void* port);
+ const char* getHALErrorMessage(int32_t code);
+
+ uint16_t getFPGAVersion(int32_t *status);
+ uint32_t getFPGARevision(int32_t *status);
+ uint32_t getFPGATime(int32_t *status);
+
+ bool getFPGAButton(int32_t *status);
+
+ int HALSetErrorData(const char *errors, int errorsLength, int wait_ms);
+
+ int HALGetControlWord(HALControlWord *data);
+ int HALGetAllianceStation(enum HALAllianceStationID *allianceStation);
+ int HALGetJoystickAxes(uint8_t joystickNum, HALJoystickAxes *axes);
+ int HALGetJoystickPOVs(uint8_t joystickNum, HALJoystickPOVs *povs);
+ int HALGetJoystickButtons(uint8_t joystickNum, HALJoystickButtons *buttons);
+ int HALGetJoystickDescriptor(uint8_t joystickNum, HALJoystickDescriptor *desc);
+ int HALGetJoystickIsXbox(uint8_t joystickNum);
+ int HALGetJoystickType(uint8_t joystickNum);
+ char* HALGetJoystickName(uint8_t joystickNum);
+ int HALGetJoystickAxisType(uint8_t joystickNum, uint8_t axis);
+ int HALSetJoystickOutputs(uint8_t joystickNum, uint32_t outputs, uint16_t leftRumble, uint16_t rightRumble);
+ int HALGetMatchTime(float *matchTime);
+
+ void HALSetNewDataSem(MULTIWAIT_ID sem);
+
+ bool HALGetSystemActive(int32_t *status);
+ bool HALGetBrownedOut(int32_t *status);
+
+ int HALInitialize(int mode = 0);
+ void HALNetworkCommunicationObserveUserProgramStarting();
+ void HALNetworkCommunicationObserveUserProgramDisabled();
+ void HALNetworkCommunicationObserveUserProgramAutonomous();
+ void HALNetworkCommunicationObserveUserProgramTeleop();
+ void HALNetworkCommunicationObserveUserProgramTest();
+
+ uint32_t HALReport(uint8_t resource, uint8_t instanceNumber, uint8_t context = 0,
+ const char *feature = NULL);
+}
+
+// TODO: HACKS for now...
+extern "C"
+{
+
+ void NumericArrayResize();
+ void RTSetCleanupProc();
+ void EDVR_CreateReference();
+ void Occur();
+}
diff --git a/hal/include/HAL/Interrupts.hpp b/hal/include/HAL/Interrupts.hpp
new file mode 100644
index 0000000..a41ca6b
--- /dev/null
+++ b/hal/include/HAL/Interrupts.hpp
@@ -0,0 +1,26 @@
+#pragma once
+
+#include <stdint.h>
+
+#include <iostream>
+#include "errno.h"
+
+extern "C"
+{
+ typedef void (*InterruptHandlerFunction)(uint32_t interruptAssertedMask, void *param);
+
+ void* initializeInterrupts(uint32_t interruptIndex, bool watcher, int32_t *status);
+ void cleanInterrupts(void* interrupt_pointer, int32_t *status);
+
+ uint32_t waitForInterrupt(void* interrupt_pointer, double timeout, bool ignorePrevious, int32_t *status);
+ void enableInterrupts(void* interrupt_pointer, int32_t *status);
+ void disableInterrupts(void* interrupt_pointer, int32_t *status);
+ double readRisingTimestamp(void* interrupt_pointer, int32_t *status);
+ double readFallingTimestamp(void* interrupt_pointer, int32_t *status);
+ void requestInterrupts(void* interrupt_pointer, uint8_t routing_module, uint32_t routing_pin,
+ bool routing_analog_trigger, int32_t *status);
+ void attachInterruptHandler(void* interrupt_pointer, InterruptHandlerFunction handler,
+ void* param, int32_t *status);
+ void setInterruptUpSourceEdge(void* interrupt_pointer, bool risingEdge, bool fallingEdge,
+ int32_t *status);
+}
diff --git a/hal/include/HAL/Notifier.hpp b/hal/include/HAL/Notifier.hpp
new file mode 100644
index 0000000..f16572f
--- /dev/null
+++ b/hal/include/HAL/Notifier.hpp
@@ -0,0 +1,11 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+ void* initializeNotifier(void (*ProcessQueue)(uint32_t, void*), void* param, int32_t *status);
+ void cleanNotifier(void* notifier_pointer, int32_t *status);
+
+ void updateNotifierAlarm(void* notifier_pointer, uint32_t triggerTime, int32_t *status);
+}
diff --git a/hal/include/HAL/PDP.hpp b/hal/include/HAL/PDP.hpp
new file mode 100644
index 0000000..54ab6fa
--- /dev/null
+++ b/hal/include/HAL/PDP.hpp
@@ -0,0 +1,16 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+ void initializePDP(uint8_t module);
+ double getPDPTemperature(uint8_t module, int32_t *status);
+ double getPDPVoltage(uint8_t module, int32_t *status);
+ double getPDPChannelCurrent(uint8_t module, uint8_t channel, int32_t *status);
+ double getPDPTotalCurrent(uint8_t module, int32_t *status);
+ double getPDPTotalPower(uint8_t module, int32_t *status);
+ double getPDPTotalEnergy(uint8_t module, int32_t *status);
+ void resetPDPTotalEnergy(uint8_t module, int32_t *status);
+ void clearPDPStickyFaults(uint8_t module, int32_t *status);
+}
diff --git a/hal/include/HAL/Port.h b/hal/include/HAL/Port.h
new file mode 100644
index 0000000..8679c26
--- /dev/null
+++ b/hal/include/HAL/Port.h
@@ -0,0 +1,7 @@
+#pragma once
+
+typedef struct port_t
+{
+ uint8_t pin;
+ uint8_t module;
+} Port;
diff --git a/hal/include/HAL/Power.hpp b/hal/include/HAL/Power.hpp
new file mode 100644
index 0000000..b430c1e
--- /dev/null
+++ b/hal/include/HAL/Power.hpp
@@ -0,0 +1,21 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+ float getVinVoltage(int32_t *status);
+ float getVinCurrent(int32_t *status);
+ float getUserVoltage6V(int32_t *status);
+ float getUserCurrent6V(int32_t *status);
+ bool getUserActive6V(int32_t *status);
+ int getUserCurrentFaults6V(int32_t *status);
+ float getUserVoltage5V(int32_t *status);
+ float getUserCurrent5V(int32_t *status);
+ bool getUserActive5V(int32_t *status);
+ int getUserCurrentFaults5V(int32_t *status);
+ float getUserVoltage3V3(int32_t *status);
+ float getUserCurrent3V3(int32_t *status);
+ bool getUserActive3V3(int32_t *status);
+ int getUserCurrentFaults3V3(int32_t *status);
+}
diff --git a/hal/include/HAL/Semaphore.hpp b/hal/include/HAL/Semaphore.hpp
new file mode 100644
index 0000000..6b9c9e3
--- /dev/null
+++ b/hal/include/HAL/Semaphore.hpp
@@ -0,0 +1,21 @@
+#pragma once
+
+#include "cpp/priority_condition_variable.h"
+#include "cpp/priority_mutex.h"
+
+typedef priority_mutex* MUTEX_ID;
+typedef priority_condition_variable* MULTIWAIT_ID;
+typedef priority_condition_variable::native_handle_type NATIVE_MULTIWAIT_ID;
+
+extern "C" {
+ MUTEX_ID initializeMutexNormal();
+ void deleteMutex(MUTEX_ID sem);
+ void takeMutex(MUTEX_ID sem);
+ bool tryTakeMutex(MUTEX_ID sem);
+ void giveMutex(MUTEX_ID sem);
+
+ MULTIWAIT_ID initializeMultiWait();
+ void deleteMultiWait(MULTIWAIT_ID sem);
+ void takeMultiWait(MULTIWAIT_ID sem, MUTEX_ID m);
+ void giveMultiWait(MULTIWAIT_ID sem);
+}
diff --git a/hal/include/HAL/SerialPort.hpp b/hal/include/HAL/SerialPort.hpp
new file mode 100644
index 0000000..89f1817
--- /dev/null
+++ b/hal/include/HAL/SerialPort.hpp
@@ -0,0 +1,25 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+ void serialInitializePort(uint8_t port, int32_t *status);
+ void serialSetBaudRate(uint8_t port, uint32_t baud, int32_t *status);
+ void serialSetDataBits(uint8_t port, uint8_t bits, int32_t *status);
+ void serialSetParity(uint8_t port, uint8_t parity, int32_t *status);
+ void serialSetStopBits(uint8_t port, uint8_t stopBits, int32_t *status);
+ void serialSetWriteMode(uint8_t port, uint8_t mode, int32_t *status);
+ void serialSetFlowControl(uint8_t port, uint8_t flow, int32_t *status);
+ void serialSetTimeout(uint8_t port, float timeout, int32_t *status);
+ void serialEnableTermination(uint8_t port, char terminator, int32_t *status);
+ void serialDisableTermination(uint8_t port, int32_t *status);
+ void serialSetReadBufferSize(uint8_t port, uint32_t size, int32_t *status);
+ void serialSetWriteBufferSize(uint8_t port, uint32_t size, int32_t *status);
+ int32_t serialGetBytesReceived(uint8_t port, int32_t *status);
+ uint32_t serialRead(uint8_t port, char* buffer, int32_t count, int32_t *status);
+ uint32_t serialWrite(uint8_t port, const char *buffer, int32_t count, int32_t *status);
+ void serialFlush(uint8_t port, int32_t *status);
+ void serialClear(uint8_t port, int32_t *status);
+ void serialClose(uint8_t port, int32_t *status);
+}
diff --git a/hal/include/HAL/Solenoid.hpp b/hal/include/HAL/Solenoid.hpp
new file mode 100644
index 0000000..3b51f21
--- /dev/null
+++ b/hal/include/HAL/Solenoid.hpp
@@ -0,0 +1,19 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+ void* initializeSolenoidPort(void* port_pointer, int32_t *status);
+ void freeSolenoidPort(void* solenoid_port_pointer);
+ bool checkSolenoidModule(uint8_t module);
+
+ bool getSolenoid(void* solenoid_port_pointer, int32_t *status);
+ uint8_t getAllSolenoids(void* solenoid_port_pointer, int32_t *status);
+ void setSolenoid(void* solenoid_port_pointer, bool value, int32_t *status);
+
+ int getPCMSolenoidBlackList(void* solenoid_port_pointer, int32_t *status);
+ bool getPCMSolenoidVoltageStickyFault(void* solenoid_port_pointer, int32_t *status);
+ bool getPCMSolenoidVoltageFault(void* solenoid_port_pointer, int32_t *status);
+ void clearAllPCMStickyFaults_sol(void *solenoid_port_pointer, int32_t *status);
+}
diff --git a/hal/include/HAL/Task.hpp b/hal/include/HAL/Task.hpp
new file mode 100644
index 0000000..3feeec8
--- /dev/null
+++ b/hal/include/HAL/Task.hpp
@@ -0,0 +1,40 @@
+#pragma once
+
+#include <stdint.h>
+#include <pthread.h>
+
+#ifndef _FUNCPTR_DEFINED
+#define _FUNCPTR_DEFINED
+#ifdef __cplusplus
+typedef int (*FUNCPTR)(...);
+/* ptr to function returning int */
+#else
+typedef int (*FUNCPTR) (); /* ptr to function returning int */
+#endif /* __cplusplus */
+#endif /* _FUNCPTR_DEFINED */
+
+#ifndef _STATUS_DEFINED
+#define _STATUS_DEFINED
+typedef int STATUS;
+#endif /* _STATUS_DEFINED */
+
+#ifndef OK
+#define OK 0
+#endif /* OK */
+#ifndef ERROR
+#define ERROR (-1)
+#endif /* ERROR */
+
+#define NULL_TASK NULL
+typedef pthread_t* TASK;
+
+extern "C" {
+ // Note: These constants used to be declared extern and were defined in
+ // Task.cpp. This caused issues with the JNI bindings for java, and so the
+ // instantiations were moved here.
+ const int32_t HAL_taskLib_ILLEGAL_PRIORITY = 22; // 22 is EINVAL
+
+ STATUS verifyTaskID(TASK task);
+ STATUS setTaskPriority(TASK task, int priority); // valid priority [1..99]
+ STATUS getTaskPriority(TASK task, int* priority);
+}
diff --git a/hal/include/HAL/Utilities.hpp b/hal/include/HAL/Utilities.hpp
new file mode 100644
index 0000000..df8ff5e
--- /dev/null
+++ b/hal/include/HAL/Utilities.hpp
@@ -0,0 +1,13 @@
+#pragma once
+
+#include <stdint.h>
+
+extern "C"
+{
+ extern const int32_t HAL_NO_WAIT;
+ extern const int32_t HAL_WAIT_FOREVER;
+
+ void delayTicks(int32_t ticks);
+ void delayMillis(double ms);
+ void delaySeconds(double s);
+}
diff --git a/hal/include/HAL/cpp/Resource.hpp b/hal/include/HAL/cpp/Resource.hpp
new file mode 100644
index 0000000..ae31996
--- /dev/null
+++ b/hal/include/HAL/cpp/Resource.hpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#pragma once
+
+#include "../Errors.hpp"
+#include "HAL/cpp/priority_mutex.h"
+#include <stdint.h>
+
+#include <vector>
+
+// TODO: Replace this with something appropriate to avoid conflicts with
+// wpilibC++ Resource class (which performs an essentially identical function).
+namespace hal {
+
+/**
+ * The Resource class is a convenient way to track allocated resources.
+ * It tracks them as indicies in the range [0 .. elements - 1].
+ * E.g. the library uses this to track hardware channel allocation.
+ *
+ * The Resource class does not allocate the hardware channels or other
+ * resources; it just tracks which indices were marked in use by
+ * Allocate and not yet freed by Free.
+ */
+class Resource
+{
+public:
+ Resource(const Resource&) = delete;
+ Resource& operator=(const Resource&) = delete;
+ explicit Resource(uint32_t size);
+ virtual ~Resource() = default;
+ static void CreateResourceObject(Resource **r, uint32_t elements);
+ uint32_t Allocate(const char *resourceDesc);
+ uint32_t Allocate(uint32_t index, const char *resourceDesc);
+ void Free(uint32_t index);
+
+private:
+ std::vector<bool> m_isAllocated;
+ priority_recursive_mutex m_allocateLock;
+
+ static priority_recursive_mutex m_createLock;
+};
+
+} // namespace hal
diff --git a/hal/include/HAL/cpp/Semaphore.hpp b/hal/include/HAL/cpp/Semaphore.hpp
new file mode 100644
index 0000000..6a6374b
--- /dev/null
+++ b/hal/include/HAL/cpp/Semaphore.hpp
@@ -0,0 +1,30 @@
+#pragma once
+
+#include <cstdint>
+#include <condition_variable>
+
+#include "HAL/cpp/priority_mutex.h"
+
+class Semaphore {
+ public:
+ explicit Semaphore(uint32_t count = 0);
+ Semaphore(Semaphore&&);
+ Semaphore& operator=(Semaphore&&);
+
+ void give();
+ void take();
+
+ // @return true if semaphore was locked successfully. false if not.
+ bool tryTake();
+
+ static const int32_t kNoWait = 0;
+ static const int32_t kWaitForever = -1;
+
+ static const uint32_t kEmpty = 0;
+ static const uint32_t kFull = 1;
+
+ private:
+ priority_mutex m_mutex;
+ std::condition_variable_any m_condition;
+ uint32_t m_count = 0;
+};
diff --git a/hal/include/HAL/cpp/priority_condition_variable.h b/hal/include/HAL/cpp/priority_condition_variable.h
new file mode 100644
index 0000000..e8ab9e5
--- /dev/null
+++ b/hal/include/HAL/cpp/priority_condition_variable.h
@@ -0,0 +1,117 @@
+#pragma once
+
+/* std::condition_variable provides the native_handle() method to return its
+ * underlying pthread_cond_t*. WPILib uses this to interface with the FRC
+ * network communication library. Since WPILib uses a custom mutex class and
+ * not std::mutex, std::condition_variable_any must be used instead.
+ * std::condition_variable_any doesn't expose its internal handle, so this
+ * class provides the same interface and implementation in addition to a
+ * native_handle() method.
+ */
+
+#include <condition_variable>
+#include <memory>
+#include "priority_mutex.h"
+
+class priority_condition_variable {
+ typedef std::chrono::system_clock clock_t;
+
+ public:
+ typedef std::condition_variable::native_handle_type native_handle_type;
+
+ priority_condition_variable() : m_mutex(std::make_shared<std::mutex>()) {}
+ ~priority_condition_variable() = default;
+
+ priority_condition_variable(const priority_condition_variable&) = delete;
+ priority_condition_variable& operator=(const priority_condition_variable&) = delete;
+
+ void notify_one() noexcept {
+ std::lock_guard<std::mutex> lock(*m_mutex);
+ m_cond.notify_one();
+ }
+
+ void notify_all() noexcept {
+ std::lock_guard<std::mutex> lock(*m_mutex);
+ m_cond.notify_all();
+ }
+
+ template<typename Lock>
+ void wait(Lock& _lock) {
+ std::shared_ptr<std::mutex> _mutex = m_mutex;
+ std::unique_lock<std::mutex> my_lock(*_mutex);
+ Unlock<Lock> unlock(_lock);
+
+ // *mutex must be unlocked before re-locking _lock so move
+ // ownership of *_mutex lock to an object with shorter lifetime.
+ std::unique_lock<std::mutex> my_lock2(std::move(my_lock));
+ m_cond.wait(my_lock2);
+ }
+
+ template<typename Lock, typename Predicate>
+ void wait(Lock& lock, Predicate p) {
+ while (!p()) { wait(lock); }
+ }
+
+ template<typename Lock, typename Clock, typename Duration>
+ std::cv_status wait_until(Lock& _lock,
+ const std::chrono::time_point<Clock, Duration>& atime) {
+ std::shared_ptr<std::mutex> _mutex = m_mutex;
+ std::unique_lock<std::mutex> my_lock(*_mutex);
+ Unlock<Lock> unlock(_lock);
+
+ // *_mutex must be unlocked before re-locking _lock so move
+ // ownership of *_mutex lock to an object with shorter lifetime.
+ std::unique_lock<std::mutex> my_lock2(std::move(my_lock));
+ return m_cond.wait_until(my_lock2, atime);
+ }
+
+ template<typename Lock, typename Clock, typename Duration, typename Predicate>
+ bool wait_until(Lock& lock,
+ const std::chrono::time_point<Clock, Duration>& atime, Predicate p) {
+ while (!p()) {
+ if (wait_until(lock, atime) == std::cv_status::timeout) {
+ return p();
+ }
+ }
+ return true;
+ }
+
+ template<typename Lock, typename Rep, typename Period>
+ std::cv_status wait_for(Lock& lock, const std::chrono::duration<Rep, Period>& rtime) {
+ return wait_until(lock, clock_t::now() + rtime);
+ }
+
+ template<typename Lock, typename Rep, typename Period, typename Predicate>
+ bool wait_for(Lock& lock, const std::chrono::duration<Rep, Period>& rtime,
+ Predicate p) {
+ return wait_until(lock, clock_t::now() + rtime, std::move(p));
+ }
+
+ native_handle_type native_handle() {
+ return m_cond.native_handle();
+ }
+
+ private:
+ std::condition_variable m_cond;
+ std::shared_ptr<std::mutex> m_mutex;
+
+ // scoped unlock - unlocks in ctor, re-locks in dtor
+ template<typename Lock>
+ struct Unlock {
+ explicit Unlock(Lock& lk) : m_lock(lk) { lk.unlock(); }
+
+ ~Unlock() /*noexcept(false)*/ {
+ if (std::uncaught_exception()) {
+ try { m_lock.lock(); } catch(...) {}
+ }
+ else {
+ m_lock.lock();
+ }
+ }
+
+ Unlock(const Unlock&) = delete;
+ Unlock& operator=(const Unlock&) = delete;
+
+ Lock& m_lock;
+ };
+};
diff --git a/hal/include/HAL/cpp/priority_mutex.h b/hal/include/HAL/cpp/priority_mutex.h
new file mode 100644
index 0000000..16e88f6
--- /dev/null
+++ b/hal/include/HAL/cpp/priority_mutex.h
@@ -0,0 +1,76 @@
+#pragma once
+
+// Allows usage with std::lock_guard without including <mutex> separately
+#include <mutex>
+
+#ifdef FRC_SIMULATOR
+// We do not want to use pthreads if in the simulator; however, in the
+// simulator, we do not care about priority inversion.
+typedef std::mutex priority_mutex;
+typedef std::recursive_mutex priority_recursive_mutex;
+#else // Covers rest of file.
+
+#include <pthread.h>
+
+class priority_recursive_mutex {
+ public:
+ typedef pthread_mutex_t *native_handle_type;
+
+ constexpr priority_recursive_mutex() noexcept = default;
+ priority_recursive_mutex(const priority_recursive_mutex &) = delete;
+ priority_recursive_mutex &operator=(const priority_recursive_mutex &) = delete;
+
+ // Lock the mutex, blocking until it's available.
+ void lock();
+
+ // Unlock the mutex.
+ void unlock();
+
+ // Tries to lock the mutex.
+ bool try_lock() noexcept;
+
+ pthread_mutex_t *native_handle();
+
+ private:
+ // Do the equivalent of setting PTHREAD_PRIO_INHERIT and
+ // PTHREAD_MUTEX_RECURSIVE_NP.
+#if __WORDSIZE == 64
+ pthread_mutex_t m_mutex = {
+ {0, 0, 0, 0, 0x20 | PTHREAD_MUTEX_RECURSIVE_NP, 0, 0, {0, 0}}};
+#else
+ pthread_mutex_t m_mutex = {
+ {0, 0, 0, 0x20 | PTHREAD_MUTEX_RECURSIVE_NP, 0, {0}}};
+#endif
+};
+
+class priority_mutex {
+ public:
+ typedef pthread_mutex_t *native_handle_type;
+
+ constexpr priority_mutex() noexcept = default;
+ priority_mutex(const priority_mutex &) = delete;
+ priority_mutex &operator=(const priority_mutex &) = delete;
+
+ // Lock the mutex, blocking until it's available.
+ void lock();
+
+ // Unlock the mutex.
+ void unlock();
+
+ // Tries to lock the mutex.
+ bool try_lock() noexcept;
+
+ pthread_mutex_t *native_handle();
+
+ private:
+ // Do the equivalent of setting PTHREAD_PRIO_INHERIT.
+#if __WORDSIZE == 64
+ pthread_mutex_t m_mutex = {
+ {0, 0, 0, 0, 0x20, 0, 0, {0, 0}}};
+#else
+ pthread_mutex_t m_mutex = {
+ {0, 0, 0, 0x20, 0, {0}}};
+#endif
+};
+
+#endif // FRC_SIMULATOR
diff --git a/hal/include/Log.hpp b/hal/include/Log.hpp
new file mode 100644
index 0000000..81b7b84
--- /dev/null
+++ b/hal/include/Log.hpp
@@ -0,0 +1,119 @@
+#pragma once
+
+#include <sstream>
+#include <iomanip>
+#include <string>
+#include <stdio.h>
+#ifdef _WIN32
+ #include <Windows.h>
+#else
+ #include <sys/time.h>
+#endif
+
+inline std::string NowTime();
+
+enum TLogLevel {logNONE, logERROR, logWARNING, logINFO, logDEBUG, logDEBUG1, logDEBUG2, logDEBUG3, logDEBUG4};
+
+class Log
+{
+public:
+ Log();
+ virtual ~Log();
+ std::ostringstream& Get(TLogLevel level = logINFO);
+public:
+ static TLogLevel& ReportingLevel();
+ static std::string ToString(TLogLevel level);
+ static TLogLevel FromString(const std::string& level);
+protected:
+ std::ostringstream os;
+private:
+ Log(const Log&);
+ Log& operator =(const Log&);
+};
+
+inline Log::Log()
+{
+}
+
+inline std::ostringstream& Log::Get(TLogLevel level)
+{
+ os << "- " << NowTime();
+ os << " " << ToString(level) << ": ";
+ os << std::string(level > logDEBUG ? level - logDEBUG : 0, '\t');
+ return os;
+}
+
+inline Log::~Log()
+{
+ os << std::endl;
+ fprintf(stderr, "%s", os.str().c_str());
+ fflush(stderr);
+}
+
+inline TLogLevel& Log::ReportingLevel()
+{
+ static TLogLevel reportingLevel = logDEBUG4;
+ return reportingLevel;
+}
+
+inline std::string Log::ToString(TLogLevel level)
+{
+ static const char* const buffer[] = {"NONE", "ERROR", "WARNING", "INFO", "DEBUG", "DEBUG1", "DEBUG2", "DEBUG3", "DEBUG4"};
+ return buffer[level];
+}
+
+inline TLogLevel Log::FromString(const std::string& level)
+{
+ if (level == "DEBUG4")
+ return logDEBUG4;
+ if (level == "DEBUG3")
+ return logDEBUG3;
+ if (level == "DEBUG2")
+ return logDEBUG2;
+ if (level == "DEBUG1")
+ return logDEBUG1;
+ if (level == "DEBUG")
+ return logDEBUG;
+ if (level == "INFO")
+ return logINFO;
+ if (level == "WARNING")
+ return logWARNING;
+ if (level == "ERROR")
+ return logERROR;
+ if (level == "NONE")
+ return logNONE;
+ Log().Get(logWARNING) << "Unknown logging level '" << level << "'. Using INFO level as default.";
+ return logINFO;
+}
+
+typedef Log FILELog;
+
+#define FILE_LOG(level) \
+ if (level > FILELog::ReportingLevel()) ; \
+ else Log().Get(level)
+
+
+#ifdef _WIN32
+inline std::string NowTime()
+{
+ SYSTEMTIME st;
+ GetLocalTime(&st);
+ char result[100] = {0};
+ sprintf(result, "%d:%d:%d.%d", st.wHour , st.wMinute , st.wSecond , st.wMilliseconds);
+ return result;
+}
+#else
+inline std::string NowTime()
+{
+ char buffer[11];
+ time_t t;
+ time(&t);
+ tm * r = gmtime(&t);
+ strftime(buffer, sizeof(buffer), "%H:%M:%S", r);
+ struct timeval tv;
+ gettimeofday(&tv, 0);
+ char result[100] = {0};
+ sprintf(result, "%s.%03ld", buffer, (long)tv.tv_usec / 1000);
+ return result;
+}
+#endif
diff --git a/hal/include/ctre/CtreCanNode.h b/hal/include/ctre/CtreCanNode.h
new file mode 100644
index 0000000..4af7307
--- /dev/null
+++ b/hal/include/ctre/CtreCanNode.h
@@ -0,0 +1,114 @@
+#ifndef CtreCanNode_H_
+#define CtreCanNode_H_
+#include "ctre.h" //BIT Defines + Typedefs
+#include <map>
+#include <string.h> // memcpy
+#include <sys/time.h>
+class CtreCanNode
+{
+public:
+ CtreCanNode(UINT8 deviceNumber);
+ ~CtreCanNode();
+
+ UINT8 GetDeviceNumber()
+ {
+ return _deviceNumber;
+ }
+protected:
+
+
+ template <typename T> class txTask{
+ public:
+ uint32_t arbId;
+ T * toSend;
+ T * operator -> ()
+ {
+ return toSend;
+ }
+ T & operator*()
+ {
+ return *toSend;
+ }
+ bool IsEmpty()
+ {
+ if(toSend == 0)
+ return true;
+ return false;
+ }
+ };
+ template <typename T> class recMsg{
+ public:
+ uint32_t arbId;
+ uint8_t bytes[8];
+ CTR_Code err;
+ T * operator -> ()
+ {
+ return (T *)bytes;
+ }
+ T & operator*()
+ {
+ return *(T *)bytes;
+ }
+ };
+ UINT8 _deviceNumber;
+ void RegisterRx(uint32_t arbId);
+ void RegisterTx(uint32_t arbId, uint32_t periodMs);
+
+ CTR_Code GetRx(uint32_t arbId,uint8_t * dataBytes,uint32_t timeoutMs);
+ void FlushTx(uint32_t arbId);
+
+ template<typename T> txTask<T> GetTx(uint32_t arbId)
+ {
+ txTask<T> retval = {0, nullptr};
+ txJobs_t::iterator i = _txJobs.find(arbId);
+ if(i != _txJobs.end()){
+ retval.arbId = i->second.arbId;
+ retval.toSend = (T*)i->second.toSend;
+ }
+ return retval;
+ }
+ template<class T> void FlushTx(T & par)
+ {
+ FlushTx(par.arbId);
+ }
+
+ template<class T> recMsg<T> GetRx(uint32_t arbId, uint32_t timeoutMs)
+ {
+ recMsg<T> retval;
+ retval.err = GetRx(arbId,retval.bytes, timeoutMs);
+ return retval;
+ }
+
+private:
+
+ class txJob_t {
+ public:
+ uint32_t arbId;
+ uint8_t toSend[8];
+ uint32_t periodMs;
+ };
+
+ class rxEvent_t{
+ public:
+ uint8_t bytes[8];
+ struct timespec time;
+ rxEvent_t()
+ {
+ bytes[0] = 0;
+ bytes[1] = 0;
+ bytes[2] = 0;
+ bytes[3] = 0;
+ bytes[4] = 0;
+ bytes[5] = 0;
+ bytes[6] = 0;
+ bytes[7] = 0;
+ }
+ };
+
+ typedef std::map<uint32_t,txJob_t> txJobs_t;
+ txJobs_t _txJobs;
+
+ typedef std::map<uint32_t,rxEvent_t> rxRxEvents_t;
+ rxRxEvents_t _rxRxEvents;
+};
+#endif
diff --git a/hal/include/ctre/PCM.h b/hal/include/ctre/PCM.h
new file mode 100644
index 0000000..625108c
--- /dev/null
+++ b/hal/include/ctre/PCM.h
@@ -0,0 +1,218 @@
+#ifndef PCM_H_
+#define PCM_H_
+#include "ctre.h" //BIT Defines + Typedefs
+#include "CtreCanNode.h"
+class PCM : public CtreCanNode
+{
+public:
+ PCM(UINT8 deviceNumber=0);
+ ~PCM();
+
+ /* Set PCM solenoid state
+ *
+ * @Return - CTR_Code - Error code (if any) for setting solenoid
+ * @Param - idx - ID of solenoid (0-7)
+ * @Param - en - Enable / Disable identified solenoid
+ */
+ CTR_Code SetSolenoid(unsigned char idx, bool en);
+
+ /* Enables PCM Closed Loop Control of Compressor via pressure switch
+ * @Return - CTR_Code - Error code (if any) for setting solenoid
+ * @Param - en - Enable / Disable Closed Loop Control
+ */
+ CTR_Code SetClosedLoopControl(bool en);
+
+ /* Clears PCM sticky faults (indicators of past faults
+ * @Return - CTR_Code - Error code (if any) for setting solenoid
+ */
+ CTR_Code ClearStickyFaults();
+
+ /* Get solenoid state
+ *
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - idx - ID of solenoid (0-7) to return if solenoid is on.
+ * @Param - status - true if solenoid enabled, false otherwise
+ */
+ CTR_Code GetSolenoid(UINT8 idx, bool &status);
+
+ /* Get state of all solenoids
+ *
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - bitfield of solenoid states
+ */
+ CTR_Code GetAllSolenoids(UINT8 &status);
+
+ /* Get pressure switch state
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if pressure adequate, false if low
+ */
+ CTR_Code GetPressure(bool &status);
+
+ /* Get compressor state
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if compress ouput is on, false if otherwise
+ */
+ CTR_Code GetCompressor(bool &status);
+
+ /* Get closed loop control state
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if closed loop enabled, false if otherwise
+ */
+ CTR_Code GetClosedLoopControl(bool &status);
+
+ /* Get compressor current draw
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - Compressor current returned in Amperes (A)
+ */
+ CTR_Code GetCompressorCurrent(float &status);
+
+ /* Get voltage across solenoid rail
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - Voltage across solenoid rail in Volts (V)
+ */
+ CTR_Code GetSolenoidVoltage(float &status);
+
+ /* Get hardware fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if hardware failure detected, false if otherwise
+ */
+ CTR_Code GetHardwareFault(bool &status);
+
+ /* Get compressor fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if abnormally high compressor current detected, false if otherwise
+ */
+ CTR_Code GetCompressorCurrentTooHighFault(bool &status);
+
+ /* Get solenoid fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if shorted solenoid detected, false if otherwise
+ */
+ CTR_Code GetSolenoidFault(bool &status);
+
+ /* Get compressor sticky fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if solenoid had previously been shorted
+ * (and sticky fault was not cleared), false if otherwise
+ */
+ CTR_Code GetCompressorCurrentTooHighStickyFault(bool &status);
+ /* Get compressor shorted sticky fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if compressor output is shorted, false if otherwise
+ */
+ CTR_Code GetCompressorShortedStickyFault(bool &status);
+ /* Get compressor shorted fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if compressor output is shorted, false if otherwise
+ */
+ CTR_Code GetCompressorShortedFault(bool &status);
+ /* Get compressor is not connected sticky fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if compressor current is too low,
+ * indicating compressor is not connected, false if otherwise
+ */
+ CTR_Code GetCompressorNotConnectedStickyFault(bool &status);
+ /* Get compressor is not connected fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if compressor current is too low,
+ * indicating compressor is not connected, false if otherwise
+ */
+ CTR_Code GetCompressorNotConnectedFault(bool &status);
+
+ /* Get solenoid sticky fault value
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - True if compressor had previously been shorted
+ * (and sticky fault was not cleared), false if otherwise
+ */
+ CTR_Code GetSolenoidStickyFault(bool &status);
+
+ /* Get battery voltage
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - Voltage across PCM power ports in Volts (V)
+ */
+ CTR_Code GetBatteryVoltage(float &status);
+
+ /* Set PCM Device Number and according CAN frame IDs
+ * @Return - void
+ * @Param - deviceNumber - Device number of PCM to control
+ */
+ void SetDeviceNumber(UINT8 deviceNumber);
+ /* Get number of total failed PCM Control Frame
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - Number of failed control frames (tokenization fails)
+ * @WARNING - Return only valid if [SeekDebugFrames] is enabled
+ * See function SeekDebugFrames
+ * See function EnableSeekDebugFrames
+ */
+ CTR_Code GetNumberOfFailedControlFrames(UINT16 &status);
+
+ /* Get raw Solenoid Blacklist
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - Raw binary breakdown of Solenoid Blacklist
+ * BIT7 = Solenoid 1, BIT6 = Solenoid 2, etc.
+ * @WARNING - Return only valid if [SeekStatusFaultFrames] is enabled
+ * See function SeekStatusFaultFrames
+ * See function EnableSeekStatusFaultFrames
+ */
+ CTR_Code GetSolenoidBlackList(UINT8 &status);
+
+ /* Get solenoid Blacklist status
+ * - Blacklisted solenoids cannot be enabled until PCM is power cycled
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - idx - ID of solenoid [0,7]
+ * @Param - status - True if Solenoid is blacklisted, false if otherwise
+ * @WARNING - Return only valid if [SeekStatusFaultFrames] is enabled
+ * See function SeekStatusFaultFrames
+ * See function EnableSeekStatusFaultFrames
+ */
+ CTR_Code IsSolenoidBlacklisted(UINT8 idx, bool &status);
+
+ /* Return status of module enable/disable
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - status - Returns TRUE if PCM is enabled, FALSE if disabled
+ */
+ CTR_Code isModuleEnabled(bool &status);
+
+ /* Get solenoid Blacklist status
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - idx - ID of solenoid [0,7] to fire one shot pulse.
+ */
+ CTR_Code FireOneShotSolenoid(UINT8 idx);
+
+ /* Configure the pulse width of a solenoid channel for one-shot pulse.
+ * Preprogrammed pulsewidth is 10ms resolute and can be between 20ms and 5.1s.
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - idx - ID of solenoid [0,7] to configure.
+ * @Param - durMs - pulse width in ms.
+ */
+ CTR_Code SetOneShotDurationMs(UINT8 idx,uint32_t durMs);
+
+};
+//------------------ C interface --------------------------------------------//
+extern "C" {
+ void * c_PCM_Init(void);
+ CTR_Code c_SetSolenoid(void * handle,unsigned char idx,INT8 param);
+ CTR_Code c_SetClosedLoopControl(void * handle,INT8 param);
+ CTR_Code c_ClearStickyFaults(void * handle,INT8 param);
+ CTR_Code c_GetSolenoid(void * handle,UINT8 idx,INT8 * status);
+ CTR_Code c_GetAllSolenoids(void * handle,UINT8 * status);
+ CTR_Code c_GetPressure(void * handle,INT8 * status);
+ CTR_Code c_GetCompressor(void * handle,INT8 * status);
+ CTR_Code c_GetClosedLoopControl(void * handle,INT8 * status);
+ CTR_Code c_GetCompressorCurrent(void * handle,float * status);
+ CTR_Code c_GetSolenoidVoltage(void * handle,float*status);
+ CTR_Code c_GetHardwareFault(void * handle,INT8*status);
+ CTR_Code c_GetCompressorFault(void * handle,INT8*status);
+ CTR_Code c_GetSolenoidFault(void * handle,INT8*status);
+ CTR_Code c_GetCompressorStickyFault(void * handle,INT8*status);
+ CTR_Code c_GetSolenoidStickyFault(void * handle,INT8*status);
+ CTR_Code c_GetBatteryVoltage(void * handle,float*status);
+ void c_SetDeviceNumber_PCM(void * handle,UINT8 deviceNumber);
+ void c_EnableSeekStatusFrames(void * handle,INT8 enable);
+ void c_EnableSeekStatusFaultFrames(void * handle,INT8 enable);
+ void c_EnableSeekDebugFrames(void * handle,INT8 enable);
+ CTR_Code c_GetNumberOfFailedControlFrames(void * handle,UINT16*status);
+ CTR_Code c_GetSolenoidBlackList(void * handle,UINT8 *status);
+ CTR_Code c_IsSolenoidBlacklisted(void * handle,UINT8 idx,INT8*status);
+}
+#endif
diff --git a/hal/include/ctre/PDP.h b/hal/include/ctre/PDP.h
new file mode 100644
index 0000000..b968a44
--- /dev/null
+++ b/hal/include/ctre/PDP.h
@@ -0,0 +1,62 @@
+#ifndef PDP_H_
+#define PDP_H_
+#include "ctre.h" //BIT Defines + Typedefs
+#include "CtreCanNode.h"
+class PDP : public CtreCanNode
+{
+public:
+ /* Get PDP Channel Current
+ *
+ * @Param - deviceNumber - Device ID for PDP. Factory default is 60. Function defaults to 60.
+ */
+ PDP(UINT8 deviceNumber=0);
+ ~PDP();
+ /* Get PDP Channel Current
+ *
+ * @Return - CTR_Code - Error code (if any)
+ *
+ * @Param - idx - ID of channel to return current for (channels 1-16)
+ *
+ * @Param - status - Current of channel 'idx' in Amps (A)
+ */
+ CTR_Code GetChannelCurrent(UINT8 idx, double &status);
+
+ /* Get Bus Voltage of PDP
+ *
+ * @Return - CTR_Code - Error code (if any)
+ *
+ * @Param - status - Voltage (V) across PDP
+ */
+ CTR_Code GetVoltage(double &status);
+
+ /* Get Temperature of PDP
+ *
+ * @Return - CTR_Code - Error code (if any)
+ *
+ * @Param - status - Temperature of PDP in Centigrade / Celcius (C)
+ */
+ CTR_Code GetTemperature(double &status);
+
+ CTR_Code GetTotalCurrent(double ¤tAmps);
+ CTR_Code GetTotalPower(double &powerWatts);
+ CTR_Code GetTotalEnergy(double &energyJoules);
+ /* Clear sticky faults.
+ * @Return - CTR_Code - Error code (if any)
+ */
+ CTR_Code ClearStickyFaults();
+
+ /* Reset Energy Signals
+ * @Return - CTR_Code - Error code (if any)
+ */
+ CTR_Code ResetEnergy();
+private:
+ uint64_t ReadCurrents(uint8_t api);
+};
+extern "C" {
+ void * c_PDP_Init();
+ CTR_Code c_GetChannelCurrent(void * handle,UINT8 idx, double *status);
+ CTR_Code c_GetVoltage(void * handle,double *status);
+ CTR_Code c_GetTemperature(void * handle,double *status);
+ void c_SetDeviceNumber_PDP(void * handle,UINT8 deviceNumber);
+}
+#endif /* PDP_H_ */
diff --git a/hal/include/ctre/ctre.h b/hal/include/ctre/ctre.h
new file mode 100644
index 0000000..c2d3f69
--- /dev/null
+++ b/hal/include/ctre/ctre.h
@@ -0,0 +1,50 @@
+#ifndef GLOBAL_H
+#define GLOBAL_H
+
+//Bit Defines
+#define BIT0 0x01
+#define BIT1 0x02
+#define BIT2 0x04
+#define BIT3 0x08
+#define BIT4 0x10
+#define BIT5 0x20
+#define BIT6 0x40
+#define BIT7 0x80
+#define BIT8 0x0100
+#define BIT9 0x0200
+#define BIT10 0x0400
+#define BIT11 0x0800
+#define BIT12 0x1000
+#define BIT13 0x2000
+#define BIT14 0x4000
+#define BIT15 0x8000
+
+//Signed
+typedef signed char INT8;
+typedef signed short INT16;
+typedef signed int INT32;
+typedef signed long long INT64;
+
+//Unsigned
+typedef unsigned char UINT8;
+typedef unsigned short UINT16;
+typedef unsigned int UINT32;
+typedef unsigned long long UINT64;
+
+//Other
+typedef unsigned char UCHAR;
+typedef unsigned short USHORT;
+typedef unsigned int UINT;
+typedef unsigned long ULONG;
+
+typedef enum {
+ CTR_OKAY, //!< No Error - Function executed as expected
+ CTR_RxTimeout, //!< CAN frame has not been received within specified period of time.
+ CTR_TxTimeout, //!< Not used.
+ CTR_InvalidParamValue, //!< Caller passed an invalid param
+ CTR_UnexpectedArbId, //!< Specified CAN Id is invalid.
+ CTR_TxFailed, //!< Could not transmit the CAN frame.
+ CTR_SigNotUpdated, //!< Have not received an value response for signal.
+}CTR_Code;
+
+#endif
diff --git a/hal/lib/Athena/Accelerometer.cpp b/hal/lib/Athena/Accelerometer.cpp
new file mode 100644
index 0000000..0895c9c
--- /dev/null
+++ b/hal/lib/Athena/Accelerometer.cpp
@@ -0,0 +1,234 @@
+#include "HAL/Accelerometer.hpp"
+
+#include "ChipObject.h"
+#include <stdint.h>
+#include <stdio.h>
+#include <assert.h>
+
+// The 7-bit I2C address with a 0 "send" bit
+static const uint8_t kSendAddress = (0x1c << 1) | 0;
+
+// The 7-bit I2C address with a 1 "receive" bit
+static const uint8_t kReceiveAddress = (0x1c << 1) | 1;
+
+static const uint8_t kControlTxRx = 1;
+static const uint8_t kControlStart = 2;
+static const uint8_t kControlStop = 4;
+
+static tAccel *accel = 0;
+static AccelerometerRange accelerometerRange;
+
+// Register addresses
+enum Register {
+ kReg_Status = 0x00,
+ kReg_OutXMSB = 0x01,
+ kReg_OutXLSB = 0x02,
+ kReg_OutYMSB = 0x03,
+ kReg_OutYLSB = 0x04,
+ kReg_OutZMSB = 0x05,
+ kReg_OutZLSB = 0x06,
+ kReg_Sysmod = 0x0B,
+ kReg_IntSource = 0x0C,
+ kReg_WhoAmI = 0x0D,
+ kReg_XYZDataCfg = 0x0E,
+ kReg_HPFilterCutoff = 0x0F,
+ kReg_PLStatus = 0x10,
+ kReg_PLCfg = 0x11,
+ kReg_PLCount = 0x12,
+ kReg_PLBfZcomp = 0x13,
+ kReg_PLThsReg = 0x14,
+ kReg_FFMtCfg = 0x15,
+ kReg_FFMtSrc = 0x16,
+ kReg_FFMtThs = 0x17,
+ kReg_FFMtCount = 0x18,
+ kReg_TransientCfg = 0x1D,
+ kReg_TransientSrc = 0x1E,
+ kReg_TransientThs = 0x1F,
+ kReg_TransientCount = 0x20,
+ kReg_PulseCfg = 0x21,
+ kReg_PulseSrc = 0x22,
+ kReg_PulseThsx = 0x23,
+ kReg_PulseThsy = 0x24,
+ kReg_PulseThsz = 0x25,
+ kReg_PulseTmlt = 0x26,
+ kReg_PulseLtcy = 0x27,
+ kReg_PulseWind = 0x28,
+ kReg_ASlpCount = 0x29,
+ kReg_CtrlReg1 = 0x2A,
+ kReg_CtrlReg2 = 0x2B,
+ kReg_CtrlReg3 = 0x2C,
+ kReg_CtrlReg4 = 0x2D,
+ kReg_CtrlReg5 = 0x2E,
+ kReg_OffX = 0x2F,
+ kReg_OffY = 0x30,
+ kReg_OffZ = 0x31
+};
+
+extern "C" uint32_t getFPGATime(int32_t *status);
+
+static void writeRegister(Register reg, uint8_t data);
+static uint8_t readRegister(Register reg);
+
+/**
+ * Initialize the accelerometer.
+ */
+static void initializeAccelerometer() {
+ int32_t status;
+
+ if(!accel) {
+ accel = tAccel::create(&status);
+
+ // Enable I2C
+ accel->writeCNFG(1, &status);
+
+ // Set the counter to 100 kbps
+ accel->writeCNTR(213, &status);
+
+ // The device identification number should be 0x2a
+ assert(readRegister(kReg_WhoAmI) == 0x2a);
+ }
+}
+
+static void writeRegister(Register reg, uint8_t data) {
+ int32_t status = 0;
+ uint32_t initialTime;
+
+ accel->writeADDR(kSendAddress, &status);
+
+ // Send a start transmit/receive message with the register address
+ accel->writeCNTL(kControlStart | kControlTxRx, &status);
+ accel->writeDATO(reg, &status);
+ accel->strobeGO(&status);
+
+ // Execute and wait until it's done (up to a millisecond)
+ initialTime = getFPGATime(&status);
+ while(accel->readSTAT(&status) & 1) {
+ if(getFPGATime(&status) > initialTime + 1000) break;
+ }
+
+ // Send a stop transmit/receive message with the data
+ accel->writeCNTL(kControlStop | kControlTxRx, &status);
+ accel->writeDATO(data, &status);
+ accel->strobeGO(&status);
+
+ // Execute and wait until it's done (up to a millisecond)
+ initialTime = getFPGATime(&status);
+ while(accel->readSTAT(&status) & 1) {
+ if(getFPGATime(&status) > initialTime + 1000) break;
+ }
+
+ fflush(stdout);
+}
+
+static uint8_t readRegister(Register reg) {
+ int32_t status = 0;
+ uint32_t initialTime;
+
+ // Send a start transmit/receive message with the register address
+ accel->writeADDR(kSendAddress, &status);
+ accel->writeCNTL(kControlStart | kControlTxRx, &status);
+ accel->writeDATO(reg, &status);
+ accel->strobeGO(&status);
+
+ // Execute and wait until it's done (up to a millisecond)
+ initialTime = getFPGATime(&status);
+ while(accel->readSTAT(&status) & 1) {
+ if(getFPGATime(&status) > initialTime + 1000) break;
+ }
+
+ // Receive a message with the data and stop
+ accel->writeADDR(kReceiveAddress, &status);
+ accel->writeCNTL(kControlStart | kControlStop | kControlTxRx, &status);
+ accel->strobeGO(&status);
+
+ // Execute and wait until it's done (up to a millisecond)
+ initialTime = getFPGATime(&status);
+ while(accel->readSTAT(&status) & 1) {
+ if(getFPGATime(&status) > initialTime + 1000) break;
+ }
+
+ fflush(stdout);
+
+ return accel->readDATI(&status);
+}
+
+/**
+ * Convert a 12-bit raw acceleration value into a scaled double in units of
+ * 1 g-force, taking into account the accelerometer range.
+ */
+static double unpackAxis(int16_t raw) {
+ // The raw value is actually 12 bits, not 16, so we need to propogate the
+ // 2's complement sign bit to the unused 4 bits for this to work with
+ // negative numbers.
+ raw <<= 4;
+ raw >>= 4;
+
+ switch(accelerometerRange) {
+ case kRange_2G: return raw / 1024.0;
+ case kRange_4G: return raw / 512.0;
+ case kRange_8G: return raw / 256.0;
+ default: return 0.0;
+ }
+}
+
+/**
+ * Set the accelerometer to active or standby mode. It must be in standby
+ * mode to change any configuration.
+ */
+void setAccelerometerActive(bool active) {
+ initializeAccelerometer();
+
+ uint8_t ctrlReg1 = readRegister(kReg_CtrlReg1);
+ ctrlReg1 &= ~1; // Clear the existing active bit
+ writeRegister(kReg_CtrlReg1, ctrlReg1 | (active? 1 : 0));
+}
+
+/**
+ * Set the range of values that can be measured (either 2, 4, or 8 g-forces).
+ * The accelerometer should be in standby mode when this is called.
+ */
+void setAccelerometerRange(AccelerometerRange range) {
+ initializeAccelerometer();
+
+ accelerometerRange = range;
+
+ uint8_t xyzDataCfg = readRegister(kReg_XYZDataCfg);
+ xyzDataCfg &= ~3; // Clear the existing two range bits
+ writeRegister(kReg_XYZDataCfg, xyzDataCfg | range);
+}
+
+/**
+ * Get the x-axis acceleration
+ *
+ * This is a floating point value in units of 1 g-force
+ */
+double getAccelerometerX() {
+ initializeAccelerometer();
+
+ int raw = (readRegister(kReg_OutXMSB) << 4) | (readRegister(kReg_OutXLSB) >> 4);
+ return unpackAxis(raw);
+}
+
+/**
+ * Get the y-axis acceleration
+ *
+ * This is a floating point value in units of 1 g-force
+ */
+double getAccelerometerY() {
+ initializeAccelerometer();
+
+ int raw = (readRegister(kReg_OutYMSB) << 4) | (readRegister(kReg_OutYLSB) >> 4);
+ return unpackAxis(raw);
+}
+
+/**
+ * Get the z-axis acceleration
+ *
+ * This is a floating point value in units of 1 g-force
+ */
+double getAccelerometerZ() {
+ initializeAccelerometer();
+
+ int raw = (readRegister(kReg_OutZMSB) << 4) | (readRegister(kReg_OutZLSB) >> 4);
+ return unpackAxis(raw);
+}
diff --git a/hal/lib/Athena/Analog.cpp b/hal/lib/Athena/Analog.cpp
new file mode 100644
index 0000000..e56d658
--- /dev/null
+++ b/hal/lib/Athena/Analog.cpp
@@ -0,0 +1,746 @@
+
+#include "HAL/Analog.hpp"
+
+#include "HAL/cpp/priority_mutex.h"
+#include "HAL/Port.h"
+#include "HAL/HAL.hpp"
+#include "ChipObject.h"
+#include "HAL/cpp/Resource.hpp"
+#include "FRC_NetworkCommunication/AICalibration.h"
+#include "FRC_NetworkCommunication/LoadOut.h"
+
+static const long kTimebase = 40000000; ///< 40 MHz clock
+static const long kDefaultOversampleBits = 0;
+static const long kDefaultAverageBits = 7;
+static const float kDefaultSampleRate = 50000.0;
+static const uint32_t kAnalogInputPins = 8;
+static const uint32_t kAnalogOutputPins = 2;
+
+static const uint32_t kAccumulatorNumChannels = 2;
+static const uint32_t kAccumulatorChannels[] = {0, 1};
+
+struct AnalogPort {
+ Port port;
+ tAccumulator *accumulator;
+};
+
+bool analogSampleRateSet = false;
+priority_recursive_mutex analogRegisterWindowMutex;
+tAI* analogInputSystem = NULL;
+tAO* analogOutputSystem = NULL;
+uint32_t analogNumChannelsToActivate = 0;
+
+// Utility methods defined below.
+uint32_t getAnalogNumActiveChannels(int32_t *status);
+uint32_t getAnalogNumChannelsToActivate(int32_t *status);
+void setAnalogNumChannelsToActivate(uint32_t channels);
+
+bool analogSystemInitialized = false;
+
+/**
+ * Initialize the analog System.
+ */
+void initializeAnalog(int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(analogRegisterWindowMutex);
+ if (analogSystemInitialized) return;
+ analogInputSystem = tAI::create(status);
+ analogOutputSystem = tAO::create(status);
+ setAnalogNumChannelsToActivate(kAnalogInputPins);
+ setAnalogSampleRate(kDefaultSampleRate, status);
+ analogSystemInitialized = true;
+}
+
+/**
+ * Initialize the analog input port using the given port object.
+ */
+void* initializeAnalogInputPort(void* port_pointer, int32_t *status) {
+ initializeAnalog(status);
+ Port* port = (Port*) port_pointer;
+
+ // Initialize port structure
+ AnalogPort* analog_port = new AnalogPort();
+ analog_port->port = *port;
+ if (isAccumulatorChannel(analog_port, status)) {
+ analog_port->accumulator = tAccumulator::create(port->pin, status);
+ } else analog_port->accumulator = NULL;
+
+ // Set default configuration
+ analogInputSystem->writeScanList(port->pin, port->pin, status);
+ setAnalogAverageBits(analog_port, kDefaultAverageBits, status);
+ setAnalogOversampleBits(analog_port, kDefaultOversampleBits, status);
+ return analog_port;
+}
+
+void freeAnalogInputPort(void* analog_port_pointer) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (!port) return;
+ delete port->accumulator;
+ delete port;
+}
+
+/**
+ * Initialize the analog output port using the given port object.
+ */
+void* initializeAnalogOutputPort(void* port_pointer, int32_t *status) {
+ initializeAnalog(status);
+ Port* port = (Port*) port_pointer;
+
+ // Initialize port structure
+ AnalogPort* analog_port = new AnalogPort();
+ analog_port->port = *port;
+ analog_port->accumulator = NULL;
+ return analog_port;
+}
+
+void freeAnalogOutputPort(void* analog_port_pointer) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (!port) return;
+ delete port->accumulator;
+ delete port;
+}
+
+
+/**
+ * Check that the analog module number is valid.
+ *
+ * @return Analog module is valid and present
+ */
+bool checkAnalogModule(uint8_t module) {
+ return module == 1;
+}
+
+/**
+ * Check that the analog output channel number is value.
+ * Verify that the analog channel number is one of the legal channel numbers. Channel numbers
+ * are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool checkAnalogInputChannel(uint32_t pin) {
+ if (pin < kAnalogInputPins)
+ return true;
+ return false;
+}
+
+/**
+ * Check that the analog output channel number is value.
+ * Verify that the analog channel number is one of the legal channel numbers. Channel numbers
+ * are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool checkAnalogOutputChannel(uint32_t pin) {
+ if (pin < kAnalogOutputPins)
+ return true;
+ return false;
+}
+
+void setAnalogOutput(void* analog_port_pointer, double voltage, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+
+ uint16_t rawValue = (uint16_t)(voltage / 5.0 * 0x1000);
+
+ if(voltage < 0.0) rawValue = 0;
+ else if(voltage > 5.0) rawValue = 0x1000;
+
+ analogOutputSystem->writeMXP(port->port.pin, rawValue, status);
+}
+
+double getAnalogOutput(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+
+ uint16_t rawValue = analogOutputSystem->readMXP(port->port.pin, status);
+
+ return rawValue * 5.0 / 0x1000;
+}
+
+/**
+ * Set the sample rate.
+ *
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @param samplesPerSecond The number of samples per channel per second.
+ */
+void setAnalogSampleRate(double samplesPerSecond, int32_t *status) {
+ // TODO: This will change when variable size scan lists are implemented.
+ // TODO: Need float comparison with epsilon.
+ //wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond);
+ analogSampleRateSet = true;
+
+ // Compute the convert rate
+ uint32_t ticksPerSample = (uint32_t)((float)kTimebase / samplesPerSecond);
+ uint32_t ticksPerConversion = ticksPerSample / getAnalogNumChannelsToActivate(status);
+ // ticksPerConversion must be at least 80
+ if (ticksPerConversion < 80) {
+ if ((*status) >= 0) *status = SAMPLE_RATE_TOO_HIGH;
+ ticksPerConversion = 80;
+ }
+
+ // Atomically set the scan size and the convert rate so that the sample rate is constant
+ tAI::tConfig config;
+ config.ScanSize = getAnalogNumChannelsToActivate(status);
+ config.ConvertRate = ticksPerConversion;
+ analogInputSystem->writeConfig(config, status);
+
+ // Indicate that the scan size has been commited to hardware.
+ setAnalogNumChannelsToActivate(0);
+}
+
+/**
+ * Get the current sample rate.
+ *
+ * This assumes one entry in the scan list.
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @return Sample rate.
+ */
+float getAnalogSampleRate(int32_t *status) {
+ uint32_t ticksPerConversion = analogInputSystem->readLoopTiming(status);
+ uint32_t ticksPerSample = ticksPerConversion * getAnalogNumActiveChannels(status);
+ return (float)kTimebase / (float)ticksPerSample;
+}
+
+/**
+ * Set the number of averaging bits.
+ *
+ * This sets the number of averaging bits. The actual number of averaged samples is 2**bits.
+ * Use averaging to improve the stability of your measurement at the expense of sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param analog_port_pointer Pointer to the analog port to configure.
+ * @param bits Number of bits to average.
+ */
+void setAnalogAverageBits(void* analog_port_pointer, uint32_t bits, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ analogInputSystem->writeAverageBits(port->port.pin, bits, status);
+}
+
+/**
+ * Get the number of averaging bits.
+ *
+ * This gets the number of averaging bits from the FPGA. The actual number of averaged samples is 2**bits.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Bits to average.
+ */
+uint32_t getAnalogAverageBits(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ uint32_t result = analogInputSystem->readAverageBits(port->port.pin, status);
+ return result;
+}
+
+/**
+ * Set the number of oversample bits.
+ *
+ * This sets the number of oversample bits. The actual number of oversampled values is 2**bits.
+ * Use oversampling to improve the resolution of your measurements at the expense of sampling rate.
+ * The oversampling is done automatically in the FPGA.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @param bits Number of bits to oversample.
+ */
+void setAnalogOversampleBits(void* analog_port_pointer, uint32_t bits, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ analogInputSystem->writeOversampleBits(port->port.pin, bits, status);
+}
+
+
+/**
+ * Get the number of oversample bits.
+ *
+ * This gets the number of oversample bits from the FPGA. The actual number of oversampled values is
+ * 2**bits. The oversampling is done automatically in the FPGA.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Bits to oversample.
+ */
+uint32_t getAnalogOversampleBits(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ uint32_t result = analogInputSystem->readOversampleBits(port->port.pin, status);
+ return result;
+}
+
+/**
+ * Get a sample straight from the channel on this module.
+ *
+ * The sample is a 12-bit value representing the 0V to 5V range of the A/D converter in the module.
+ * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A sample straight from the channel on this module.
+ */
+int16_t getAnalogValue(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ int16_t value;
+ if (!checkAnalogInputChannel(port->port.pin)) {
+ return 0;
+ }
+
+ tAI::tReadSelect readSelect;
+ readSelect.Channel = port->port.pin;
+ readSelect.Averaged = false;
+
+ {
+ std::lock_guard<priority_recursive_mutex> sync(analogRegisterWindowMutex);
+ analogInputSystem->writeReadSelect(readSelect, status);
+ analogInputSystem->strobeLatchOutput(status);
+ value = (int16_t) analogInputSystem->readOutput(status);
+ }
+
+ return value;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for the channel.
+ *
+ * The sample is 12-bit + the value configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged 2**bits number of samples.
+ * This is not a sliding window. The sample will not change until 2**(OversamplBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A sample from the oversample and average engine for the channel.
+ */
+int32_t getAnalogAverageValue(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ int32_t value;
+ if (!checkAnalogInputChannel(port->port.pin)) {
+ return 0;
+ }
+
+ tAI::tReadSelect readSelect;
+ readSelect.Channel = port->port.pin;
+ readSelect.Averaged = true;
+
+ {
+ std::lock_guard<priority_recursive_mutex> sync(analogRegisterWindowMutex);
+ analogInputSystem->writeReadSelect(readSelect, status);
+ analogInputSystem->strobeLatchOutput(status);
+ value = (int32_t) analogInputSystem->readOutput(status);
+ }
+
+ return value;
+}
+
+/**
+ * Get a scaled sample straight from the channel on this module.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A scaled sample straight from the channel on this module.
+ */
+float getAnalogVoltage(void* analog_port_pointer, int32_t *status) {
+ int16_t value = getAnalogValue(analog_port_pointer, status);
+ uint32_t LSBWeight = getAnalogLSBWeight(analog_port_pointer, status);
+ int32_t offset = getAnalogOffset(analog_port_pointer, status);
+ float voltage = LSBWeight * 1.0e-9 * value - offset * 1.0e-9;
+ return voltage;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for the channel.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update more slowly.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return A scaled sample from the output of the oversample and average engine for the channel.
+ */
+float getAnalogAverageVoltage(void* analog_port_pointer, int32_t *status) {
+ int32_t value = getAnalogAverageValue(analog_port_pointer, status);
+ uint32_t LSBWeight = getAnalogLSBWeight(analog_port_pointer, status);
+ int32_t offset = getAnalogOffset(analog_port_pointer, status);
+ uint32_t oversampleBits = getAnalogOversampleBits(analog_port_pointer, status);
+ float voltage = ((LSBWeight * 1.0e-9 * value) / (float)(1 << oversampleBits)) - offset * 1.0e-9;
+ return voltage;
+}
+
+/**
+ * Convert a voltage to a raw value for a specified channel.
+ *
+ * This process depends on the calibration of each channel, so the channel
+ * must be specified.
+ *
+ * @todo This assumes raw values. Oversampling not supported as is.
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @param voltage The voltage to convert.
+ * @return The raw value for the channel.
+ */
+int32_t getAnalogVoltsToValue(void* analog_port_pointer, double voltage, int32_t *status) {
+ if (voltage > 5.0) {
+ voltage = 5.0;
+ *status = VOLTAGE_OUT_OF_RANGE;
+ }
+ if (voltage < 0.0) {
+ voltage = 0.0;
+ *status = VOLTAGE_OUT_OF_RANGE;
+ }
+ uint32_t LSBWeight = getAnalogLSBWeight(analog_port_pointer, status);
+ int32_t offset = getAnalogOffset(analog_port_pointer, status);
+ int32_t value = (int32_t) ((voltage + offset * 1.0e-9) / (LSBWeight * 1.0e-9));
+ return value;
+}
+
+/**
+ * Get the factory scaling least significant bit weight constant.
+ * The least significant bit weight constant for the channel that was calibrated in
+ * manufacturing and stored in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Least significant bit weight.
+ */
+uint32_t getAnalogLSBWeight(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ uint32_t lsbWeight = FRC_NetworkCommunication_nAICalibration_getLSBWeight(0, port->port.pin, status); // XXX: aiSystemIndex == 0?
+ return lsbWeight;
+}
+
+/**
+ * Get the factory scaling offset constant.
+ * The offset constant for the channel that was calibrated in manufacturing and stored
+ * in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param analog_port_pointer Pointer to the analog port to use.
+ * @return Offset constant.
+ */
+int32_t getAnalogOffset(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ int32_t offset = FRC_NetworkCommunication_nAICalibration_getOffset(0, port->port.pin, status); // XXX: aiSystemIndex == 0?
+ return offset;
+}
+
+
+/**
+ * Return the number of channels on the module in use.
+ *
+ * @return Active channels.
+ */
+uint32_t getAnalogNumActiveChannels(int32_t *status) {
+ uint32_t scanSize = analogInputSystem->readConfig_ScanSize(status);
+ if (scanSize == 0)
+ return 8;
+ return scanSize;
+}
+
+/**
+ * Get the number of active channels.
+ *
+ * This is an internal function to allow the atomic update of both the
+ * number of active channels and the sample rate.
+ *
+ * When the number of channels changes, use the new value. Otherwise,
+ * return the curent value.
+ *
+ * @return Value to write to the active channels field.
+ */
+uint32_t getAnalogNumChannelsToActivate(int32_t *status) {
+ if(analogNumChannelsToActivate == 0) return getAnalogNumActiveChannels(status);
+ return analogNumChannelsToActivate;
+}
+
+/**
+ * Set the number of active channels.
+ *
+ * Store the number of active channels to set. Don't actually commit to hardware
+ * until SetSampleRate().
+ *
+ * @param channels Number of active channels.
+ */
+void setAnalogNumChannelsToActivate(uint32_t channels) {
+ analogNumChannelsToActivate = channels;
+}
+
+//// Accumulator Stuff
+
+/**
+ * Is the channel attached to an accumulator.
+ *
+ * @return The analog channel is attached to an accumulator.
+ */
+bool isAccumulatorChannel(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ for (uint32_t i=0; i < kAccumulatorNumChannels; i++) {
+ if (port->port.pin == kAccumulatorChannels[i]) return true;
+ }
+ return false;
+}
+
+/**
+ * Initialize the accumulator.
+ */
+void initAccumulator(void* analog_port_pointer, int32_t *status) {
+ setAccumulatorCenter(analog_port_pointer, 0, status);
+ resetAccumulator(analog_port_pointer, status);
+}
+
+/**
+ * Resets the accumulator to the initial value.
+ */
+void resetAccumulator(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (port->accumulator == NULL) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ port->accumulator->strobeReset(status);
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each A/D value before it is added to the accumulator. This
+ * is used for the center value of devices like gyros and accelerometers to make integration work
+ * and to take the device offset into account when integrating.
+ *
+ * This center value is based on the output of the oversampled and averaged source from channel 1.
+ * Because of this, any non-zero oversample bits will affect the size of the value for this field.
+ */
+void setAccumulatorCenter(void* analog_port_pointer, int32_t center, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (port->accumulator == NULL) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ port->accumulator->writeCenter(center, status);
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void setAccumulatorDeadband(void* analog_port_pointer, int32_t deadband, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (port->accumulator == NULL) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ port->accumulator->writeDeadband(deadband, status);
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * Read the value that has been accumulating on channel 1.
+ * The accumulator is attached after the oversample and average engine.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t getAccumulatorValue(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (port->accumulator == NULL) {
+ *status = NULL_PARAMETER;
+ return 0;
+ }
+ int64_t value = port->accumulator->readOutput_Value(status);
+ return value;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+uint32_t getAccumulatorCount(void* analog_port_pointer, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (port->accumulator == NULL) {
+ *status = NULL_PARAMETER;
+ return 0;
+ }
+ return port->accumulator->readOutput_Count(status);
+}
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count from the FPGA atomically.
+ * This can be used for averaging.
+ *
+ * @param value Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void getAccumulatorOutput(void* analog_port_pointer, int64_t *value, uint32_t *count, int32_t *status) {
+ AnalogPort* port = (AnalogPort*) analog_port_pointer;
+ if (port->accumulator == NULL) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ if (value == NULL || count == NULL) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+
+ tAccumulator::tOutput output = port->accumulator->readOutput(status);
+
+ *value = output.Value;
+ *count = output.Count;
+}
+
+
+struct trigger_t {
+ tAnalogTrigger* trigger;
+ AnalogPort* port;
+ uint32_t index;
+};
+typedef struct trigger_t AnalogTrigger;
+
+static hal::Resource *triggers = NULL;
+
+void* initializeAnalogTrigger(void* port_pointer, uint32_t *index, int32_t *status) {
+ Port* port = (Port*) port_pointer;
+ hal::Resource::CreateResourceObject(&triggers, tAnalogTrigger::kNumSystems);
+
+ AnalogTrigger* trigger = new AnalogTrigger();
+ trigger->port = (AnalogPort*) initializeAnalogInputPort(port, status);
+ trigger->index = triggers->Allocate("Analog Trigger");
+ *index = trigger->index;
+ // TODO: if (index == ~0ul) { CloneError(triggers); return; }
+
+ trigger->trigger = tAnalogTrigger::create(trigger->index, status);
+ trigger->trigger->writeSourceSelect_Channel(port->pin, status);
+
+ return trigger;
+}
+
+void cleanAnalogTrigger(void* analog_trigger_pointer, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ if (!trigger) return;
+ triggers->Free(trigger->index);
+ delete trigger->trigger;
+ freeAnalogInputPort(trigger->port);
+ delete trigger;
+}
+
+void setAnalogTriggerLimitsRaw(void* analog_trigger_pointer, int32_t lower, int32_t upper, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ if (lower > upper) {
+ *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+ }
+ trigger->trigger->writeLowerLimit(lower, status);
+ trigger->trigger->writeUpperLimit(upper, status);
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ * The limits are given as floating point voltage values.
+ */
+void setAnalogTriggerLimitsVoltage(void* analog_trigger_pointer, double lower, double upper, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ if (lower > upper) {
+ *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+ }
+ // TODO: This depends on the averaged setting. Only raw values will work as is.
+ trigger->trigger->writeLowerLimit(getAnalogVoltsToValue(trigger->port, lower, status), status);
+ trigger->trigger->writeUpperLimit(getAnalogVoltsToValue(trigger->port, upper, status), status);
+}
+
+/**
+ * Configure the analog trigger to use the averaged vs. raw values.
+ * If the value is true, then the averaged value is selected for the analog trigger, otherwise
+ * the immediate value is used.
+ */
+void setAnalogTriggerAveraged(void* analog_trigger_pointer, bool useAveragedValue, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ if (trigger->trigger->readSourceSelect_Filter(status) != 0) {
+ *status = INCOMPATIBLE_STATE;
+ // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not support average and filtering at the same time.");
+ }
+ trigger->trigger->writeSourceSelect_Averaged(useAveragedValue, status);
+}
+
+/**
+ * Configure the analog trigger to use a filtered value.
+ * The analog trigger will operate with a 3 point average rejection filter. This is designed to
+ * help with 360 degree pot applications for the period where the pot crosses through zero.
+ */
+void setAnalogTriggerFiltered(void* analog_trigger_pointer, bool useFilteredValue, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ if (trigger->trigger->readSourceSelect_Averaged(status) != 0) {
+ *status = INCOMPATIBLE_STATE;
+ // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not support average and filtering at the same time.");
+ }
+ trigger->trigger->writeSourceSelect_Filter(useFilteredValue, status);
+}
+
+/**
+ * Return the InWindow output of the analog trigger.
+ * True if the analog input is between the upper and lower limits.
+ * @return The InWindow output of the analog trigger.
+ */
+bool getAnalogTriggerInWindow(void* analog_trigger_pointer, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ return trigger->trigger->readOutput_InHysteresis(trigger->index, status) != 0;
+}
+
+/**
+ * Return the TriggerState output of the analog trigger.
+ * True if above upper limit.
+ * False if below lower limit.
+ * If in Hysteresis, maintain previous state.
+ * @return The TriggerState output of the analog trigger.
+ */
+bool getAnalogTriggerTriggerState(void* analog_trigger_pointer, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ return trigger->trigger->readOutput_OverLimit(trigger->index, status) != 0;
+}
+
+/**
+ * Get the state of the analog trigger output.
+ * @return The state of the analog trigger output.
+ */
+bool getAnalogTriggerOutput(void* analog_trigger_pointer, AnalogTriggerType type, int32_t *status) {
+ AnalogTrigger* trigger = (AnalogTrigger*) analog_trigger_pointer;
+ bool result = false;
+ switch(type) {
+ case kInWindow:
+ result = trigger->trigger->readOutput_InHysteresis(trigger->index, status);
+ break; // XXX: Backport
+ case kState:
+ result = trigger->trigger->readOutput_OverLimit(trigger->index, status);
+ break; // XXX: Backport
+ case kRisingPulse:
+ case kFallingPulse:
+ *status = ANALOG_TRIGGER_PULSE_OUTPUT_ERROR;
+ return false;
+ }
+ return result;
+}
+
+
+
+//// Float JNA Hack
+// Float
+int getAnalogSampleRateIntHack(int32_t *status) {
+ return floatToInt(getAnalogSampleRate(status));
+}
+
+int getAnalogVoltageIntHack(void* analog_port_pointer, int32_t *status) {
+ return floatToInt(getAnalogVoltage(analog_port_pointer, status));
+}
+
+int getAnalogAverageVoltageIntHack(void* analog_port_pointer, int32_t *status) {
+ return floatToInt(getAnalogAverageVoltage(analog_port_pointer, status));
+}
+
+
+// Doubles
+void setAnalogSampleRateIntHack(int samplesPerSecond, int32_t *status) {
+ setAnalogSampleRate(intToFloat(samplesPerSecond), status);
+}
+
+int32_t getAnalogVoltsToValueIntHack(void* analog_port_pointer, int voltage, int32_t *status) {
+ return getAnalogVoltsToValue(analog_port_pointer, intToFloat(voltage), status);
+}
+
+void setAnalogTriggerLimitsVoltageIntHack(void* analog_trigger_pointer, int lower, int upper, int32_t *status) {
+ setAnalogTriggerLimitsVoltage(analog_trigger_pointer, intToFloat(lower), intToFloat(upper), status);
+}
diff --git a/hal/lib/Athena/ChipObject.h b/hal/lib/Athena/ChipObject.h
new file mode 100644
index 0000000..630c34d
--- /dev/null
+++ b/hal/lib/Athena/ChipObject.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+#pragma once
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wpedantic"
+#pragma GCC diagnostic ignored "-Wignored-qualifiers"
+
+#include <stdint.h>
+
+#include "FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h"
+#include "FRC_FPGA_ChipObject/tDMAChannelDescriptor.h"
+#include "FRC_FPGA_ChipObject/tDMAManager.h"
+#include "FRC_FPGA_ChipObject/tInterruptManager.h"
+#include "FRC_FPGA_ChipObject/tSystem.h"
+#include "FRC_FPGA_ChipObject/tSystemInterface.h"
+
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h"
+#include "FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h"
+
+// FIXME: these should not be here!
+using namespace nFPGA;
+using namespace nRoboRIO_FPGANamespace;
+#pragma GCC diagnostic pop
diff --git a/hal/lib/Athena/Compressor.cpp b/hal/lib/Athena/Compressor.cpp
new file mode 100644
index 0000000..9305097
--- /dev/null
+++ b/hal/lib/Athena/Compressor.cpp
@@ -0,0 +1,116 @@
+#include "HAL/Compressor.hpp"
+#include "ctre/PCM.h"
+#include <iostream>
+
+static const int NUM_MODULE_NUMBERS = 63;
+extern PCM *modules[NUM_MODULE_NUMBERS];
+extern void initializePCM(int module);
+
+void *initializeCompressor(uint8_t module) {
+ initializePCM(module);
+
+ return modules[module];
+}
+
+bool checkCompressorModule(uint8_t module) {
+ return module < NUM_MODULE_NUMBERS;
+}
+
+bool getCompressor(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressor(value);
+
+ return value;
+}
+
+
+void setClosedLoopControl(void *pcm_pointer, bool value, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+
+ *status = module->SetClosedLoopControl(value);
+}
+
+
+bool getClosedLoopControl(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetClosedLoopControl(value);
+
+ return value;
+}
+
+
+bool getPressureSwitch(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetPressure(value);
+
+ return value;
+}
+
+
+float getCompressorCurrent(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ float value;
+
+ *status = module->GetCompressorCurrent(value);
+
+ return value;
+}
+bool getCompressorCurrentTooHighFault(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressorCurrentTooHighFault(value);
+
+ return value;
+}
+bool getCompressorCurrentTooHighStickyFault(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressorCurrentTooHighStickyFault(value);
+
+ return value;
+}
+bool getCompressorShortedStickyFault(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressorShortedStickyFault(value);
+
+ return value;
+}
+bool getCompressorShortedFault(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressorShortedFault(value);
+
+ return value;
+}
+bool getCompressorNotConnectedStickyFault(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressorNotConnectedStickyFault(value);
+
+ return value;
+}
+bool getCompressorNotConnectedFault(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+ bool value;
+
+ *status = module->GetCompressorNotConnectedFault(value);
+
+ return value;
+}
+void clearAllPCMStickyFaults(void *pcm_pointer, int32_t *status) {
+ PCM *module = (PCM *)pcm_pointer;
+
+ *status = module->ClearStickyFaults();
+}
diff --git a/hal/lib/Athena/Digital.cpp b/hal/lib/Athena/Digital.cpp
new file mode 100644
index 0000000..0d4ff5f
--- /dev/null
+++ b/hal/lib/Athena/Digital.cpp
@@ -0,0 +1,1874 @@
+
+#include "HAL/Digital.hpp"
+
+#include "HAL/Port.h"
+#include "HAL/HAL.hpp"
+#include "ChipObject.h"
+#include "HAL/cpp/Resource.hpp"
+#include "HAL/cpp/priority_mutex.h"
+#include "FRC_NetworkCommunication/LoadOut.h"
+#include <stdio.h>
+#include <math.h>
+#include <mutex>
+#include "i2clib/i2c-lib.h"
+#include "spilib/spi-lib.h"
+
+static_assert(sizeof(uint32_t) <= sizeof(void *), "This file shoves uint32_ts into pointers.");
+
+static const uint32_t kExpectedLoopTiming = 40;
+static const uint32_t kDigitalPins = 26;
+static const uint32_t kPwmPins = 20;
+static const uint32_t kRelayPins = 8;
+static const uint32_t kNumHeaders = 10; // Number of non-MXP pins
+
+/**
+ * kDefaultPwmPeriod is in ms
+ *
+ * - 20ms periods (50 Hz) are the "safest" setting in that this works for all devices
+ * - 20ms periods seem to be desirable for Vex Motors
+ * - 20ms periods are the specified period for HS-322HD servos, but work reliably down
+ * to 10.0 ms; starting at about 8.5ms, the servo sometimes hums and get hot;
+ * by 5.0ms the hum is nearly continuous
+ * - 10ms periods work well for Victor 884
+ * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed controllers.
+ * Due to the shipping firmware on the Jaguar, we can't run the update period less
+ * than 5.05 ms.
+ *
+ * kDefaultPwmPeriod is the 1x period (5.05 ms). In hardware, the period scaling is implemented as an
+ * output squelch to get longer periods for old devices.
+ */
+static const float kDefaultPwmPeriod = 5.05;
+/**
+ * kDefaultPwmCenter is the PWM range center in ms
+ */
+static const float kDefaultPwmCenter = 1.5;
+/**
+ * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
+ */
+static const int32_t kDefaultPwmStepsDown = 1000;
+static const int32_t kPwmDisabled = 0;
+
+struct DigitalPort {
+ Port port;
+ uint32_t PWMGeneratorID;
+};
+
+// XXX: Set these back to static once we figure out the memory clobbering issue
+// Create a mutex to protect changes to the digital output values
+priority_recursive_mutex digitalDIOMutex;
+// Create a mutex to protect changes to the relay values
+priority_recursive_mutex digitalRelayMutex;
+// Create a mutex to protect changes to the DO PWM config
+priority_recursive_mutex digitalPwmMutex;
+priority_recursive_mutex digitalI2COnBoardMutex;
+priority_recursive_mutex digitalI2CMXPMutex;
+
+tDIO* digitalSystem = NULL;
+tRelay* relaySystem = NULL;
+tPWM* pwmSystem = NULL;
+hal::Resource *DIOChannels = NULL;
+hal::Resource *DO_PWMGenerators = NULL;
+hal::Resource *PWMChannels = NULL;
+
+bool digitalSystemsInitialized = false;
+
+uint8_t i2COnboardObjCount = 0;
+uint8_t i2CMXPObjCount = 0;
+uint8_t i2COnBoardHandle = 0;
+uint8_t i2CMXPHandle = 0;
+
+int32_t m_spiCS0Handle = 0;
+int32_t m_spiCS1Handle = 0;
+int32_t m_spiCS2Handle = 0;
+int32_t m_spiCS3Handle = 0;
+int32_t m_spiMXPHandle = 0;
+priority_recursive_mutex spiOnboardSemaphore;
+priority_recursive_mutex spiMXPSemaphore;
+tSPI *spiSystem;
+
+struct SPIAccumulator {
+ void* notifier = nullptr;
+ uint32_t triggerTime;
+ uint32_t period;
+
+ int64_t value = 0;
+ uint32_t count = 0;
+ int32_t last_value = 0;
+
+ int32_t center = 0;
+ int32_t deadband = 0;
+
+ uint8_t cmd[4]; // command to send (up to 4 bytes)
+ uint32_t valid_mask;
+ uint32_t valid_value;
+ int32_t data_max; // one more than max data value
+ int32_t data_msb_mask; // data field MSB mask (for signed)
+ uint8_t data_shift; // data field shift right amount, in bits
+ uint8_t xfer_size; // SPI transfer size, in bytes (up to 4)
+ uint8_t port;
+ bool is_signed; // is data field signed?
+ bool big_endian; // is response big endian?
+};
+SPIAccumulator* spiAccumulators[5] = {nullptr, nullptr, nullptr, nullptr, nullptr};
+
+/**
+ * Initialize the digital system.
+ */
+void initializeDigital(int32_t *status) {
+ if (digitalSystemsInitialized) return;
+
+ hal::Resource::CreateResourceObject(&DIOChannels, tDIO::kNumSystems * kDigitalPins);
+ hal::Resource::CreateResourceObject(&DO_PWMGenerators, tDIO::kNumPWMDutyCycleAElements + tDIO::kNumPWMDutyCycleBElements);
+ hal::Resource::CreateResourceObject(&PWMChannels, tPWM::kNumSystems * kPwmPins);
+ digitalSystem = tDIO::create(status);
+
+ // Relay Setup
+ relaySystem = tRelay::create(status);
+
+ // Turn off all relay outputs.
+ relaySystem->writeValue_Forward(0, status);
+ relaySystem->writeValue_Reverse(0, status);
+
+ // PWM Setup
+ pwmSystem = tPWM::create(status);
+
+ // Make sure that the 9403 IONode has had a chance to initialize before continuing.
+ while(pwmSystem->readLoopTiming(status) == 0) delayTicks(1);
+
+ if (pwmSystem->readLoopTiming(status) != kExpectedLoopTiming) {
+ // TODO: char err[128];
+ // TODO: sprintf(err, "DIO LoopTiming: %d, expecting: %lu\n", digitalModules[port->module-1]->readLoopTiming(status), kExpectedLoopTiming);
+ *status = LOOP_TIMING_ERROR; // NOTE: Doesn't display the error
+ }
+
+ //Calculate the length, in ms, of one DIO loop
+ double loopTime = pwmSystem->readLoopTiming(status)/(kSystemClockTicksPerMicrosecond*1e3);
+
+ pwmSystem->writeConfig_Period((uint16_t) (kDefaultPwmPeriod/loopTime + .5), status);
+ uint16_t minHigh = (uint16_t) ((kDefaultPwmCenter-kDefaultPwmStepsDown*loopTime)/loopTime + .5);
+ pwmSystem->writeConfig_MinHigh(minHigh, status);
+// printf("MinHigh: %d\n", minHigh);
+ // Ensure that PWM output values are set to OFF
+ for (uint32_t pwm_index = 0; pwm_index < kPwmPins; pwm_index++) {
+ // Initialize port structure
+ DigitalPort digital_port;
+ digital_port.port.pin = pwm_index;
+
+ setPWM(&digital_port, kPwmDisabled, status);
+ setPWMPeriodScale(&digital_port, 3, status); // Set all to 4x by default.
+ }
+
+ digitalSystemsInitialized = true;
+}
+
+/**
+ * Create a new instance of a digital port.
+ */
+void* initializeDigitalPort(void* port_pointer, int32_t *status) {
+ initializeDigital(status);
+ Port* port = (Port*) port_pointer;
+
+ // Initialize port structure
+ DigitalPort* digital_port = new DigitalPort();
+ digital_port->port = *port;
+
+ return digital_port;
+}
+
+void freeDigitalPort(void* digital_port_pointer) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ delete port;
+}
+
+bool checkPWMChannel(void* digital_port_pointer) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ return port->port.pin < kPwmPins;
+}
+
+bool checkRelayChannel(void* digital_port_pointer) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ return port->port.pin < kRelayPins;
+}
+
+/**
+ * Check a port to make sure that it is not NULL and is a valid PWM port.
+ *
+ * Sets the status to contain the appropriate error.
+ *
+ * @return true if the port passed validation.
+ */
+static bool verifyPWMChannel(DigitalPort *port, int32_t *status) {
+ if (port == NULL) {
+ *status = NULL_PARAMETER;
+ return false;
+ } else if (!checkPWMChannel(port)) {
+ *status = PARAMETER_OUT_OF_RANGE;
+ return false;
+ } else {
+ return true;
+ }
+}
+
+/**
+ * Check a port to make sure that it is not NULL and is a valid Relay port.
+ *
+ * Sets the status to contain the appropriate error.
+ *
+ * @return true if the port passed validation.
+ */
+static bool verifyRelayChannel(DigitalPort *port, int32_t *status) {
+ if (port == NULL) {
+ *status = NULL_PARAMETER;
+ return false;
+ } else if (!checkRelayChannel(port)) {
+ *status = PARAMETER_OUT_OF_RANGE;
+ return false;
+ } else {
+ return true;
+ }
+}
+
+/**
+ * Map DIO pin numbers from their physical number (10 to 26) to their position
+ * in the bit field.
+ */
+uint32_t remapMXPChannel(uint32_t pin) {
+ return pin - 10;
+}
+
+uint32_t remapMXPPWMChannel(uint32_t pin) {
+ if(pin < 14) {
+ return pin - 10; //first block of 4 pwms (MXP 0-3)
+ } else {
+ return pin - 6; //block of PWMs after SPI
+ }
+}
+
+/**
+ * Set a PWM channel to the desired value. The values range from 0 to 255 and the period is controlled
+ * by the PWM Period and MinHigh registers.
+ *
+ * @param channel The PWM channel to set.
+ * @param value The PWM value to set.
+ */
+void setPWM(void* digital_port_pointer, unsigned short value, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyPWMChannel(port, status)) { return; }
+
+ if(port->port.pin < tPWM::kNumHdrRegisters) {
+ pwmSystem->writeHdr(port->port.pin, value, status);
+ } else {
+ pwmSystem->writeMXP(port->port.pin - tPWM::kNumHdrRegisters, value, status);
+ }
+}
+
+/**
+ * Get a value from a PWM channel. The values range from 0 to 255.
+ *
+ * @param channel The PWM channel to read from.
+ * @return The raw PWM value.
+ */
+unsigned short getPWM(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyPWMChannel(port, status)) { return 0; }
+
+ if(port->port.pin < tPWM::kNumHdrRegisters) {
+ return pwmSystem->readHdr(port->port.pin, status);
+ } else {
+ return pwmSystem->readMXP(port->port.pin - tPWM::kNumHdrRegisters, status);
+ }
+}
+
+void latchPWMZero(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyPWMChannel(port, status)) { return; }
+
+ pwmSystem->writeZeroLatch(port->port.pin, true, status);
+ pwmSystem->writeZeroLatch(port->port.pin, false, status);
+}
+
+/**
+ * Set how how often the PWM signal is squelched, thus scaling the period.
+ *
+ * @param channel The PWM channel to configure.
+ * @param squelchMask The 2-bit mask of outputs to squelch.
+ */
+void setPWMPeriodScale(void* digital_port_pointer, uint32_t squelchMask, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyPWMChannel(port, status)) { return; }
+
+ if(port->port.pin < tPWM::kNumPeriodScaleHdrElements) {
+ pwmSystem->writePeriodScaleHdr(port->port.pin, squelchMask, status);
+ } else {
+ pwmSystem->writePeriodScaleMXP(port->port.pin - tPWM::kNumPeriodScaleHdrElements, squelchMask, status);
+ }
+}
+
+/**
+ * Allocate a DO PWM Generator.
+ * Allocate PWM generators so that they are not accidentally reused.
+ *
+ * @return PWM Generator refnum
+ */
+void* allocatePWM(int32_t *status) {
+ return (void*)DO_PWMGenerators->Allocate("DO_PWM");
+}
+
+/**
+ * Free the resource associated with a DO PWM generator.
+ *
+ * @param pwmGenerator The pwmGen to free that was allocated with AllocateDO_PWM()
+ */
+void freePWM(void* pwmGenerator, int32_t *status) {
+ uint32_t id = (uint32_t) pwmGenerator;
+ if (id == ~0ul) return;
+ DO_PWMGenerators->Free(id);
+}
+
+/**
+ * Change the frequency of the DO PWM generator.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is logarithmic.
+ *
+ * @param rate The frequency to output all digital output PWM signals.
+ */
+void setPWMRate(double rate, int32_t *status) {
+ // Currently rounding in the log rate domain... heavy weight toward picking a higher freq.
+ // TODO: Round in the linear rate domain.
+ uint8_t pwmPeriodPower = (uint8_t)(log(1.0 / (pwmSystem->readLoopTiming(status) * 0.25E-6 * rate))/log(2.0) + 0.5);
+ digitalSystem->writePWMPeriodPower(pwmPeriodPower, status);
+}
+
+
+/**
+ * Configure the duty-cycle of the PWM generator
+ *
+ * @param pwmGenerator The generator index reserved by AllocateDO_PWM()
+ * @param dutyCycle The percent duty cycle to output [0..1].
+ */
+void setPWMDutyCycle(void* pwmGenerator, double dutyCycle, int32_t *status) {
+ uint32_t id = (uint32_t) pwmGenerator;
+ if (id == ~0ul) return;
+ if (dutyCycle > 1.0) dutyCycle = 1.0;
+ if (dutyCycle < 0.0) dutyCycle = 0.0;
+ float rawDutyCycle = 256.0 * dutyCycle;
+ if (rawDutyCycle > 255.5) rawDutyCycle = 255.5;
+ {
+ std::lock_guard<priority_recursive_mutex> sync(digitalPwmMutex);
+ uint8_t pwmPeriodPower = digitalSystem->readPWMPeriodPower(status);
+ if (pwmPeriodPower < 4) {
+ // The resolution of the duty cycle drops close to the highest frequencies.
+ rawDutyCycle = rawDutyCycle / pow(2.0, 4 - pwmPeriodPower);
+ }
+ if(id < 4)
+ digitalSystem->writePWMDutyCycleA(id, (uint8_t)rawDutyCycle, status);
+ else
+ digitalSystem->writePWMDutyCycleB(id - 4, (uint8_t)rawDutyCycle, status);
+ }
+}
+
+/**
+ * Configure which DO channel the PWM signal is output on
+ *
+ * @param pwmGenerator The generator index reserved by AllocateDO_PWM()
+ * @param channel The Digital Output channel to output on
+ */
+void setPWMOutputChannel(void* pwmGenerator, uint32_t pin, int32_t *status) {
+ uint32_t id = (uint32_t) pwmGenerator;
+ if (id > 5) return;
+ digitalSystem->writePWMOutputSelect(id, pin, status);
+}
+
+/**
+ * Set the state of a relay.
+ * Set the state of a relay output to be forward. Relays have two outputs and each is
+ * independently set to 0v or 12v.
+ */
+void setRelayForward(void* digital_port_pointer, bool on, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyRelayChannel(port, status)) {
+ return;
+ }
+
+ {
+ std::lock_guard<priority_recursive_mutex> sync(digitalRelayMutex);
+ uint8_t forwardRelays = relaySystem->readValue_Forward(status);
+ if (on)
+ forwardRelays |= 1 << port->port.pin;
+ else
+ forwardRelays &= ~(1 << port->port.pin);
+ relaySystem->writeValue_Forward(forwardRelays, status);
+ }
+}
+
+/**
+ * Set the state of a relay.
+ * Set the state of a relay output to be reverse. Relays have two outputs and each is
+ * independently set to 0v or 12v.
+ */
+void setRelayReverse(void* digital_port_pointer, bool on, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyRelayChannel(port, status)) {
+ return;
+ }
+
+ {
+ std::lock_guard<priority_recursive_mutex> sync(digitalRelayMutex);
+ uint8_t reverseRelays = relaySystem->readValue_Reverse(status);
+ if (on)
+ reverseRelays |= 1 << port->port.pin;
+ else
+ reverseRelays &= ~(1 << port->port.pin);
+ relaySystem->writeValue_Reverse(reverseRelays, status);
+ }
+}
+
+/**
+ * Get the current state of the forward relay channel
+ */
+bool getRelayForward(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyRelayChannel(port, status)) { return false; }
+
+ uint8_t forwardRelays = relaySystem->readValue_Forward(status);
+ return (forwardRelays & (1 << port->port.pin)) != 0;
+}
+
+/**
+ * Get the current state of the reverse relay channel
+ */
+bool getRelayReverse(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyRelayChannel(port, status)) { return false; }
+
+ uint8_t reverseRelays = relaySystem->readValue_Reverse(status);
+ return (reverseRelays & (1 << port->port.pin)) != 0;
+}
+
+/**
+ * Allocate Digital I/O channels.
+ * Allocate channels so that they are not accidently reused. Also the direction is set at the
+ * time of the allocation.
+ *
+ * @param channel The Digital I/O channel
+ * @param input If true open as input; if false open as output
+ * @return Was successfully allocated
+ */
+bool allocateDIO(void* digital_port_pointer, bool input, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ char buf[64];
+ snprintf(buf, 64, "DIO %d", port->port.pin);
+ if (DIOChannels->Allocate(port->port.pin, buf) == ~0ul) {
+ *status = RESOURCE_IS_ALLOCATED;
+ return false;
+ }
+
+ {
+ std::lock_guard<priority_recursive_mutex> sync(digitalDIOMutex);
+
+ tDIO::tOutputEnable outputEnable = digitalSystem->readOutputEnable(status);
+
+ if(port->port.pin < kNumHeaders) {
+ uint32_t bitToSet = 1 << port->port.pin;
+ if (input) {
+ outputEnable.Headers = outputEnable.Headers & (~bitToSet); // clear the bit for read
+ } else {
+ outputEnable.Headers = outputEnable.Headers | bitToSet; // set the bit for write
+ }
+ } else {
+ uint32_t bitToSet = 1 << remapMXPChannel(port->port.pin);
+
+ // Disable special functions on this pin
+ short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+ digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status);
+
+ if (input) {
+ outputEnable.MXP = outputEnable.MXP & (~bitToSet); // clear the bit for read
+ } else {
+ outputEnable.MXP = outputEnable.MXP | bitToSet; // set the bit for write
+ }
+ }
+
+ digitalSystem->writeOutputEnable(outputEnable, status);
+ }
+ return true;
+}
+
+bool allocatePWMChannel(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!verifyPWMChannel(port, status)) { return false; }
+
+ char buf[64];
+ snprintf(buf, 64, "PWM %d", port->port.pin);
+ if (PWMChannels->Allocate(port->port.pin, buf) == ~0ul) {
+ *status = RESOURCE_IS_ALLOCATED;
+ return false;
+ }
+
+ if (port->port.pin > tPWM::kNumHdrRegisters-1) {
+ snprintf(buf, 64, "PWM %d and DIO %d", port->port.pin, remapMXPPWMChannel(port->port.pin) + 10);
+ if (DIOChannels->Allocate(remapMXPPWMChannel(port->port.pin) + 10, buf) == ~0ul) return false;
+ uint32_t bitToSet = 1 << remapMXPPWMChannel(port->port.pin);
+ short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+ digitalSystem->writeEnableMXPSpecialFunction(specialFunctions | bitToSet, status);
+ }
+ return true;
+}
+
+void freePWMChannel(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!port) return;
+ if (!verifyPWMChannel(port, status)) { return; }
+
+ PWMChannels->Free(port->port.pin);
+ if(port->port.pin > tPWM::kNumHdrRegisters-1) {
+ DIOChannels->Free(remapMXPPWMChannel(port->port.pin) + 10);
+ uint32_t bitToUnset = 1 << remapMXPPWMChannel(port->port.pin);
+ short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+ digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToUnset, status);
+ }
+}
+
+/**
+ * Free the resource associated with a digital I/O channel.
+ *
+ * @param channel The Digital I/O channel to free
+ */
+void freeDIO(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (!port) return;
+ DIOChannels->Free(port->port.pin);
+}
+
+/**
+ * Write a digital I/O bit to the FPGA.
+ * Set a single value on a digital I/O channel.
+ *
+ * @param channel The Digital I/O channel
+ * @param value The state to set the digital channel (if it is configured as an output)
+ */
+void setDIO(void* digital_port_pointer, short value, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ if (value != 0 && value != 1) {
+ if (value != 0)
+ value = 1;
+ }
+ {
+ std::lock_guard<priority_recursive_mutex> sync(digitalDIOMutex);
+ tDIO::tDO currentDIO = digitalSystem->readDO(status);
+
+ if(port->port.pin < kNumHeaders) {
+ if(value == 0) {
+ currentDIO.Headers = currentDIO.Headers & ~(1 << port->port.pin);
+ } else if (value == 1) {
+ currentDIO.Headers = currentDIO.Headers | (1 << port->port.pin);
+ }
+ } else {
+ if(value == 0) {
+ currentDIO.MXP = currentDIO.MXP & ~(1 << remapMXPChannel(port->port.pin));
+ } else if (value == 1) {
+ currentDIO.MXP = currentDIO.MXP | (1 << remapMXPChannel(port->port.pin));
+ }
+
+ uint32_t bitToSet = 1 << remapMXPChannel(port->port.pin);
+ short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+ digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status);
+ }
+ digitalSystem->writeDO(currentDIO, status);
+ }
+}
+
+/**
+ * Read a digital I/O bit from the FPGA.
+ * Get a single value from a digital I/O channel.
+ *
+ * @param channel The digital I/O channel
+ * @return The state of the specified channel
+ */
+bool getDIO(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ tDIO::tDI currentDIO = digitalSystem->readDI(status);
+ //Shift 00000001 over channel-1 places.
+ //AND it against the currentDIO
+ //if it == 0, then return false
+ //else return true
+
+ if(port->port.pin < kNumHeaders) {
+ return ((currentDIO.Headers >> port->port.pin) & 1) != 0;
+ } else {
+ // Disable special functions
+ uint32_t bitToSet = 1 << remapMXPChannel(port->port.pin);
+ short specialFunctions = digitalSystem->readEnableMXPSpecialFunction(status);
+ digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet, status);
+
+ return ((currentDIO.MXP >> remapMXPChannel(port->port.pin)) & 1) != 0;
+ }
+}
+
+/**
+ * Read the direction of a the Digital I/O lines
+ * A 1 bit means output and a 0 bit means input.
+ *
+ * @param channel The digital I/O channel
+ * @return The direction of the specified channel
+ */
+bool getDIODirection(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ tDIO::tOutputEnable currentOutputEnable = digitalSystem->readOutputEnable(status);
+ //Shift 00000001 over port->port.pin-1 places.
+ //AND it against the currentOutputEnable
+ //if it == 0, then return false
+ //else return true
+
+ if(port->port.pin < kNumHeaders) {
+ return ((currentOutputEnable.Headers >> port->port.pin) & 1) != 0;
+ } else {
+ return ((currentOutputEnable.MXP >> remapMXPChannel(port->port.pin)) & 1) != 0;
+ }
+}
+
+/**
+ * Generate a single pulse.
+ * Write a pulse to the specified digital output channel. There can only be a single pulse going at any time.
+ *
+ * @param channel The Digital Output channel that the pulse should be output on
+ * @param pulseLength The active length of the pulse (in seconds)
+ */
+void pulse(void* digital_port_pointer, double pulseLength, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ tDIO::tPulse pulse;
+
+ if(port->port.pin < kNumHeaders) {
+ pulse.Headers = 1 << port->port.pin;
+ } else {
+ pulse.MXP = 1 << remapMXPChannel(port->port.pin);
+ }
+
+ digitalSystem->writePulseLength((uint8_t)(1.0e9 * pulseLength / (pwmSystem->readLoopTiming(status) * 25)), status);
+ digitalSystem->writePulse(pulse, status);
+}
+
+/**
+ * Check a DIO line to see if it is currently generating a pulse.
+ *
+ * @return A pulse is in progress
+ */
+bool isPulsing(void* digital_port_pointer, int32_t *status) {
+ DigitalPort* port = (DigitalPort*) digital_port_pointer;
+ tDIO::tPulse pulseRegister = digitalSystem->readPulse(status);
+
+ if(port->port.pin < kNumHeaders) {
+ return (pulseRegister.Headers & (1 << port->port.pin)) != 0;
+ } else {
+ return (pulseRegister.MXP & (1 << remapMXPChannel(port->port.pin))) != 0;
+ }
+}
+
+/**
+ * Check if any DIO line is currently generating a pulse.
+ *
+ * @return A pulse on some line is in progress
+ */
+bool isAnyPulsing(int32_t *status) {
+ tDIO::tPulse pulseRegister = digitalSystem->readPulse(status);
+ return pulseRegister.Headers != 0 && pulseRegister.MXP != 0;
+}
+
+/**
+ * Write the filter index from the FPGA.
+ * Set the filter index used to filter out short pulses.
+ *
+ * @param digital_port_pointer The digital I/O channel
+ * @param filter_index The filter index. Must be in the range 0 - 3,
+ * where 0 means "none" and 1 - 3 means filter # filter_index - 1.
+ */
+void setFilterSelect(void* digital_port_pointer, int filter_index,
+ int32_t* status) {
+ DigitalPort* port = (DigitalPort*)digital_port_pointer;
+
+ std::lock_guard<priority_recursive_mutex> sync(digitalDIOMutex);
+ if (port->port.pin < kNumHeaders) {
+ digitalSystem->writeFilterSelectHdr(port->port.pin, filter_index, status);
+ }
+ else {
+ digitalSystem->writeFilterSelectMXP(remapMXPChannel(port->port.pin),
+ filter_index, status);
+ }
+}
+
+/**
+ * Read the filter index from the FPGA.
+ * Get the filter index used to filter out short pulses.
+ *
+ * @param digital_port_pointer The digital I/O channel
+ * @return filter_index The filter index. Must be in the range 0 - 3,
+ * where 0 means "none" and 1 - 3 means filter # filter_index - 1.
+ */
+int getFilterSelect(void* digital_port_pointer, int32_t* status) {
+ DigitalPort* port = (DigitalPort*)digital_port_pointer;
+
+ std::lock_guard<priority_recursive_mutex> sync(digitalDIOMutex);
+ if (port->port.pin < kNumHeaders) {
+ return digitalSystem->readFilterSelectHdr(port->port.pin, status);
+ }
+ else {
+ return digitalSystem->readFilterSelectMXP(remapMXPChannel(port->port.pin),
+ status);
+ }
+}
+
+/**
+ * Set the filter period for the specified filter index.
+ *
+ * Set the filter period in FPGA cycles. Even though there are 2 different
+ * filter index domains (MXP vs HDR), ignore that distinction for now since it
+ * compilicates the interface. That can be changed later.
+ *
+ * @param filter_index The filter index, 0 - 2.
+ * @param value The number of cycles that the signal must not transition to be
+ * counted as a transition.
+ */
+void setFilterPeriod(int filter_index, uint32_t value, int32_t* status) {
+ std::lock_guard<priority_recursive_mutex> sync(digitalDIOMutex);
+ digitalSystem->writeFilterPeriodHdr(filter_index, value, status);
+ if (*status == 0) {
+ digitalSystem->writeFilterPeriodMXP(filter_index, value, status);
+ }
+}
+
+/**
+ * Get the filter period for the specified filter index.
+ *
+ * Get the filter period in FPGA cycles. Even though there are 2 different
+ * filter index domains (MXP vs HDR), ignore that distinction for now since it
+ * compilicates the interface. Set status to NiFpga_Status_SoftwareFault if the
+ * filter values miss-match.
+ *
+ * @param filter_index The filter index, 0 - 2.
+ * @param value The number of cycles that the signal must not transition to be
+ * counted as a transition.
+ */
+uint32_t getFilterPeriod(int filter_index, int32_t* status) {
+ uint32_t hdr_period = 0;
+ uint32_t mxp_period = 0;
+ {
+ std::lock_guard<priority_recursive_mutex> sync(digitalDIOMutex);
+ hdr_period = digitalSystem->readFilterPeriodHdr(filter_index, status);
+ if (*status == 0) {
+ mxp_period = digitalSystem->readFilterPeriodMXP(filter_index, status);
+ }
+ }
+ if (hdr_period != mxp_period) {
+ *status = NiFpga_Status_SoftwareFault;
+ return -1;
+ }
+ return hdr_period;
+}
+
+struct counter_t {
+ tCounter* counter;
+ uint32_t index;
+};
+typedef struct counter_t Counter;
+
+static hal::Resource *counters = NULL;
+
+void* initializeCounter(Mode mode, uint32_t *index, int32_t *status) {
+ hal::Resource::CreateResourceObject(&counters, tCounter::kNumSystems);
+ *index = counters->Allocate("Counter");
+ if (*index == ~0ul) {
+ *status = NO_AVAILABLE_RESOURCES;
+ return NULL;
+ }
+ Counter* counter = new Counter();
+ counter->counter = tCounter::create(*index, status);
+ counter->counter->writeConfig_Mode(mode, status);
+ counter->counter->writeTimerConfig_AverageSize(1, status);
+ counter->index = *index;
+ return counter;
+}
+
+void freeCounter(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ if (!counter) return;
+ delete counter->counter;
+ counters->Free(counter->index);
+}
+
+void setCounterAverageSize(void* counter_pointer, int32_t size, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeTimerConfig_AverageSize(size, status);
+}
+
+/**
+ * remap the digital source pin and set the module.
+ * If it's an analog trigger, determine the module from the high order routing channel
+ * else do normal digital input remapping based on pin number (MXP)
+ */
+void remapDigitalSource(bool analogTrigger, uint32_t &pin, uint8_t &module) {
+ if (analogTrigger) {
+ module = pin >> 4;
+ } else {
+ if(pin >= kNumHeaders) {
+ pin = remapMXPChannel(pin);
+ module = 1;
+ } else {
+ module = 0;
+ }
+ }
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ * Set the up counting DigitalSource.
+ */
+void setCounterUpSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+
+ uint8_t module;
+
+ remapDigitalSource(analogTrigger, pin, module);
+
+ counter->counter->writeConfig_UpSource_Module(module, status);
+ counter->counter->writeConfig_UpSource_Channel(pin, status);
+ counter->counter->writeConfig_UpSource_AnalogTrigger(analogTrigger, status);
+
+ if(counter->counter->readConfig_Mode(status) == kTwoPulse ||
+ counter->counter->readConfig_Mode(status) == kExternalDirection) {
+ setCounterUpSourceEdge(counter_pointer, true, false, status);
+ }
+ counter->counter->strobeReset(status);
+}
+
+/**
+ * Set the edge sensitivity on an up counting source.
+ * Set the up source to either detect rising edges or falling edges.
+ */
+void setCounterUpSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_UpRisingEdge(risingEdge, status);
+ counter->counter->writeConfig_UpFallingEdge(fallingEdge, status);
+}
+
+/**
+ * Disable the up counting source to the counter.
+ */
+void clearCounterUpSource(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_UpFallingEdge(false, status);
+ counter->counter->writeConfig_UpRisingEdge(false, status);
+ // Index 0 of digital is always 0.
+ counter->counter->writeConfig_UpSource_Channel(0, status);
+ counter->counter->writeConfig_UpSource_AnalogTrigger(false, status);
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ * Set the down counting DigitalSource.
+ */
+void setCounterDownSource(void* counter_pointer, uint32_t pin, bool analogTrigger, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ unsigned char mode = counter->counter->readConfig_Mode(status);
+ if (mode != kTwoPulse && mode != kExternalDirection) {
+ // TODO: wpi_setWPIErrorWithContext(ParameterOutOfRange, "Counter only supports DownSource in TwoPulse and ExternalDirection modes.");
+ *status = PARAMETER_OUT_OF_RANGE;
+ return;
+ }
+
+ uint8_t module;
+
+ remapDigitalSource(analogTrigger, pin, module);
+
+ counter->counter->writeConfig_DownSource_Module(module, status);
+ counter->counter->writeConfig_DownSource_Channel(pin, status);
+ counter->counter->writeConfig_DownSource_AnalogTrigger(analogTrigger, status);
+
+ setCounterDownSourceEdge(counter_pointer, true, false, status);
+ counter->counter->strobeReset(status);
+}
+
+/**
+ * Set the edge sensitivity on a down counting source.
+ * Set the down source to either detect rising edges or falling edges.
+ */
+void setCounterDownSourceEdge(void* counter_pointer, bool risingEdge, bool fallingEdge, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_DownRisingEdge(risingEdge, status);
+ counter->counter->writeConfig_DownFallingEdge(fallingEdge, status);
+}
+
+/**
+ * Disable the down counting source to the counter.
+ */
+void clearCounterDownSource(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_DownFallingEdge(false, status);
+ counter->counter->writeConfig_DownRisingEdge(false, status);
+ // Index 0 of digital is always 0.
+ counter->counter->writeConfig_DownSource_Channel(0, status);
+ counter->counter->writeConfig_DownSource_AnalogTrigger(false, status);
+}
+
+/**
+ * Set standard up / down counting mode on this counter.
+ * Up and down counts are sourced independently from two inputs.
+ */
+void setCounterUpDownMode(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_Mode(kTwoPulse, status);
+}
+
+/**
+ * Set external direction mode on this counter.
+ * Counts are sourced on the Up counter input.
+ * The Down counter input represents the direction to count.
+ */
+void setCounterExternalDirectionMode(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_Mode(kExternalDirection, status);
+}
+
+/**
+ * Set Semi-period mode on this counter.
+ * Counts up on both rising and falling edges.
+ */
+void setCounterSemiPeriodMode(void* counter_pointer, bool highSemiPeriod, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_Mode(kSemiperiod, status);
+ counter->counter->writeConfig_UpRisingEdge(highSemiPeriod, status);
+ setCounterUpdateWhenEmpty(counter_pointer, false, status);
+}
+
+/**
+ * Configure the counter to count in up or down based on the length of the input pulse.
+ * This mode is most useful for direction sensitive gear tooth sensors.
+ * @param threshold The pulse length beyond which the counter counts the opposite direction. Units are seconds.
+ */
+void setCounterPulseLengthMode(void* counter_pointer, double threshold, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeConfig_Mode(kPulseLength, status);
+ counter->counter->writeConfig_PulseLengthThreshold((uint32_t)(threshold * 1.0e6) * kSystemClockTicksPerMicrosecond, status);
+}
+
+/**
+ * Get the Samples to Average which specifies the number of samples of the timer to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+ */
+int32_t getCounterSamplesToAverage(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ return counter->counter->readTimerConfig_AverageSize(status);
+}
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void setCounterSamplesToAverage(void* counter_pointer, int samplesToAverage, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ if (samplesToAverage < 1 || samplesToAverage > 127) {
+ *status = PARAMETER_OUT_OF_RANGE;
+ }
+ counter->counter->writeTimerConfig_AverageSize(samplesToAverage, status);
+}
+
+/**
+ * Reset the Counter to zero.
+ * Set the counter value to zero. This doesn't effect the running state of the counter, just sets
+ * the current value to zero.
+ */
+void resetCounter(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->strobeReset(status);
+}
+
+/**
+ * Read the current counter value.
+ * Read the value at this instant. It may still be running, so it reflects the current value. Next
+ * time it is read, it might have a different value.
+ */
+int32_t getCounter(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ int32_t value = counter->counter->readOutput_Value(status);
+ return value;
+}
+
+/*
+ * Get the Period of the most recent count.
+ * Returns the time interval of the most recent count. This can be used for velocity calculations
+ * to determine shaft speed.
+ * @returns The period of the last two pulses in units of seconds.
+ */
+double getCounterPeriod(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ tCounter::tTimerOutput output = counter->counter->readTimerOutput(status);
+ double period;
+ if (output.Stalled) {
+ // Return infinity
+ double zero = 0.0;
+ period = 1.0 / zero;
+ } else {
+ // output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits)
+ period = (double)(output.Period << 1) / (double)output.Count;
+ }
+ return period * 2.5e-8; // result * timebase (currently 40ns)
+}
+
+/**
+ * Set the maximum period where the device is still considered "moving".
+ * Sets the maximum period where the device is considered moving. This value is used to determine
+ * the "stopped" state of the counter using the GetStopped method.
+ * @param maxPeriod The maximum period where the counted device is considered moving in
+ * seconds.
+ */
+void setCounterMaxPeriod(void* counter_pointer, double maxPeriod, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeTimerConfig_StallPeriod((uint32_t)(maxPeriod * 4.0e8), status);
+}
+
+/**
+ * Select whether you want to continue updating the event timer output when there are no samples captured.
+ * The output of the event timer has a buffer of periods that are averaged and posted to
+ * a register on the FPGA. When the timer detects that the event source has stopped
+ * (based on the MaxPeriod) the buffer of samples to be averaged is emptied. If you
+ * enable the update when empty, you will be notified of the stopped source and the event
+ * time will report 0 samples. If you disable update when empty, the most recent average
+ * will remain on the output until a new sample is acquired. You will never see 0 samples
+ * output (except when there have been no events since an FPGA reset) and you will likely not
+ * see the stopped bit become true (since it is updated at the end of an average and there are
+ * no samples to average).
+ */
+void setCounterUpdateWhenEmpty(void* counter_pointer, bool enabled, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ counter->counter->writeTimerConfig_UpdateWhenEmpty(enabled, status);
+}
+
+/**
+ * Determine if the clock is stopped.
+ * Determine if the clocked input is stopped based on the MaxPeriod value set using the
+ * SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the device (and counter) are
+ * assumed to be stopped and it returns true.
+ * @return Returns true if the most recent counter period exceeds the MaxPeriod value set by
+ * SetMaxPeriod.
+ */
+bool getCounterStopped(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ return counter->counter->readTimerOutput_Stalled(status);
+}
+
+/**
+ * The last direction the counter value changed.
+ * @return The last direction the counter value changed.
+ */
+bool getCounterDirection(void* counter_pointer, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ bool value = counter->counter->readOutput_Direction(status);
+ return value;
+}
+
+/**
+ * Set the Counter to return reversed sensing on the direction.
+ * This allows counters to change the direction they are counting in the case of 1X and 2X
+ * quadrature encoding only. Any other counter mode isn't supported.
+ * @param reverseDirection true if the value counted should be negated.
+ */
+void setCounterReverseDirection(void* counter_pointer, bool reverseDirection, int32_t *status) {
+ Counter* counter = (Counter*) counter_pointer;
+ if (counter->counter->readConfig_Mode(status) == kExternalDirection) {
+ if (reverseDirection)
+ setCounterDownSourceEdge(counter_pointer, true, true, status);
+ else
+ setCounterDownSourceEdge(counter_pointer, false, true, status);
+ }
+}
+
+struct encoder_t {
+ tEncoder* encoder;
+ uint32_t index;
+};
+typedef struct encoder_t Encoder;
+
+static const double DECODING_SCALING_FACTOR = 0.25;
+static hal::Resource *quadEncoders = NULL;
+
+void* initializeEncoder(uint8_t port_a_module, uint32_t port_a_pin, bool port_a_analog_trigger,
+ uint8_t port_b_module, uint32_t port_b_pin, bool port_b_analog_trigger,
+ bool reverseDirection, int32_t *index, int32_t *status) {
+
+ // Initialize encoder structure
+ Encoder* encoder = new Encoder();
+
+ remapDigitalSource(port_a_analog_trigger, port_a_pin, port_a_module);
+ remapDigitalSource(port_b_analog_trigger, port_b_pin, port_b_module);
+
+ hal::Resource::CreateResourceObject(&quadEncoders, tEncoder::kNumSystems);
+ encoder->index = quadEncoders->Allocate("4X Encoder");
+ *index = encoder->index;
+ // TODO: if (index == ~0ul) { CloneError(quadEncoders); return; }
+ encoder->encoder = tEncoder::create(encoder->index, status);
+ encoder->encoder->writeConfig_ASource_Module(port_a_module, status);
+ encoder->encoder->writeConfig_ASource_Channel(port_a_pin, status);
+ encoder->encoder->writeConfig_ASource_AnalogTrigger(port_a_analog_trigger, status);
+ encoder->encoder->writeConfig_BSource_Module(port_b_module, status);
+ encoder->encoder->writeConfig_BSource_Channel(port_b_pin, status);
+ encoder->encoder->writeConfig_BSource_AnalogTrigger(port_b_analog_trigger, status);
+ encoder->encoder->strobeReset(status);
+ encoder->encoder->writeConfig_Reverse(reverseDirection, status);
+ encoder->encoder->writeTimerConfig_AverageSize(4, status);
+
+ return encoder;
+}
+
+void freeEncoder(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ if (!encoder) return;
+ quadEncoders->Free(encoder->index);
+ delete encoder->encoder;
+}
+
+/**
+ * Reset the Encoder distance to zero.
+ * Resets the current count to zero on the encoder.
+ */
+void resetEncoder(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ encoder->encoder->strobeReset(status);
+}
+
+/**
+ * Gets the raw value from the encoder.
+ * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
+ * factor.
+ * @return Current raw count from the encoder
+ */
+int32_t getEncoder(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ return encoder->encoder->readOutput_Value(status);
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compenstates for the decoding type.
+ *
+ * @deprecated Use GetRate() in favor of this method. This returns unscaled periods and GetRate() scales using value from SetDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ */
+double getEncoderPeriod(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ tEncoder::tTimerOutput output = encoder->encoder->readTimerOutput(status);
+ double value;
+ if (output.Stalled) {
+ // Return infinity
+ double zero = 0.0;
+ value = 1.0 / zero;
+ } else {
+ // output.Period is a fixed point number that counts by 2 (24 bits, 25 integer bits)
+ value = (double)(output.Period << 1) / (double)output.Count;
+ }
+ double measuredPeriod = value * 2.5e-8;
+ return measuredPeriod / DECODING_SCALING_FACTOR;
+}
+
+/**
+ * Sets the maximum period for stopped detection.
+ * Sets the value that represents the maximum period of the Encoder before it will assume
+ * that the attached device is stopped. This timeout allows users to determine if the wheels or
+ * other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetMinRate() in favor of this method. This takes unscaled periods and SetMinRate() scales using value from SetDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before the FPGA will
+ * report the device stopped. This is expressed in seconds.
+ */
+void setEncoderMaxPeriod(void* encoder_pointer, double maxPeriod, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ encoder->encoder->writeTimerConfig_StallPeriod((uint32_t)(maxPeriod * 4.0e8 * DECODING_SCALING_FACTOR), status);
+}
+
+/**
+ * Determine if the encoder is stopped.
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder is considered
+ * stopped and false if it is still moving. A stopped encoder is one where the most recent pulse
+ * width exceeds the MaxPeriod.
+ * @return True if the encoder is considered stopped.
+ */
+bool getEncoderStopped(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ return encoder->encoder->readTimerOutput_Stalled(status) != 0;
+}
+
+/**
+ * The last direction the encoder value changed.
+ * @return The last direction the encoder value changed.
+ */
+bool getEncoderDirection(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ return encoder->encoder->readOutput_Direction(status);
+}
+
+/**
+ * Set the direction sensing for this encoder.
+ * This sets the direction sensing on the encoder so that it could count in the correct
+ * software direction regardless of the mounting.
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void setEncoderReverseDirection(void* encoder_pointer, bool reverseDirection, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ encoder->encoder->writeConfig_Reverse(reverseDirection, status);
+}
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void setEncoderSamplesToAverage(void* encoder_pointer, uint32_t samplesToAverage, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ if (samplesToAverage < 1 || samplesToAverage > 127) {
+ *status = PARAMETER_OUT_OF_RANGE;
+ }
+ encoder->encoder->writeTimerConfig_AverageSize(samplesToAverage, status);
+}
+
+/**
+ * Get the Samples to Average which specifies the number of samples of the timer to
+ * average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+ */
+uint32_t getEncoderSamplesToAverage(void* encoder_pointer, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ return encoder->encoder->readTimerConfig_AverageSize(status);
+}
+
+/**
+ * Set an index source for an encoder, which is an input that resets the
+ * encoder's count.
+ */
+void setEncoderIndexSource(void *encoder_pointer, uint32_t pin, bool analogTrigger, bool activeHigh,
+ bool edgeSensitive, int32_t *status) {
+ Encoder* encoder = (Encoder*) encoder_pointer;
+ encoder->encoder->writeConfig_IndexSource_Channel((unsigned char)pin, status);
+ encoder->encoder->writeConfig_IndexSource_Module((unsigned char)0, status);
+ encoder->encoder->writeConfig_IndexSource_AnalogTrigger(analogTrigger, status);
+ encoder->encoder->writeConfig_IndexActiveHigh(activeHigh, status);
+ encoder->encoder->writeConfig_IndexEdgeSensitive(edgeSensitive, status);
+}
+
+/**
+ * Get the loop timing of the PWM system
+ *
+ * @return The loop time
+ */
+uint16_t getLoopTiming(int32_t *status) {
+ return pwmSystem->readLoopTiming(status);
+}
+
+/*
+ * Initialize the spi port. Opens the port if necessary and saves the handle.
+ * If opening the MXP port, also sets up the pin functions appropriately
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiInitialize(uint8_t port, int32_t *status) {
+ if(spiSystem == NULL)
+ spiSystem = tSPI::create(status);
+ if(spiGetHandle(port) !=0 ) return;
+ switch(port){
+ case 0:
+ spiSetHandle(0, spilib_open("/dev/spidev0.0"));
+ break;
+ case 1:
+ spiSetHandle(1, spilib_open("/dev/spidev0.1"));
+ break;
+ case 2:
+ spiSetHandle(2, spilib_open("/dev/spidev0.2"));
+ break;
+ case 3:
+ spiSetHandle(3, spilib_open("/dev/spidev0.3"));
+ break;
+ case 4:
+ initializeDigital(status);
+ if(!allocateDIO(getPort(14), false, status)){printf("Failed to allocate DIO 14\n"); return;}
+ if(!allocateDIO(getPort(15), false, status)) {printf("Failed to allocate DIO 15\n"); return;}
+ if(!allocateDIO(getPort(16), true, status)) {printf("Failed to allocate DIO 16\n"); return;}
+ if(!allocateDIO(getPort(17), false, status)) {printf("Failed to allocate DIO 17\n"); return;}
+ digitalSystem->writeEnableMXPSpecialFunction(digitalSystem->readEnableMXPSpecialFunction(status)|0x00F0, status);
+ spiSetHandle(4, spilib_open("/dev/spidev1.0"));
+ break;
+ default:
+ break;
+ }
+ return;
+}
+
+/**
+ * Generic transaction.
+ *
+ * This is a lower-level interface to the spi hardware giving you more control over each transaction.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param dataToSend Buffer of data to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param size Number of bytes to transfer. [0..7]
+ * @return Number of bytes transferred, -1 for error
+ */
+int32_t spiTransaction(uint8_t port, uint8_t *dataToSend, uint8_t *dataReceived, uint8_t size)
+{
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ return spilib_writeread(spiGetHandle(port), (const char*) dataToSend, (char*) dataReceived, (int32_t) size);
+}
+
+/**
+ * Execute a write transaction with the device.
+ *
+ * Write to a device and wait until the transaction is complete.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param datToSend The data to write to the register on the device.
+ * @param sendSize The number of bytes to be written
+ * @return The number of bytes written. -1 for an error
+ */
+int32_t spiWrite(uint8_t port, uint8_t* dataToSend, uint8_t sendSize)
+{
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ return spilib_write(spiGetHandle(port), (const char*) dataToSend, (int32_t) sendSize);
+}
+
+/**
+ * Execute a read from the device.
+ *
+ * This methdod does not write any data out to the device
+ * Most spi devices will require a register address to be written before
+ * they begin returning data
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param buffer A pointer to the array of bytes to store the data read from the device.
+ * @param count The number of bytes to read in the transaction. [1..7]
+ * @return Number of bytes read. -1 for error.
+ */
+int32_t spiRead(uint8_t port, uint8_t *buffer, uint8_t count)
+{
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ return spilib_read(spiGetHandle(port), (char*) buffer, (int32_t) count);
+}
+
+/**
+ * Close the SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiClose(uint8_t port) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ if (spiAccumulators[port]) {
+ int32_t status = 0;
+ spiFreeAccumulator(port, &status);
+ }
+ spilib_close(spiGetHandle(port));
+ spiSetHandle(port, 0);
+ return;
+}
+
+/**
+ * Set the clock speed for the SPI bus.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param speed The speed in Hz (0-1MHz)
+ */
+void spiSetSpeed(uint8_t port, uint32_t speed) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ spilib_setspeed(spiGetHandle(port), speed);
+}
+
+/**
+ * Set the SPI options
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @param msb_first True to write the MSB first, False for LSB first
+ * @param sample_on_trailing True to sample on the trailing edge, False to sample on the leading edge
+ * @param clk_idle_high True to set the clock to active low, False to set the clock active high
+ */
+void spiSetOpts(uint8_t port, int msb_first, int sample_on_trailing, int clk_idle_high) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ spilib_setopts(spiGetHandle(port), msb_first, sample_on_trailing, clk_idle_high);
+}
+
+/**
+ * Set the CS Active high for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiSetChipSelectActiveHigh(uint8_t port, int32_t *status){
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ if(port < 4)
+ {
+ spiSystem->writeChipSelectActiveHigh_Hdr(spiSystem->readChipSelectActiveHigh_Hdr(status) | (1<<port), status);
+ }
+ else
+ {
+ spiSystem->writeChipSelectActiveHigh_MXP(1, status);
+ }
+}
+
+/**
+ * Set the CS Active low for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void spiSetChipSelectActiveLow(uint8_t port, int32_t *status){
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ if(port < 4)
+ {
+ spiSystem->writeChipSelectActiveHigh_Hdr(spiSystem->readChipSelectActiveHigh_Hdr(status) & ~(1<<port), status);
+ }
+ else
+ {
+ spiSystem->writeChipSelectActiveHigh_MXP(0, status);
+ }
+}
+
+/**
+ * Get the stored handle for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @return The stored handle for the SPI port. 0 represents no stored handle.
+ */
+int32_t spiGetHandle(uint8_t port){
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ switch(port){
+ case 0:
+ return m_spiCS0Handle;
+ case 1:
+ return m_spiCS1Handle;
+ case 2:
+ return m_spiCS2Handle;
+ case 3:
+ return m_spiCS3Handle;
+ case 4:
+ return m_spiMXPHandle;
+ default:
+ return 0;
+ }
+}
+
+/**
+ * Set the stored handle for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP.
+ * @param handle The value of the handle for the port.
+ */
+void spiSetHandle(uint8_t port, int32_t handle){
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ switch(port){
+ case 0:
+ m_spiCS0Handle = handle;
+ break;
+ case 1:
+ m_spiCS1Handle = handle;
+ break;
+ case 2:
+ m_spiCS2Handle = handle;
+ break;
+ case 3:
+ m_spiCS3Handle = handle;
+ break;
+ case 4:
+ m_spiMXPHandle = handle;
+ break;
+ default:
+ break;
+ }
+}
+
+/**
+ * Get the semaphore for a SPI port
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @return The semaphore for the SPI port.
+ */
+priority_recursive_mutex& spiGetSemaphore(uint8_t port) {
+ if(port < 4)
+ return spiOnboardSemaphore;
+ else
+ return spiMXPSemaphore;
+}
+
+static void spiAccumulatorProcess(uint32_t currentTime, void *param) {
+ SPIAccumulator* accum = (SPIAccumulator*)param;
+
+ // perform SPI transaction
+ uint8_t resp_b[4];
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(accum->port));
+ spilib_writeread(spiGetHandle(accum->port), (const char*) accum->cmd, (char*) resp_b, (int32_t) accum->xfer_size);
+
+ // convert from bytes
+ uint32_t resp = 0;
+ if (accum->big_endian) {
+ for (int i=0; i < accum->xfer_size; ++i) {
+ resp <<= 8;
+ resp |= resp_b[i] & 0xff;
+ }
+ } else {
+ for (int i = accum->xfer_size - 1; i >= 0; --i) {
+ resp <<= 8;
+ resp |= resp_b[i] & 0xff;
+ }
+ }
+
+ // process response
+ if ((resp & accum->valid_mask) == accum->valid_value) {
+ // valid sensor data; extract data field
+ int32_t data = (int32_t)(resp >> accum->data_shift);
+ data &= accum->data_max - 1;
+ // 2s complement conversion if signed MSB is set
+ if (accum->is_signed && (data & accum->data_msb_mask) != 0)
+ data -= accum->data_max;
+ // center offset
+ data -= accum->center;
+ // only accumulate if outside deadband
+ if (data < -accum->deadband || data > accum->deadband)
+ accum->value += data;
+ ++accum->count;
+ accum->last_value = data;
+ } else {
+ // no data from the sensor; just clear the last value
+ accum->last_value = 0;
+ }
+
+ // reschedule timer
+ accum->triggerTime += accum->period;
+ // handle timer slip
+ if (accum->triggerTime < currentTime)
+ accum->triggerTime = currentTime + accum->period;
+ int32_t status = 0;
+ updateNotifierAlarm(accum->notifier, accum->triggerTime, &status);
+}
+
+/**
+ * Initialize a SPI accumulator.
+ *
+ * @param port SPI port
+ * @param period Time between reads, in us
+ * @param cmd SPI command to send to request data
+ * @param xfer_size SPI transfer size, in bytes
+ * @param valid_mask Mask to apply to received data for validity checking
+ * @param valid_data After valid_mask is applied, required matching value for
+ * validity checking
+ * @param data_shift Bit shift to apply to received data to get actual data
+ * value
+ * @param data_size Size (in bits) of data field
+ * @param is_signed Is data field signed?
+ * @param big_endian Is device big endian?
+ */
+void spiInitAccumulator(uint8_t port, uint32_t period, uint32_t cmd,
+ uint8_t xfer_size, uint32_t valid_mask, uint32_t valid_value,
+ uint8_t data_shift, uint8_t data_size, bool is_signed,
+ bool big_endian, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ if (port > 4) return;
+ if (!spiAccumulators[port])
+ spiAccumulators[port] = new SPIAccumulator();
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (big_endian) {
+ for (int i = xfer_size - 1; i >= 0; --i) {
+ accum->cmd[i] = cmd & 0xff;
+ cmd >>= 8;
+ }
+ } else {
+ accum->cmd[0] = cmd & 0xff; cmd >>= 8;
+ accum->cmd[1] = cmd & 0xff; cmd >>= 8;
+ accum->cmd[2] = cmd & 0xff; cmd >>= 8;
+ accum->cmd[3] = cmd & 0xff;
+ }
+ accum->period = period;
+ accum->xfer_size = xfer_size;
+ accum->valid_mask = valid_mask;
+ accum->valid_value = valid_value;
+ accum->data_shift = data_shift;
+ accum->data_max = (1 << data_size);
+ accum->data_msb_mask = (1 << (data_size - 1));
+ accum->is_signed = is_signed;
+ accum->big_endian = big_endian;
+ if (!accum->notifier) {
+ accum->notifier = initializeNotifier(spiAccumulatorProcess, accum, status);
+ accum->triggerTime = getFPGATime(status) + period;
+ if (*status != 0) return;
+ updateNotifierAlarm(accum->notifier, accum->triggerTime, status);
+ }
+}
+
+/**
+ * Frees a SPI accumulator.
+ */
+void spiFreeAccumulator(uint8_t port, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ cleanNotifier(accum->notifier, status);
+ delete accum;
+ spiAccumulators[port] = nullptr;
+}
+
+/**
+ * Resets the accumulator to zero.
+ */
+void spiResetAccumulator(uint8_t port, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ accum->value = 0;
+ accum->count = 0;
+ accum->last_value = 0;
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each value before it is added to the accumulator. This
+ * is used for the center value of devices like gyros and accelerometers to make integration work
+ * and to take the device offset into account when integrating.
+ */
+void spiSetAccumulatorCenter(uint8_t port, int32_t center, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ accum->center = center;
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void spiSetAccumulatorDeadband(uint8_t port, int32_t deadband, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return;
+ }
+ accum->deadband = deadband;
+}
+
+/**
+ * Read the last value read by the accumulator engine.
+ */
+int32_t spiGetAccumulatorLastValue(uint8_t port, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return 0;
+ }
+ return accum->last_value;
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t spiGetAccumulatorValue(uint8_t port, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return 0;
+ }
+ return accum->value;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+uint32_t spiGetAccumulatorCount(uint8_t port, int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ return 0;
+ }
+ return accum->count;
+}
+
+/**
+ * Read the average of the accumulated value.
+ *
+ * @return The accumulated average value (value / count).
+ */
+double spiGetAccumulatorAverage(uint8_t port, int32_t *status) {
+ int64_t value;
+ uint32_t count;
+ spiGetAccumulatorOutput(port, &value, &count, status);
+ if (count == 0) return 0.0;
+ return ((double)value) / count;
+}
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count atomically.
+ * This can be used for averaging.
+ *
+ * @param value Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void spiGetAccumulatorOutput(uint8_t port, int64_t *value, uint32_t *count,
+ int32_t *status) {
+ std::lock_guard<priority_recursive_mutex> sync(spiGetSemaphore(port));
+ SPIAccumulator* accum = spiAccumulators[port];
+ if (!accum) {
+ *status = NULL_PARAMETER;
+ *value = 0;
+ *count = 0;
+ return;
+ }
+ *value = accum->value;
+ *count = accum->count;
+}
+
+/*
+ * Initialize the I2C port. Opens the port if necessary and saves the handle.
+ * If opening the MXP port, also sets up the pin functions appropriately
+ * @param port The port to open, 0 for the on-board, 1 for the MXP.
+ */
+void i2CInitialize(uint8_t port, int32_t *status) {
+ initializeDigital(status);
+
+ if(port > 1)
+ {
+ //Set port out of range error here
+ return;
+ }
+
+ priority_recursive_mutex &lock = port == 0 ? digitalI2COnBoardMutex : digitalI2CMXPMutex;
+ {
+ std::lock_guard<priority_recursive_mutex> sync(lock);
+ if(port == 0) {
+ i2COnboardObjCount++;
+ if (i2COnBoardHandle > 0) return;
+ i2COnBoardHandle = i2clib_open("/dev/i2c-2");
+ } else if(port == 1) {
+ i2CMXPObjCount++;
+ if (i2CMXPHandle > 0) return;
+ if(!allocateDIO(getPort(24), false, status)) return;
+ if(!allocateDIO(getPort(25), false, status)) return;
+ digitalSystem->writeEnableMXPSpecialFunction(digitalSystem->readEnableMXPSpecialFunction(status)|0xC000, status);
+ i2CMXPHandle = i2clib_open("/dev/i2c-1");
+ }
+ return;
+ }
+}
+
+/**
+ * Generic transaction.
+ *
+ * This is a lower-level interface to the I2C hardware giving you more control over each transaction.
+ *
+ * @param dataToSend Buffer of data to send as part of the transaction.
+ * @param sendSize Number of bytes to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize Number of bytes to read from the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+int32_t i2CTransaction(uint8_t port, uint8_t deviceAddress, uint8_t *dataToSend, uint8_t sendSize, uint8_t *dataReceived, uint8_t receiveSize)
+{
+ if(port > 1) {
+ //Set port out of range error here
+ return -1;
+ }
+
+ int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+ priority_recursive_mutex &lock = port == 0 ? digitalI2COnBoardMutex : digitalI2CMXPMutex;
+
+ {
+ std::lock_guard<priority_recursive_mutex> sync(lock);
+ return i2clib_writeread(handle, deviceAddress, (const char*) dataToSend, (int32_t) sendSize, (char*) dataReceived, (int32_t) receiveSize);
+ }
+}
+
+/**
+ * Execute a write transaction with the device.
+ *
+ * Write a single byte to a register on a device and wait until the
+ * transaction is complete.
+ *
+ * @param registerAddress The address of the register on the device to be written.
+ * @param data The byte to write to the register on the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+int32_t i2CWrite(uint8_t port, uint8_t deviceAddress, uint8_t* dataToSend, uint8_t sendSize)
+{
+ if(port > 1) {
+ //Set port out of range error here
+ return -1;
+ }
+
+ int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+ priority_recursive_mutex &lock = port == 0 ? digitalI2COnBoardMutex : digitalI2CMXPMutex;
+ {
+ std::lock_guard<priority_recursive_mutex> sync(lock);
+ return i2clib_write(handle, deviceAddress, (const char*) dataToSend, (int32_t) sendSize);
+ }
+}
+
+/**
+ * Execute a read transaction with the device.
+ *
+ * Read bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally allowing
+ * you to read consecutive registers on a device in a single transaction.
+ *
+ * @param registerAddress The register to read first in the transaction.
+ * @param count The number of bytes to read in the transaction.
+ * @param buffer A pointer to the array of bytes to store the data read from the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+int32_t i2CRead(uint8_t port, uint8_t deviceAddress, uint8_t *buffer, uint8_t count)
+{
+ if(port > 1) {
+ //Set port out of range error here
+ return -1;
+ }
+
+ int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+ priority_recursive_mutex &lock = port == 0 ? digitalI2COnBoardMutex : digitalI2CMXPMutex;
+ {
+ std::lock_guard<priority_recursive_mutex> sync(lock);
+ return i2clib_read(handle, deviceAddress, (char*) buffer, (int32_t) count);
+ }
+
+}
+
+void i2CClose(uint8_t port) {
+ if(port > 1) {
+ //Set port out of range error here
+ return;
+ }
+ priority_recursive_mutex &lock = port == 0 ? digitalI2COnBoardMutex : digitalI2CMXPMutex;
+ {
+ std::lock_guard<priority_recursive_mutex> sync(lock);
+ if((port == 0 ? i2COnboardObjCount--:i2CMXPObjCount--) == 0) {
+ int32_t handle = port == 0 ? i2COnBoardHandle:i2CMXPHandle;
+ i2clib_close(handle);
+ }
+ }
+ return;
+}
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/FRC_FPGA_ChipObject_Aliases.h b/hal/lib/Athena/FRC_FPGA_ChipObject/FRC_FPGA_ChipObject_Aliases.h
new file mode 100644
index 0000000..d9fba25
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/FRC_FPGA_ChipObject_Aliases.h
@@ -0,0 +1,10 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __FRC_FPGA_ChipObject_Aliases_h__
+#define __FRC_FPGA_ChipObject_Aliases_h__
+
+#define nRuntimeFPGANamespace nFRC_2012_1_6_4
+#define nInvariantFPGANamespace nFRC_C0EF_1_1_0
+
+#endif // __FRC_FPGA_ChipObject_Aliases_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h b/hal/lib/Athena/FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h
new file mode 100644
index 0000000..923234e
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h
@@ -0,0 +1,9 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __RoboRIO_FRC_ChipObject_Aliases_h__
+#define __RoboRIO_FRC_ChipObject_Aliases_h__
+
+#define nRoboRIO_FPGANamespace nFRC_2016_16_1_0
+
+#endif // __RoboRIO_FRC_ChipObject_Aliases_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h b/hal/lib/Athena/FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h
new file mode 100644
index 0000000..4e9147b
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/fpgainterfacecapi/NiFpga.h
@@ -0,0 +1,2459 @@
+/*
+ * FPGA Interface C API 15.0 header file.
+ *
+ * Copyright (c) 2015,
+ * National Instruments Corporation.
+ * All rights reserved.
+ */
+
+#ifndef __NiFpga_h__
+#define __NiFpga_h__
+
+/*
+ * Determine platform details.
+ */
+#if defined(_M_IX86) \
+ || defined(_M_X64) \
+ || defined(_M_AMD64) \
+ || defined(i386) \
+ || defined(__i386) \
+ || defined(__i386__) \
+ || defined(__i486__) \
+ || defined(__i586__) \
+ || defined(__i686__) \
+ || defined(__amd64__) \
+ || defined(__amd64) \
+ || defined(__x86_64__) \
+ || defined(__x86_64) \
+ || defined(__IA32__) \
+ || defined(_X86_) \
+ || defined(__THW_INTEL__) \
+ || defined(__I86__) \
+ || defined(__INTEL__) \
+ || defined(__X86__) \
+ || defined(__386__) \
+ || defined(__I86__) \
+ || defined(M_I386) \
+ || defined(M_I86) \
+ || defined(_M_I386) \
+ || defined(_M_I86)
+ #if defined(_WIN32) \
+ || defined(_WIN64) \
+ || defined(__WIN32__) \
+ || defined(__TOS_WIN__) \
+ || defined(__WINDOWS__) \
+ || defined(_WINDOWS) \
+ || defined(__WINDOWS_386__) \
+ || defined(__CYGWIN__)
+ /* Either Windows or Phar Lap ETS. */
+ #define NiFpga_Windows 1
+ #elif defined(__linux__) \
+ || defined(__linux) \
+ || defined(linux) \
+ || defined(__gnu_linux__)
+ #define NiFpga_Linux 1
+ #elif defined(__APPLE__) && defined(__MACH__)
+ #define NiFpga_MacOsX 1
+ #else
+ #error Unsupported OS.
+ #endif
+#elif defined(__powerpc) \
+ || defined(__powerpc__) \
+ || defined(__POWERPC__) \
+ || defined(__ppc__) \
+ || defined(__PPC) \
+ || defined(_M_PPC) \
+ || defined(_ARCH_PPC) \
+ || defined(__PPC__) \
+ || defined(__ppc)
+ #if defined(__vxworks)
+ #define NiFpga_VxWorks 1
+ #else
+ #error Unsupported OS.
+ #endif
+#elif defined(__arm__) \
+ || defined(__thumb__) \
+ || defined(__TARGET_ARCH_ARM) \
+ || defined(__TARGET_ARCH_THUMB) \
+ || defined(_ARM) \
+ || defined(_M_ARM) \
+ || defined(_M_ARMT)
+#if defined(__linux__) \
+ || defined(__linux) \
+ || defined(linux) \
+ || defined(__gnu_linux__)
+ #define NiFpga_Linux 1
+#else
+ #error Unsupported OS.
+ #endif
+#else
+ #error Unsupported architecture.
+#endif
+
+/*
+ * Determine compiler.
+ */
+#if defined(_MSC_VER)
+ #define NiFpga_Msvc 1
+#elif defined(__GNUC__)
+ #define NiFpga_Gcc 1
+#elif defined(_CVI_) && !defined(_TPC_)
+ #define NiFpga_Cvi 1
+ /* Enables CVI Library Protection Errors. */
+ #pragma EnableLibraryRuntimeChecking
+#else
+ /* Unknown compiler. */
+#endif
+
+/*
+ * Determine compliance with different C/C++ language standards.
+ */
+#if defined(__cplusplus)
+ #define NiFpga_Cpp 1
+ #if __cplusplus >= 199707L
+ #define NiFpga_Cpp98 1
+ #if __cplusplus >= 201103L
+ #define NiFpga_Cpp11 1
+ #endif
+ #endif
+#endif
+#if defined(__STDC__)
+ #define NiFpga_C89 1
+ #if defined(__STDC_VERSION__)
+ #define NiFpga_C90 1
+ #if __STDC_VERSION__ >= 199409L
+ #define NiFpga_C94 1
+ #if __STDC_VERSION__ >= 199901L
+ #define NiFpga_C99 1
+ #if __STDC_VERSION__ >= 201112L
+ #define NiFpga_C11 1
+ #endif
+ #endif
+ #endif
+ #endif
+#endif
+
+/*
+ * Determine ability to inline functions.
+ */
+#if NiFpga_Cpp || NiFpga_C99
+ /* The inline keyword exists in C++ and C99. */
+#define NiFpga_Inline inline
+#elif NiFpga_Msvc
+ /* Visual C++ (at least since 6.0) also supports an alternate keyword. */
+ #define NiFpga_Inline __inline
+#elif NiFpga_Gcc
+ /* GCC (at least since 2.95.2) also supports an alternate keyword. */
+ #define NiFpga_Inline __inline__
+#elif !defined(NiFpga_Inline)
+ /*
+ * Disable inlining if inline support is unknown. To manually enable
+ * inlining, #define the following macro before #including NiFpga.h:
+ *
+ * #define NiFpga_Inline inline
+ */
+ #define NiFpga_Inline
+#endif
+
+/*
+ * Define exact-width integer types, if they have not already been defined.
+ */
+#if NiFpga_ExactWidthIntegerTypesDefined \
+ || defined(_STDINT) \
+ || defined(_STDINT_H) \
+ || defined(_STDINT_H_) \
+ || defined(_INTTYPES_H) \
+ || defined(_INTTYPES_H_) \
+ || defined(_SYS_STDINT_H) \
+ || defined(_SYS_STDINT_H_) \
+ || defined(_SYS_INTTYPES_H) \
+ || defined(_SYS_INTTYPES_H_) \
+ || defined(_STDINT_H_INCLUDED) \
+ || defined(_MSC_STDINT_H_) \
+ || defined(_PSTDINT_H_INCLUDED)
+ /* Assume that exact-width integer types have already been defined. */
+#elif NiFpga_VxWorks
+ /* VxWorks (at least 6.3 and earlier) did not have stdint.h. */
+ #include <types/vxTypes.h>
+#elif NiFpga_C99 \
+ || NiFpga_Gcc /* GCC (at least since 3.0) has a stdint.h. */ \
+ || defined(HAVE_STDINT_H)
+ /* Assume that stdint.h can be included. */
+ #include <stdint.h>
+#elif NiFpga_Msvc \
+ || NiFpga_Cvi
+ /* Manually define exact-width integer types. */
+ typedef signed char int8_t;
+ typedef unsigned char uint8_t;
+ typedef short int16_t;
+ typedef unsigned short uint16_t;
+ typedef int int32_t;
+ typedef unsigned int uint32_t;
+ typedef __int64 int64_t;
+ typedef unsigned __int64 uint64_t;
+#else
+ /*
+ * Exact-width integer types must be defined by the user, and the following
+ * macro must be #defined, before #including NiFpga.h:
+ *
+ * #define NiFpga_ExactWidthIntegerTypesDefined 1
+ */
+ #error Exact-width integer types must be defined by the user. See comment.
+#endif
+
+/* Included for definition of size_t. */
+#include <stddef.h>
+
+#if NiFpga_Cpp
+extern "C"
+{
+#endif
+
+/**
+ * A boolean value; either NiFpga_False or NiFpga_True.
+ */
+typedef uint8_t NiFpga_Bool;
+
+/**
+ * Represents a false condition.
+ */
+static const NiFpga_Bool NiFpga_False = 0;
+
+/**
+ * Represents a true condition.
+ */
+static const NiFpga_Bool NiFpga_True = 1;
+
+/**
+ * Represents the resulting status of a function call through its return value.
+ * 0 is success, negative values are errors, and positive values are warnings.
+ */
+typedef int32_t NiFpga_Status;
+
+/**
+ * No errors or warnings.
+ */
+static const NiFpga_Status NiFpga_Status_Success = 0;
+
+/**
+ * The timeout expired before the FIFO operation could complete.
+ */
+static const NiFpga_Status NiFpga_Status_FifoTimeout = -50400;
+
+/**
+ * No transfer is in progress because the transfer was aborted by the client.
+ * The operation could not be completed as specified.
+ */
+static const NiFpga_Status NiFpga_Status_TransferAborted = -50405;
+
+/**
+ * A memory allocation failed. Try again after rebooting.
+ */
+static const NiFpga_Status NiFpga_Status_MemoryFull = -52000;
+
+/**
+ * An unexpected software error occurred.
+ */
+static const NiFpga_Status NiFpga_Status_SoftwareFault = -52003;
+
+/**
+ * A parameter to a function was not valid. This could be a NULL pointer, a bad
+ * value, etc.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidParameter = -52005;
+
+/**
+ * A required resource was not found. The NiFpga.* library, the RIO resource, or
+ * some other resource may be missing.
+ */
+static const NiFpga_Status NiFpga_Status_ResourceNotFound = -52006;
+
+/**
+ * A required resource was not properly initialized. This could occur if
+ * NiFpga_Initialize was not called or a required NiFpga_IrqContext was not
+ * reserved.
+ */
+static const NiFpga_Status NiFpga_Status_ResourceNotInitialized = -52010;
+
+/**
+ * A hardware failure has occurred. The operation could not be completed as
+ * specified.
+ */
+static const NiFpga_Status NiFpga_Status_HardwareFault = -52018;
+
+/**
+ * The FPGA is already running.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaAlreadyRunning = -61003;
+
+/**
+ * An error occurred downloading the VI to the FPGA device. Verify that
+ * the target is connected and powered and that the resource of the target
+ * is properly configured.
+ */
+static const NiFpga_Status NiFpga_Status_DownloadError = -61018;
+
+/**
+ * The bitfile was not compiled for the specified resource's device type.
+ */
+static const NiFpga_Status NiFpga_Status_DeviceTypeMismatch = -61024;
+
+/**
+ * An error was detected in the communication between the host computer and the
+ * FPGA target.
+ */
+static const NiFpga_Status NiFpga_Status_CommunicationTimeout = -61046;
+
+/**
+ * The timeout expired before any of the IRQs were asserted.
+ */
+static const NiFpga_Status NiFpga_Status_IrqTimeout = -61060;
+
+/**
+ * The specified bitfile is invalid or corrupt.
+ */
+static const NiFpga_Status NiFpga_Status_CorruptBitfile = -61070;
+
+/**
+ * The requested FIFO depth is invalid. It is either 0 or an amount not
+ * supported by the hardware.
+ */
+static const NiFpga_Status NiFpga_Status_BadDepth = -61072;
+
+/**
+ * The number of FIFO elements is invalid. Either the number is greater than the
+ * depth of the host memory DMA FIFO, or more elements were requested for
+ * release than had been acquired.
+ */
+static const NiFpga_Status NiFpga_Status_BadReadWriteCount = -61073;
+
+/**
+ * A hardware clocking error occurred. A derived clock lost lock with its base
+ * clock during the execution of the LabVIEW FPGA VI. If any base clocks with
+ * derived clocks are referencing an external source, make sure that the
+ * external source is connected and within the supported frequency, jitter,
+ * accuracy, duty cycle, and voltage specifications. Also verify that the
+ * characteristics of the base clock match the configuration specified in the
+ * FPGA Base Clock Properties. If all base clocks with derived clocks are
+ * generated from free-running, on-board sources, please contact National
+ * Instruments technical support at ni.com/support.
+ */
+static const NiFpga_Status NiFpga_Status_ClockLostLock = -61083;
+
+/**
+ * The operation could not be performed because the FPGA is busy. Stop all
+ * activities on the FPGA before requesting this operation. If the target is in
+ * Scan Interface programming mode, put it in FPGA Interface programming mode.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusy = -61141;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * FPGA Interface C API mode. Stop all activities on the FPGA before requesting
+ * this operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterfaceCApi = -61200;
+
+/**
+ * The chassis is in Scan Interface programming mode. In order to run FPGA VIs,
+ * you must go to the chassis properties page, select FPGA programming mode, and
+ * deploy settings.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyScanInterface = -61201;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * FPGA Interface mode. Stop all activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterface = -61202;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * Interactive mode. Stop all activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyInteractive = -61203;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * Emulation mode. Stop all activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyEmulation = -61204;
+
+/**
+ * LabVIEW FPGA does not support the Reset method for bitfiles that allow
+ * removal of implicit enable signals in single-cycle Timed Loops.
+ */
+static const NiFpga_Status NiFpga_Status_ResetCalledWithImplicitEnableRemoval = -61211;
+
+/**
+ * LabVIEW FPGA does not support the Abort method for bitfiles that allow
+ * removal of implicit enable signals in single-cycle Timed Loops.
+ */
+static const NiFpga_Status NiFpga_Status_AbortCalledWithImplicitEnableRemoval = -61212;
+
+/**
+ * LabVIEW FPGA does not support Close and Reset if Last Reference for bitfiles
+ * that allow removal of implicit enable signals in single-cycle Timed Loops.
+ * Pass the NiFpga_CloseAttribute_NoResetIfLastSession attribute to NiFpga_Close
+ * instead of 0.
+ */
+static const NiFpga_Status NiFpga_Status_CloseAndResetCalledWithImplicitEnableRemoval = -61213;
+
+/**
+ * For bitfiles that allow removal of implicit enable signals in single-cycle
+ * Timed Loops, LabVIEW FPGA does not support this method prior to running the
+ * bitfile.
+ */
+static const NiFpga_Status NiFpga_Status_ImplicitEnableRemovalButNotYetRun = -61214;
+
+/**
+ * Bitfiles that allow removal of implicit enable signals in single-cycle Timed
+ * Loops can run only once. Download the bitfile again before re-running the VI.
+ */
+static const NiFpga_Status NiFpga_Status_RunAfterStoppedCalledWithImplicitEnableRemoval = -61215;
+
+/**
+ * A gated clock has violated the handshaking protocol. If you are using
+ * external gated clocks, ensure that they follow the required clock gating
+ * protocol. If you are generating your clocks internally, please contact
+ * National Instruments Technical Support.
+ */
+static const NiFpga_Status NiFpga_Status_GatedClockHandshakingViolation = -61216;
+
+/**
+ * The number of elements requested must be less than or equal to the number of
+ * unacquired elements left in the host memory DMA FIFO. There are currently
+ * fewer unacquired elements left in the FIFO than are being requested. Release
+ * some acquired elements before acquiring more elements.
+ */
+static const NiFpga_Status NiFpga_Status_ElementsNotPermissibleToBeAcquired = -61219;
+
+/**
+ * The operation could not be performed because the FPGA is in configuration or
+ * discovery mode. Wait for configuration or discovery to complete and retry
+ * your operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyConfiguration = -61252;
+
+/**
+ * An unexpected internal error occurred.
+ */
+static const NiFpga_Status NiFpga_Status_InternalError = -61499;
+
+/**
+ * The NI-RIO driver was unable to allocate memory for a FIFO. This can happen
+ * when the combined depth of all DMA FIFOs exceeds the maximum depth for the
+ * controller, or when the controller runs out of system memory. You may be able
+ * to reconfigure the controller with a greater maximum FIFO depth. For more
+ * information, refer to the NI KnowledgeBase article 65OF2ERQ.
+ */
+static const NiFpga_Status NiFpga_Status_TotalDmaFifoDepthExceeded = -63003;
+
+/**
+ * Access to the remote system was denied. Use MAX to check the Remote Device
+ * Access settings under Software>>NI-RIO>>NI-RIO Settings on the remote system.
+ */
+static const NiFpga_Status NiFpga_Status_AccessDenied = -63033;
+
+/**
+ * The NI-RIO software on the host is not compatible with the software on the
+ * target. Upgrade the NI-RIO software on the host in order to connect to this
+ * target.
+ */
+static const NiFpga_Status NiFpga_Status_HostVersionMismatch = -63038;
+
+/**
+ * A connection could not be established to the specified remote device. Ensure
+ * that the device is on and accessible over the network, that NI-RIO software
+ * is installed, and that the RIO server is running and properly configured.
+ */
+static const NiFpga_Status NiFpga_Status_RpcConnectionError = -63040;
+
+/**
+ * The RPC session is invalid. The target may have reset or been rebooted. Check
+ * the network connection and retry the operation.
+ */
+static const NiFpga_Status NiFpga_Status_RpcSessionError = -63043;
+
+/**
+ * The operation could not complete because another session is accessing the
+ * FIFO. Close the other session and retry.
+ */
+static const NiFpga_Status NiFpga_Status_FifoReserved = -63082;
+
+/**
+ * A Configure FIFO, Stop FIFO, Read FIFO, or Write FIFO function was called
+ * while the host had acquired elements of the FIFO. Release all acquired
+ * elements before configuring, stopping, reading, or writing.
+ */
+static const NiFpga_Status NiFpga_Status_FifoElementsCurrentlyAcquired = -63083;
+
+/**
+ * A function was called using a misaligned address. The address must be a
+ * multiple of the size of the datatype.
+ */
+static const NiFpga_Status NiFpga_Status_MisalignedAccess = -63084;
+
+/**
+ * The FPGA Read/Write Control Function is accessing a control or indicator
+ * with data that exceeds the maximum size supported on the current target.
+ * Refer to the hardware documentation for the limitations on data types for
+ * this target.
+ */
+static const NiFpga_Status NiFpga_Status_ControlOrIndicatorTooLarge = -63085;
+
+/**
+ * A valid .lvbitx bitfile is required. If you are using a valid .lvbitx
+ * bitfile, the bitfile may not be compatible with the software you are using.
+ * Determine which version of LabVIEW was used to make the bitfile, update your
+ * software to that version or later, and try again.
+ */
+static const NiFpga_Status NiFpga_Status_BitfileReadError = -63101;
+
+/**
+ * The specified signature does not match the signature of the bitfile. If the
+ * bitfile has been recompiled, regenerate the C API and rebuild the
+ * application.
+ */
+static const NiFpga_Status NiFpga_Status_SignatureMismatch = -63106;
+
+/**
+ * The bitfile you are trying to use is incompatible with the version
+ * of NI-RIO installed on the target and/or host. Update the version
+ * of NI-RIO on the target and/or host to the same version (or later)
+ * used to compile the bitfile. Alternatively, recompile the bitfile
+ * with the same version of NI-RIO that is currently installed on the
+ * target and/or host.
+ */
+static const NiFpga_Status NiFpga_Status_IncompatibleBitfile = -63107;
+
+/**
+ * Either the supplied resource name is invalid as a RIO resource name, or the
+ * device was not found. Use MAX to find the proper resource name for the
+ * intended device.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidResourceName = -63192;
+
+/**
+ * The requested feature is not supported.
+ */
+static const NiFpga_Status NiFpga_Status_FeatureNotSupported = -63193;
+
+/**
+ * The NI-RIO software on the target system is not compatible with this
+ * software. Upgrade the NI-RIO software on the target system.
+ */
+static const NiFpga_Status NiFpga_Status_VersionMismatch = -63194;
+
+/**
+ * The session is invalid or has been closed.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidSession = -63195;
+
+/**
+ * The maximum number of open FPGA sessions has been reached. Close some open
+ * sessions.
+ */
+static const NiFpga_Status NiFpga_Status_OutOfHandles = -63198;
+
+/**
+ * Tests whether a status is an error.
+ *
+ * @param status status to check for an error
+ * @return whether the status was an error
+ */
+static NiFpga_Inline NiFpga_Bool NiFpga_IsError(const NiFpga_Status status)
+{
+ return status < NiFpga_Status_Success ? NiFpga_True : NiFpga_False;
+}
+
+/**
+ * Tests whether a status is not an error. Success and warnings are not errors.
+ *
+ * @param status status to check for an error
+ * @return whether the status was a success or warning
+ */
+static NiFpga_Inline NiFpga_Bool NiFpga_IsNotError(const NiFpga_Status status)
+{
+ return status >= NiFpga_Status_Success ? NiFpga_True : NiFpga_False;
+}
+
+/**
+ * Conditionally sets the status to a new value. The previous status is
+ * preserved unless the new status is more of an error, which means that
+ * warnings and errors overwrite successes, and errors overwrite warnings. New
+ * errors do not overwrite older errors, and new warnings do not overwrite
+ * older warnings.
+ *
+ * @param status status to conditionally set
+ * @param newStatus new status value that may be set
+ * @return the resulting status
+ */
+static NiFpga_Inline NiFpga_Status NiFpga_MergeStatus(
+ NiFpga_Status* const status,
+ const NiFpga_Status newStatus)
+{
+ if (!status)
+ return NiFpga_Status_InvalidParameter;
+ if (NiFpga_IsNotError(*status)
+ && (*status == NiFpga_Status_Success || NiFpga_IsError(newStatus)))
+ *status = newStatus;
+ return *status;
+}
+
+/**
+ * This macro evaluates the expression only if the status is not an error. The
+ * expression must evaluate to an NiFpga_Status, such as a call to any NiFpga_*
+ * function, because the status will be set to the returned status if the
+ * expression is evaluated.
+ *
+ * You can use this macro to mimic status chaining in LabVIEW, where the status
+ * does not have to be explicitly checked after each call. Such code may look
+ * like the following example.
+ *
+ * NiFpga_Status status = NiFpga_Status_Success;
+ * NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));
+ * NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));
+ * NiFpga_IfIsNotError(status, NiFpga_WriteU32(...));
+ *
+ * @param status status to check for an error
+ * @param expression expression to call if the incoming status is not an error
+ */
+#define NiFpga_IfIsNotError(status, expression) \
+ if (NiFpga_IsNotError(status)) \
+ NiFpga_MergeStatus(&status, (expression)); \
+
+/**
+ * You must call this function before all other function calls. This function
+ * loads the NiFpga library so that all the other functions will work. If this
+ * function succeeds, you must call NiFpga_Finalize after all other function
+ * calls.
+ *
+ * @warning This function is not thread safe.
+ *
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Initialize(void);
+
+/**
+ * You must call this function after all other function calls if
+ * NiFpga_Initialize succeeds. This function unloads the NiFpga library.
+ *
+ * @warning This function is not thread safe.
+ *
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Finalize(void);
+
+/**
+ * A handle to an FPGA session.
+ */
+typedef uint32_t NiFpga_Session;
+
+/**
+ * Attributes that NiFpga_Open accepts.
+ */
+typedef enum
+{
+ NiFpga_OpenAttribute_NoRun = 1
+} NiFpga_OpenAttribute;
+
+/**
+ * Opens a session to the FPGA. This call ensures that the contents of the
+ * bitfile are programmed to the FPGA. The FPGA runs unless the
+ * NiFpga_OpenAttribute_NoRun attribute is used.
+ *
+ * Because different operating systems have different default current working
+ * directories for applications, you must pass an absolute path for the bitfile
+ * parameter. If you pass only the filename instead of an absolute path, the
+ * operating system may not be able to locate the bitfile. For example, the
+ * default current working directories are C:\ni-rt\system\ for Phar Lap ETS and
+ * /c/ for VxWorks. Because the generated *_Bitfile constant is a #define to a
+ * string literal, you can use C/C++ string-literal concatenation to form an
+ * absolute path. For example, if the bitfile is in the root directory of a
+ * Phar Lap ETS system, pass the following for the bitfile parameter.
+ *
+ * "C:\\" NiFpga_MyApplication_Bitfile
+ *
+ * @param bitfile path to the bitfile
+ * @param signature signature of the bitfile
+ * @param resource RIO resource string to open ("RIO0" or "rio://mysystem/RIO")
+ * @param attribute bitwise OR of any NiFpga_OpenAttributes, or 0
+ * @param session outputs the session handle, which must be closed when no
+ * longer needed
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Open(const char* bitfile,
+ const char* signature,
+ const char* resource,
+ uint32_t attribute,
+ NiFpga_Session* session);
+
+/**
+ * Attributes that NiFpga_Close accepts.
+ */
+typedef enum
+{
+ NiFpga_CloseAttribute_NoResetIfLastSession = 1
+} NiFpga_CloseAttribute;
+
+/**
+ * Closes the session to the FPGA. The FPGA resets unless either another session
+ * is still open or you use the NiFpga_CloseAttribute_NoResetIfLastSession
+ * attribute.
+ *
+ * @param session handle to a currently open session
+ * @param attribute bitwise OR of any NiFpga_CloseAttributes, or 0
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Close(NiFpga_Session session,
+ uint32_t attribute);
+
+/**
+ * Attributes that NiFpga_Run accepts.
+ */
+typedef enum
+{
+ NiFpga_RunAttribute_WaitUntilDone = 1
+} NiFpga_RunAttribute;
+
+/**
+ * Runs the FPGA VI on the target. If you use NiFpga_RunAttribute_WaitUntilDone,
+ * NiFpga_Run blocks the thread until the FPGA finishes running.
+ *
+ * @param session handle to a currently open session
+ * @param attribute bitwise OR of any NiFpga_RunAttributes, or 0
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Run(NiFpga_Session session,
+ uint32_t attribute);
+
+/**
+ * Aborts the FPGA VI.
+ *
+ * @param session handle to a currently open session
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Abort(NiFpga_Session session);
+
+/**
+ * Resets the FPGA VI.
+ *
+ * @param session handle to a currently open session
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Reset(NiFpga_Session session);
+
+/**
+ * Re-downloads the FPGA bitstream to the target.
+ *
+ * @param session handle to a currently open session
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_Download(NiFpga_Session session);
+
+/**
+ * Reads a boolean value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadBool(NiFpga_Session session,
+ uint32_t indicator,
+ NiFpga_Bool* value);
+
+/**
+ * Reads a signed 8-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI8(NiFpga_Session session,
+ uint32_t indicator,
+ int8_t* value);
+
+/**
+ * Reads an unsigned 8-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU8(NiFpga_Session session,
+ uint32_t indicator,
+ uint8_t* value);
+
+/**
+ * Reads a signed 16-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI16(NiFpga_Session session,
+ uint32_t indicator,
+ int16_t* value);
+
+/**
+ * Reads an unsigned 16-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU16(NiFpga_Session session,
+ uint32_t indicator,
+ uint16_t* value);
+
+/**
+ * Reads a signed 32-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI32(NiFpga_Session session,
+ uint32_t indicator,
+ int32_t* value);
+
+/**
+ * Reads an unsigned 32-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU32(NiFpga_Session session,
+ uint32_t indicator,
+ uint32_t* value);
+
+/**
+ * Reads a signed 64-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadI64(NiFpga_Session session,
+ uint32_t indicator,
+ int64_t* value);
+
+/**
+ * Reads an unsigned 64-bit integer value from a given indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param value outputs the value that was read
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadU64(NiFpga_Session session,
+ uint32_t indicator,
+ uint64_t* value);
+
+/**
+ * Writes a boolean value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteBool(NiFpga_Session session,
+ uint32_t control,
+ NiFpga_Bool value);
+
+/**
+ * Writes a signed 8-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI8(NiFpga_Session session,
+ uint32_t control,
+ int8_t value);
+
+/**
+ * Writes an unsigned 8-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU8(NiFpga_Session session,
+ uint32_t control,
+ uint8_t value);
+
+/**
+ * Writes a signed 16-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI16(NiFpga_Session session,
+ uint32_t control,
+ int16_t value);
+
+/**
+ * Writes an unsigned 16-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU16(NiFpga_Session session,
+ uint32_t control,
+ uint16_t value);
+
+/**
+ * Writes a signed 32-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI32(NiFpga_Session session,
+ uint32_t control,
+ int32_t value);
+
+/**
+ * Writes an unsigned 32-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU32(NiFpga_Session session,
+ uint32_t control,
+ uint32_t value);
+
+/**
+ * Writes a signed 64-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteI64(NiFpga_Session session,
+ uint32_t control,
+ int64_t value);
+
+/**
+ * Writes an unsigned 64-bit integer value to a given control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param value value to write
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteU64(NiFpga_Session session,
+ uint32_t control,
+ uint64_t value);
+
+/**
+ * Reads an entire array of boolean values from a given array indicator or
+ * control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayBool(NiFpga_Session session,
+ uint32_t indicator,
+ NiFpga_Bool* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 8-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI8(NiFpga_Session session,
+ uint32_t indicator,
+ int8_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 8-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU8(NiFpga_Session session,
+ uint32_t indicator,
+ uint8_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 16-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI16(NiFpga_Session session,
+ uint32_t indicator,
+ int16_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 16-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU16(NiFpga_Session session,
+ uint32_t indicator,
+ uint16_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 32-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI32(NiFpga_Session session,
+ uint32_t indicator,
+ int32_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 32-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU32(NiFpga_Session session,
+ uint32_t indicator,
+ uint32_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of signed 64-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayI64(NiFpga_Session session,
+ uint32_t indicator,
+ int64_t* array,
+ size_t size);
+
+/**
+ * Reads an entire array of unsigned 64-bit integer values from a given array
+ * indicator or control.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * indicator or control.
+ *
+ * @param session handle to a currently open session
+ * @param indicator indicator or control from which to read
+ * @param array outputs the entire array that was read
+ * @param size exact number of elements in the indicator or control
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadArrayU64(NiFpga_Session session,
+ uint32_t indicator,
+ uint64_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of boolean values to a given array control or
+ * indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayBool(NiFpga_Session session,
+ uint32_t control,
+ const NiFpga_Bool* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 8-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI8(NiFpga_Session session,
+ uint32_t control,
+ const int8_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 8-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU8(NiFpga_Session session,
+ uint32_t control,
+ const uint8_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 16-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI16(NiFpga_Session session,
+ uint32_t control,
+ const int16_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 16-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU16(NiFpga_Session session,
+ uint32_t control,
+ const uint16_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 32-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI32(NiFpga_Session session,
+ uint32_t control,
+ const int32_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 32-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU32(NiFpga_Session session,
+ uint32_t control,
+ const uint32_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of signed 64-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayI64(NiFpga_Session session,
+ uint32_t control,
+ const int64_t* array,
+ size_t size);
+
+/**
+ * Writes an entire array of unsigned 64-bit integer values to a given array
+ * control or indicator.
+ *
+ * @warning The size passed must be the exact number of elements in the
+ * control or indicator.
+ *
+ * @param session handle to a currently open session
+ * @param control control or indicator to which to write
+ * @param array entire array to write
+ * @param size exact number of elements in the control or indicator
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteArrayU64(NiFpga_Session session,
+ uint32_t control,
+ const uint64_t* array,
+ size_t size);
+
+/**
+ * Enumeration of all 32 possible IRQs. Multiple IRQs can be bitwise ORed
+ * together like this:
+ *
+ * NiFpga_Irq_3 | NiFpga_Irq_23
+ */
+typedef enum
+{
+ NiFpga_Irq_0 = 1 << 0,
+ NiFpga_Irq_1 = 1 << 1,
+ NiFpga_Irq_2 = 1 << 2,
+ NiFpga_Irq_3 = 1 << 3,
+ NiFpga_Irq_4 = 1 << 4,
+ NiFpga_Irq_5 = 1 << 5,
+ NiFpga_Irq_6 = 1 << 6,
+ NiFpga_Irq_7 = 1 << 7,
+ NiFpga_Irq_8 = 1 << 8,
+ NiFpga_Irq_9 = 1 << 9,
+ NiFpga_Irq_10 = 1 << 10,
+ NiFpga_Irq_11 = 1 << 11,
+ NiFpga_Irq_12 = 1 << 12,
+ NiFpga_Irq_13 = 1 << 13,
+ NiFpga_Irq_14 = 1 << 14,
+ NiFpga_Irq_15 = 1 << 15,
+ NiFpga_Irq_16 = 1 << 16,
+ NiFpga_Irq_17 = 1 << 17,
+ NiFpga_Irq_18 = 1 << 18,
+ NiFpga_Irq_19 = 1 << 19,
+ NiFpga_Irq_20 = 1 << 20,
+ NiFpga_Irq_21 = 1 << 21,
+ NiFpga_Irq_22 = 1 << 22,
+ NiFpga_Irq_23 = 1 << 23,
+ NiFpga_Irq_24 = 1 << 24,
+ NiFpga_Irq_25 = 1 << 25,
+ NiFpga_Irq_26 = 1 << 26,
+ NiFpga_Irq_27 = 1 << 27,
+ NiFpga_Irq_28 = 1 << 28,
+ NiFpga_Irq_29 = 1 << 29,
+ NiFpga_Irq_30 = 1 << 30,
+ NiFpga_Irq_31 = 1U << 31
+} NiFpga_Irq;
+
+/**
+ * Represents an infinite timeout.
+ */
+static const uint32_t NiFpga_InfiniteTimeout = 0xFFFFFFFF;
+
+/**
+ * See NiFpga_ReserveIrqContext for more information.
+ */
+typedef void* NiFpga_IrqContext;
+
+/**
+ * IRQ contexts are single-threaded; only one thread can wait with a
+ * particular context at any given time. To minimize jitter when first
+ * waiting on IRQs, reserve as many contexts as the application
+ * requires.
+ *
+ * If a context is successfully reserved (the returned status is not an error),
+ * it must be unreserved later. Otherwise a memory leak will occur.
+ *
+ * @param session handle to a currently open session
+ * @param context outputs the IRQ context
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReserveIrqContext(NiFpga_Session session,
+ NiFpga_IrqContext* context);
+
+/**
+ * Unreserves an IRQ context obtained from NiFpga_ReserveIrqContext.
+ *
+ * @param session handle to a currently open session
+ * @param context IRQ context to unreserve
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_UnreserveIrqContext(NiFpga_Session session,
+ NiFpga_IrqContext context);
+
+/**
+ * This is a blocking function that stops the calling thread until the
+ * FPGA asserts any IRQ in the irqs parameter, or until the function
+ * call times out. Before calling this function, use
+ * NiFpga_ReserveIrqContext to reserve an IRQ context. No other
+ * threads can use the same context when this function is called.
+ *
+ * You can use the irqsAsserted parameter to determine which IRQs were asserted
+ * for each function call.
+ *
+ * @param session handle to a currently open session
+ * @param context IRQ context with which to wait
+ * @param irqs bitwise OR of NiFpga_Irqs
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param irqsAsserted if non-NULL, outputs bitwise OR of IRQs that were
+ * asserted
+ * @param timedOut if non-NULL, outputs whether the timeout expired
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WaitOnIrqs(NiFpga_Session session,
+ NiFpga_IrqContext context,
+ uint32_t irqs,
+ uint32_t timeout,
+ uint32_t* irqsAsserted,
+ NiFpga_Bool* timedOut);
+
+/**
+ * Acknowledges an IRQ or set of IRQs.
+ *
+ * @param session handle to a currently open session
+ * @param irqs bitwise OR of NiFpga_Irqs
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcknowledgeIrqs(NiFpga_Session session,
+ uint32_t irqs);
+
+/**
+ * Specifies the depth of the host memory part of the DMA FIFO. This method is
+ * optional. In order to see the actual depth configured, use
+ * NiFpga_ConfigureFifo2.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to configure
+ * @param depth requested number of elements in the host memory part of the
+ * DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ConfigureFifo(NiFpga_Session session,
+ uint32_t fifo,
+ size_t depth);
+
+/**
+ * Specifies the depth of the host memory part of the DMA FIFO. This method is
+ * optional.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to configure
+ * @param requestedDepth requested number of elements in the host memory part
+ * of the DMA FIFO
+ * @param actualDepth if non-NULL, outputs the actual number of elements in the
+ * host memory part of the DMA FIFO, which may be more than
+ * the requested number
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ConfigureFifo2(NiFpga_Session session,
+ uint32_t fifo,
+ size_t requestedDepth,
+ size_t* actualDepth);
+
+/**
+ * Starts a FIFO. This method is optional.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to start
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_StartFifo(NiFpga_Session session,
+ uint32_t fifo);
+
+/**
+ * Stops a FIFO. This method is optional.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO to stop
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_StopFifo(NiFpga_Session session,
+ uint32_t fifo);
+
+/**
+ * Reads from a target-to-host FIFO of booleans.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoBool(NiFpga_Session session,
+ uint32_t fifo,
+ NiFpga_Bool* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI8(NiFpga_Session session,
+ uint32_t fifo,
+ int8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU8(NiFpga_Session session,
+ uint32_t fifo,
+ uint8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI16(NiFpga_Session session,
+ uint32_t fifo,
+ int16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU16(NiFpga_Session session,
+ uint32_t fifo,
+ uint16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI32(NiFpga_Session session,
+ uint32_t fifo,
+ int32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU32(NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of signed 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoI64(NiFpga_Session session,
+ uint32_t fifo,
+ int64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Reads from a target-to-host FIFO of unsigned 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param data outputs the data that was read
+ * @param numberOfElements number of elements to read
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReadFifoU64(NiFpga_Session session,
+ uint32_t fifo,
+ uint64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* elementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of booleans.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoBool(NiFpga_Session session,
+ uint32_t fifo,
+ const NiFpga_Bool* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI8(NiFpga_Session session,
+ uint32_t fifo,
+ const int8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 8-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU8(NiFpga_Session session,
+ uint32_t fifo,
+ const uint8_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI16(NiFpga_Session session,
+ uint32_t fifo,
+ const int16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 16-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU16(NiFpga_Session session,
+ uint32_t fifo,
+ const uint16_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI32(NiFpga_Session session,
+ uint32_t fifo,
+ const int32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 32-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU32(NiFpga_Session session,
+ uint32_t fifo,
+ const uint32_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of signed 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoI64(NiFpga_Session session,
+ uint32_t fifo,
+ const int64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Writes to a host-to-target FIFO of unsigned 64-bit integers.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param data data to write
+ * @param numberOfElements number of elements to write
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param emptyElementsRemaining if non-NULL, outputs the number of empty
+ * elements remaining in the host memory part of
+ * the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_WriteFifoU64(NiFpga_Session session,
+ uint32_t fifo,
+ const uint64_t* data,
+ size_t numberOfElements,
+ uint32_t timeout,
+ size_t* emptyElementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of booleans.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsBool(
+ NiFpga_Session session,
+ uint32_t fifo,
+ NiFpga_Bool** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 8-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 8-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 16-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 16-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 32-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 32-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of signed 64-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsI64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for reading from a target-to-host FIFO of unsigned 64-bit
+ * integers.
+ *
+ * Acquiring, reading, and releasing FIFO elements prevents the need to copy
+ * the contents of elements from the host memory buffer to a separate
+ * user-allocated buffer before reading. The FPGA target cannot write to
+ * elements acquired by the host. Therefore, the host must release elements
+ * after reading them. The number of elements acquired may differ from the
+ * number of elements requested if, for example, the number of elements
+ * requested reaches the end of the host memory buffer. Always release all
+ * acquired elements before closing the session. Do not attempt to access FIFO
+ * elements after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo target-to-host FIFO from which to read
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoReadElementsU64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of booleans.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsBool(
+ NiFpga_Session session,
+ uint32_t fifo,
+ NiFpga_Bool** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 8-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 8-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU8(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint8_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 16-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 16-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU16(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint16_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 32-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 32-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU32(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of signed 64-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsI64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ int64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Acquires elements for writing to a host-to-target FIFO of unsigned 64-bit
+ * integers.
+ *
+ * Acquiring, writing, and releasing FIFO elements prevents the need to write
+ * first into a separate user-allocated buffer and then copy the contents of
+ * elements to the host memory buffer. The FPGA target cannot read elements
+ * acquired by the host. Therefore, the host must release elements after
+ * writing to them. The number of elements acquired may differ from the number
+ * of elements requested if, for example, the number of elements requested
+ * reaches the end of the host memory buffer. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo host-to-target FIFO to which to write
+ * @param elements outputs a pointer to the elements acquired
+ * @param elementsRequested requested number of elements
+ * @param timeout timeout in milliseconds, or NiFpga_InfiniteTimeout
+ * @param elementsAcquired actual number of elements acquired, which may be
+ * less than the requested number
+ * @param elementsRemaining if non-NULL, outputs the number of elements
+ * remaining in the host memory part of the DMA FIFO
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_AcquireFifoWriteElementsU64(
+ NiFpga_Session session,
+ uint32_t fifo,
+ uint64_t** elements,
+ size_t elementsRequested,
+ uint32_t timeout,
+ size_t* elementsAcquired,
+ size_t* elementsRemaining);
+
+/**
+ * Releases previously acquired FIFO elements.
+ *
+ * The FPGA target cannot read elements acquired by the host. Therefore, the
+ * host must release elements after acquiring them. Always release all acquired
+ * elements before closing the session. Do not attempt to access FIFO elements
+ * after the elements are released or the session is closed.
+ *
+ * @param session handle to a currently open session
+ * @param fifo FIFO from which to release elements
+ * @param elements number of elements to release
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_ReleaseFifoElements(NiFpga_Session session,
+ uint32_t fifo,
+ size_t elements);
+
+/**
+ * Gets an endpoint reference to a peer-to-peer FIFO.
+ *
+ * @param session handle to a currently open session
+ * @param fifo peer-to-peer FIFO
+ * @param endpoint outputs the endpoint reference
+ * @return result of the call
+ */
+NiFpga_Status NiFpga_GetPeerToPeerFifoEndpoint(NiFpga_Session session,
+ uint32_t fifo,
+ uint32_t* endpoint);
+
+#if NiFpga_Cpp
+}
+#endif
+
+#endif
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/nInterfaceGlobals.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/nInterfaceGlobals.h
new file mode 100644
index 0000000..abd07d4
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/nInterfaceGlobals.h
@@ -0,0 +1,15 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_C0EF_1_1_0_nInterfaceGlobals_h__
+#define __nFRC_C0EF_1_1_0_nInterfaceGlobals_h__
+
+namespace nFPGA
+{
+namespace nFRC_C0EF_1_1_0
+{
+ extern unsigned int g_currentTargetClass;
+}
+}
+
+#endif // __nFRC_C0EF_1_1_0_nInterfaceGlobals_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tAI.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tAI.h
new file mode 100644
index 0000000..14121b5
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tAI.h
@@ -0,0 +1,73 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_C0EF_1_1_0_AI_h__
+#define __nFRC_C0EF_1_1_0_AI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_C0EF_1_1_0
+{
+
+class tAI
+{
+public:
+ tAI(){}
+ virtual ~tAI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAI* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+
+
+ typedef enum
+ {
+ } tCalOK_IfaceConstants;
+
+ virtual bool readCalOK(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDoneTime_IfaceConstants;
+
+ virtual unsigned int readDoneTime(tRioStatusCode *status) = 0;
+
+
+
+
+ typedef enum
+ {
+ kNumOffsetRegisters = 8,
+ } tOffset_IfaceConstants;
+
+ virtual signed int readOffset(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumLSBWeightRegisters = 8,
+ } tLSBWeight_IfaceConstants;
+
+ virtual unsigned int readLSBWeight(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+
+private:
+ tAI(const tAI&);
+ void operator=(const tAI&);
+};
+
+}
+}
+
+#endif // __nFRC_C0EF_1_1_0_AI_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tGlobal.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tGlobal.h
new file mode 100644
index 0000000..0b74117
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tGlobal.h
@@ -0,0 +1,69 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_C0EF_1_1_0_Global_h__
+#define __nFRC_C0EF_1_1_0_Global_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_C0EF_1_1_0
+{
+
+class tGlobal
+{
+public:
+ tGlobal(){}
+ virtual ~tGlobal(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tGlobal* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tVersion_IfaceConstants;
+
+ virtual unsigned short readVersion(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLocalTime_IfaceConstants;
+
+ virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tRevision_IfaceConstants;
+
+ virtual unsigned int readRevision(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReserved_IfaceConstants;
+
+ virtual unsigned char readReserved(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tGlobal(const tGlobal&);
+ void operator=(const tGlobal&);
+};
+
+}
+}
+
+#endif // __nFRC_C0EF_1_1_0_Global_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tLoadOut.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tLoadOut.h
new file mode 100644
index 0000000..a7c4ebb
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nInvariantFPGANamespace/tLoadOut.h
@@ -0,0 +1,79 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_C0EF_1_1_0_LoadOut_h__
+#define __nFRC_C0EF_1_1_0_LoadOut_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_C0EF_1_1_0
+{
+
+class tLoadOut
+{
+public:
+ tLoadOut(){}
+ virtual ~tLoadOut(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tLoadOut* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tReady_IfaceConstants;
+
+ virtual bool readReady(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDoneTime_IfaceConstants;
+
+ virtual unsigned int readDoneTime(tRioStatusCode *status) = 0;
+
+
+
+
+ typedef enum
+ {
+ kNumVendorIDRegisters = 8,
+ } tVendorID_IfaceConstants;
+
+ virtual unsigned short readVendorID(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumSerialNumberRegisters = 8,
+ } tSerialNumber_IfaceConstants;
+
+ virtual unsigned int readSerialNumber(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumModuleIDRegisters = 8,
+ } tModuleID_IfaceConstants;
+
+ virtual unsigned short readModuleID(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+private:
+ tLoadOut(const tLoadOut&);
+ void operator=(const tLoadOut&);
+};
+
+}
+}
+
+#endif // __nFRC_C0EF_1_1_0_LoadOut_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h
new file mode 100644
index 0000000..ddd27c6
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h
@@ -0,0 +1,15 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_nInterfaceGlobals_h__
+#define __nFRC_2016_16_1_0_nInterfaceGlobals_h__
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+ extern unsigned int g_currentTargetClass;
+}
+}
+
+#endif // __nFRC_2016_16_1_0_nInterfaceGlobals_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h
new file mode 100644
index 0000000..a4e9aa9
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h
@@ -0,0 +1,143 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_AI_h__
+#define __nFRC_2016_16_1_0_AI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tAI
+{
+public:
+ tAI(){}
+ virtual ~tAI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAI* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ScanSize : 3;
+ unsigned ConvertRate : 26;
+#else
+ unsigned ConvertRate : 26;
+ unsigned ScanSize : 3;
+#endif
+ };
+ struct{
+ unsigned value : 29;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Channel : 3;
+ unsigned Averaged : 1;
+#else
+ unsigned Averaged : 1;
+ unsigned Channel : 3;
+#endif
+ };
+ struct{
+ unsigned value : 4;
+ };
+ } tReadSelect;
+
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual signed int readOutput(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ScanSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ConvertRate(unsigned int value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ScanSize(tRioStatusCode *status) = 0;
+ virtual unsigned int readConfig_ConvertRate(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLoopTiming_IfaceConstants;
+
+ virtual unsigned int readLoopTiming(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumOversampleBitsElements = 8,
+ } tOversampleBits_IfaceConstants;
+
+ virtual void writeOversampleBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readOversampleBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumAverageBitsElements = 8,
+ } tAverageBits_IfaceConstants;
+
+ virtual void writeAverageBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readAverageBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumScanListElements = 8,
+ } tScanList_IfaceConstants;
+
+ virtual void writeScanList(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readScanList(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLatchOutput_IfaceConstants;
+
+ virtual void strobeLatchOutput(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReadSelect_IfaceConstants;
+
+ virtual void writeReadSelect(tReadSelect value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Averaged(bool value, tRioStatusCode *status) = 0;
+ virtual tReadSelect readReadSelect(tRioStatusCode *status) = 0;
+ virtual unsigned char readReadSelect_Channel(tRioStatusCode *status) = 0;
+ virtual bool readReadSelect_Averaged(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAI(const tAI&);
+ void operator=(const tAI&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_AI_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h
new file mode 100644
index 0000000..467503a
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h
@@ -0,0 +1,50 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_AO_h__
+#define __nFRC_2016_16_1_0_AO_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tAO
+{
+public:
+ tAO(){}
+ virtual ~tAO(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAO* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+
+
+ typedef enum
+ {
+ kNumMXPRegisters = 2,
+ } tMXP_IfaceConstants;
+
+ virtual void writeMXP(unsigned char reg_index, unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readMXP(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+private:
+ tAO(const tAO&);
+ void operator=(const tAO&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_AO_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h
new file mode 100644
index 0000000..3fb1193
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h
@@ -0,0 +1,102 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Accel_h__
+#define __nFRC_2016_16_1_0_Accel_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tAccel
+{
+public:
+ tAccel(){}
+ virtual ~tAccel(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAccel* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tSTAT_IfaceConstants;
+
+ virtual unsigned char readSTAT(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCNTR_IfaceConstants;
+
+ virtual void writeCNTR(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readCNTR(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDATO_IfaceConstants;
+
+ virtual void writeDATO(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readDATO(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCNFG_IfaceConstants;
+
+ virtual void writeCNFG(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readCNFG(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCNTL_IfaceConstants;
+
+ virtual void writeCNTL(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readCNTL(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDATI_IfaceConstants;
+
+ virtual unsigned char readDATI(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tGO_IfaceConstants;
+
+ virtual void strobeGO(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tADDR_IfaceConstants;
+
+ virtual void writeADDR(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readADDR(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAccel(const tAccel&);
+ void operator=(const tAccel&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Accel_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h
new file mode 100644
index 0000000..ace0028
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h
@@ -0,0 +1,87 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Accumulator_h__
+#define __nFRC_2016_16_1_0_Accumulator_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tAccumulator
+{
+public:
+ tAccumulator(){}
+ virtual ~tAccumulator(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAccumulator* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ signed long long Value;
+ unsigned Count : 32;
+ };
+ struct{
+ unsigned value : 32;
+ unsigned value2 : 32;
+ unsigned value3 : 32;
+ };
+ } tOutput;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual signed long long readOutput_Value(tRioStatusCode *status) = 0;
+ virtual unsigned int readOutput_Count(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCenter_IfaceConstants;
+
+ virtual void writeCenter(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readCenter(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDeadband_IfaceConstants;
+
+ virtual void writeDeadband(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readDeadband(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tAccumulator(const tAccumulator&);
+ void operator=(const tAccumulator&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Accumulator_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h
new file mode 100644
index 0000000..be6a1fe
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h
@@ -0,0 +1,57 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Alarm_h__
+#define __nFRC_2016_16_1_0_Alarm_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tAlarm
+{
+public:
+ tAlarm(){}
+ virtual ~tAlarm(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAlarm* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tEnable_IfaceConstants;
+
+ virtual void writeEnable(bool value, tRioStatusCode *status) = 0;
+ virtual bool readEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTriggerTime_IfaceConstants;
+
+ virtual void writeTriggerTime(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readTriggerTime(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAlarm(const tAlarm&);
+ void operator=(const tAlarm&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Alarm_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h
new file mode 100644
index 0000000..347d692
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h
@@ -0,0 +1,129 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_AnalogTrigger_h__
+#define __nFRC_2016_16_1_0_AnalogTrigger_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tAnalogTrigger
+{
+public:
+ tAnalogTrigger(){}
+ virtual ~tAnalogTrigger(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAnalogTrigger* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned InHysteresis : 1;
+ unsigned OverLimit : 1;
+ unsigned Rising : 1;
+ unsigned Falling : 1;
+#else
+ unsigned Falling : 1;
+ unsigned Rising : 1;
+ unsigned OverLimit : 1;
+ unsigned InHysteresis : 1;
+#endif
+ };
+ struct{
+ unsigned value : 4;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Channel : 3;
+ unsigned Averaged : 1;
+ unsigned Filter : 1;
+ unsigned FloatingRollover : 1;
+ signed RolloverLimit : 8;
+#else
+ signed RolloverLimit : 8;
+ unsigned FloatingRollover : 1;
+ unsigned Filter : 1;
+ unsigned Averaged : 1;
+ unsigned Channel : 3;
+#endif
+ };
+ struct{
+ unsigned value : 14;
+ };
+ } tSourceSelect;
+
+
+ typedef enum
+ {
+ } tSourceSelect_IfaceConstants;
+
+ virtual void writeSourceSelect(tSourceSelect value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Averaged(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Filter(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_FloatingRollover(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_RolloverLimit(signed short value, tRioStatusCode *status) = 0;
+ virtual tSourceSelect readSourceSelect(tRioStatusCode *status) = 0;
+ virtual unsigned char readSourceSelect_Channel(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_Averaged(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_Filter(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_FloatingRollover(tRioStatusCode *status) = 0;
+ virtual signed short readSourceSelect_RolloverLimit(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUpperLimit_IfaceConstants;
+
+ virtual void writeUpperLimit(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readUpperLimit(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLowerLimit_IfaceConstants;
+
+ virtual void writeLowerLimit(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readLowerLimit(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ kNumOutputElements = 8,
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_InHysteresis(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_OverLimit(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_Rising(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_Falling(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAnalogTrigger(const tAnalogTrigger&);
+ void operator=(const tAnalogTrigger&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_AnalogTrigger_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h
new file mode 100644
index 0000000..ba60770
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h
@@ -0,0 +1,90 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_BIST_h__
+#define __nFRC_2016_16_1_0_BIST_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tBIST
+{
+public:
+ tBIST(){}
+ virtual ~tBIST(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tBIST* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tDO0SquareTicks_IfaceConstants;
+
+ virtual void writeDO0SquareTicks(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readDO0SquareTicks(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tEnable_IfaceConstants;
+
+ virtual void writeEnable(bool value, tRioStatusCode *status) = 0;
+ virtual bool readEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO1SquareEnable_IfaceConstants;
+
+ virtual void writeDO1SquareEnable(bool value, tRioStatusCode *status) = 0;
+ virtual bool readDO1SquareEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO0SquareEnable_IfaceConstants;
+
+ virtual void writeDO0SquareEnable(bool value, tRioStatusCode *status) = 0;
+ virtual bool readDO0SquareEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO1SquareTicks_IfaceConstants;
+
+ virtual void writeDO1SquareTicks(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readDO1SquareTicks(tRioStatusCode *status) = 0;
+
+
+
+
+ typedef enum
+ {
+ kNumDORegisters = 2,
+ } tDO_IfaceConstants;
+
+ virtual void writeDO(unsigned char reg_index, bool value, tRioStatusCode *status) = 0;
+ virtual bool readDO(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+private:
+ tBIST(const tBIST&);
+ void operator=(const tBIST&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_BIST_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h
new file mode 100644
index 0000000..ebfb680
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h
@@ -0,0 +1,219 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Counter_h__
+#define __nFRC_2016_16_1_0_Counter_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tCounter
+{
+public:
+ tCounter(){}
+ virtual ~tCounter(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tCounter* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Direction : 1;
+ signed Value : 31;
+#else
+ signed Value : 31;
+ unsigned Direction : 1;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned UpSource_Channel : 4;
+ unsigned UpSource_Module : 1;
+ unsigned UpSource_AnalogTrigger : 1;
+ unsigned DownSource_Channel : 4;
+ unsigned DownSource_Module : 1;
+ unsigned DownSource_AnalogTrigger : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned IndexEdgeSensitive : 1;
+ unsigned UpRisingEdge : 1;
+ unsigned UpFallingEdge : 1;
+ unsigned DownRisingEdge : 1;
+ unsigned DownFallingEdge : 1;
+ unsigned Mode : 2;
+ unsigned PulseLengthThreshold : 6;
+#else
+ unsigned PulseLengthThreshold : 6;
+ unsigned Mode : 2;
+ unsigned DownFallingEdge : 1;
+ unsigned DownRisingEdge : 1;
+ unsigned UpFallingEdge : 1;
+ unsigned UpRisingEdge : 1;
+ unsigned IndexEdgeSensitive : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned DownSource_AnalogTrigger : 1;
+ unsigned DownSource_Module : 1;
+ unsigned DownSource_Channel : 4;
+ unsigned UpSource_AnalogTrigger : 1;
+ unsigned UpSource_Module : 1;
+ unsigned UpSource_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Period : 23;
+ signed Count : 8;
+ unsigned Stalled : 1;
+#else
+ unsigned Stalled : 1;
+ signed Count : 8;
+ unsigned Period : 23;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned StallPeriod : 24;
+ unsigned AverageSize : 7;
+ unsigned UpdateWhenEmpty : 1;
+#else
+ unsigned UpdateWhenEmpty : 1;
+ unsigned AverageSize : 7;
+ unsigned StallPeriod : 24;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerConfig;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual bool readOutput_Direction(tRioStatusCode *status) = 0;
+ virtual signed int readOutput_Value(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexEdgeSensitive(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpRisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpFallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownRisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownFallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Mode(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_PulseLengthThreshold(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_UpSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_UpSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_DownSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_DownSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexEdgeSensitive(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpRisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpFallingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownRisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownFallingEdge(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Mode(tRioStatusCode *status) = 0;
+ virtual unsigned short readConfig_PulseLengthThreshold(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerOutput_IfaceConstants;
+
+ virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;
+ virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;
+ virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerConfig_IfaceConstants;
+
+ virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;
+ virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;
+ virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;
+ virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tCounter(const tCounter&);
+ void operator=(const tCounter&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Counter_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h
new file mode 100644
index 0000000..c14ebf9
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h
@@ -0,0 +1,248 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_DIO_h__
+#define __nFRC_2016_16_1_0_DIO_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tDIO
+{
+public:
+ tDIO(){}
+ virtual ~tDIO(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tDIO* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Headers : 10;
+ unsigned Reserved : 6;
+ unsigned MXP : 16;
+#else
+ unsigned MXP : 16;
+ unsigned Reserved : 6;
+ unsigned Headers : 10;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tDO;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Headers : 10;
+ unsigned Reserved : 6;
+ unsigned MXP : 16;
+#else
+ unsigned MXP : 16;
+ unsigned Reserved : 6;
+ unsigned Headers : 10;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutputEnable;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Headers : 10;
+ unsigned Reserved : 6;
+ unsigned MXP : 16;
+#else
+ unsigned MXP : 16;
+ unsigned Reserved : 6;
+ unsigned Headers : 10;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tPulse;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Headers : 10;
+ unsigned Reserved : 6;
+ unsigned MXP : 16;
+#else
+ unsigned MXP : 16;
+ unsigned Reserved : 6;
+ unsigned Headers : 10;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tDI;
+
+
+
+ typedef enum
+ {
+ } tDO_IfaceConstants;
+
+ virtual void writeDO(tDO value, tRioStatusCode *status) = 0;
+ virtual void writeDO_Headers(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeDO_Reserved(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_MXP(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tDO readDO(tRioStatusCode *status) = 0;
+ virtual unsigned short readDO_Headers(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_Reserved(tRioStatusCode *status) = 0;
+ virtual unsigned short readDO_MXP(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPWMDutyCycleAElements = 4,
+ } tPWMDutyCycleA_IfaceConstants;
+
+ virtual void writePWMDutyCycleA(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMDutyCycleA(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPWMDutyCycleBElements = 2,
+ } tPWMDutyCycleB_IfaceConstants;
+
+ virtual void writePWMDutyCycleB(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMDutyCycleB(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumFilterSelectHdrElements = 16,
+ } tFilterSelectHdr_IfaceConstants;
+
+ virtual void writeFilterSelectHdr(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readFilterSelectHdr(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tOutputEnable_IfaceConstants;
+
+ virtual void writeOutputEnable(tOutputEnable value, tRioStatusCode *status) = 0;
+ virtual void writeOutputEnable_Headers(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeOutputEnable_Reserved(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeOutputEnable_MXP(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tOutputEnable readOutputEnable(tRioStatusCode *status) = 0;
+ virtual unsigned short readOutputEnable_Headers(tRioStatusCode *status) = 0;
+ virtual unsigned char readOutputEnable_Reserved(tRioStatusCode *status) = 0;
+ virtual unsigned short readOutputEnable_MXP(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPWMOutputSelectElements = 6,
+ } tPWMOutputSelect_IfaceConstants;
+
+ virtual void writePWMOutputSelect(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMOutputSelect(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPulse_IfaceConstants;
+
+ virtual void writePulse(tPulse value, tRioStatusCode *status) = 0;
+ virtual void writePulse_Headers(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writePulse_Reserved(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writePulse_MXP(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tPulse readPulse(tRioStatusCode *status) = 0;
+ virtual unsigned short readPulse_Headers(tRioStatusCode *status) = 0;
+ virtual unsigned char readPulse_Reserved(tRioStatusCode *status) = 0;
+ virtual unsigned short readPulse_MXP(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDI_IfaceConstants;
+
+ virtual tDI readDI(tRioStatusCode *status) = 0;
+ virtual unsigned short readDI_Headers(tRioStatusCode *status) = 0;
+ virtual unsigned char readDI_Reserved(tRioStatusCode *status) = 0;
+ virtual unsigned short readDI_MXP(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tEnableMXPSpecialFunction_IfaceConstants;
+
+ virtual void writeEnableMXPSpecialFunction(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readEnableMXPSpecialFunction(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumFilterSelectMXPElements = 16,
+ } tFilterSelectMXP_IfaceConstants;
+
+ virtual void writeFilterSelectMXP(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readFilterSelectMXP(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPulseLength_IfaceConstants;
+
+ virtual void writePulseLength(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPulseLength(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPWMPeriodPower_IfaceConstants;
+
+ virtual void writePWMPeriodPower(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readPWMPeriodPower(tRioStatusCode *status) = 0;
+
+
+
+
+ typedef enum
+ {
+ kNumFilterPeriodMXPRegisters = 3,
+ } tFilterPeriodMXP_IfaceConstants;
+
+ virtual void writeFilterPeriodMXP(unsigned char reg_index, unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readFilterPeriodMXP(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumFilterPeriodHdrRegisters = 3,
+ } tFilterPeriodHdr_IfaceConstants;
+
+ virtual void writeFilterPeriodHdr(unsigned char reg_index, unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readFilterPeriodHdr(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+private:
+ tDIO(const tDIO&);
+ void operator=(const tDIO&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_DIO_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h
new file mode 100644
index 0000000..760ee35
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h
@@ -0,0 +1,197 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_DMA_h__
+#define __nFRC_2016_16_1_0_DMA_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tDMA
+{
+public:
+ tDMA(){}
+ virtual ~tDMA(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tDMA* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Pause : 1;
+ unsigned Enable_AI0_Low : 1;
+ unsigned Enable_AI0_High : 1;
+ unsigned Enable_AIAveraged0_Low : 1;
+ unsigned Enable_AIAveraged0_High : 1;
+ unsigned Enable_AI1_Low : 1;
+ unsigned Enable_AI1_High : 1;
+ unsigned Enable_AIAveraged1_Low : 1;
+ unsigned Enable_AIAveraged1_High : 1;
+ unsigned Enable_Accumulator0 : 1;
+ unsigned Enable_Accumulator1 : 1;
+ unsigned Enable_DI : 1;
+ unsigned Enable_AnalogTriggers : 1;
+ unsigned Enable_Counters_Low : 1;
+ unsigned Enable_Counters_High : 1;
+ unsigned Enable_CounterTimers_Low : 1;
+ unsigned Enable_CounterTimers_High : 1;
+ unsigned Enable_Encoders_Low : 1;
+ unsigned Enable_Encoders_High : 1;
+ unsigned Enable_EncoderTimers_Low : 1;
+ unsigned Enable_EncoderTimers_High : 1;
+ unsigned ExternalClock : 1;
+#else
+ unsigned ExternalClock : 1;
+ unsigned Enable_EncoderTimers_High : 1;
+ unsigned Enable_EncoderTimers_Low : 1;
+ unsigned Enable_Encoders_High : 1;
+ unsigned Enable_Encoders_Low : 1;
+ unsigned Enable_CounterTimers_High : 1;
+ unsigned Enable_CounterTimers_Low : 1;
+ unsigned Enable_Counters_High : 1;
+ unsigned Enable_Counters_Low : 1;
+ unsigned Enable_AnalogTriggers : 1;
+ unsigned Enable_DI : 1;
+ unsigned Enable_Accumulator1 : 1;
+ unsigned Enable_Accumulator0 : 1;
+ unsigned Enable_AIAveraged1_High : 1;
+ unsigned Enable_AIAveraged1_Low : 1;
+ unsigned Enable_AI1_High : 1;
+ unsigned Enable_AI1_Low : 1;
+ unsigned Enable_AIAveraged0_High : 1;
+ unsigned Enable_AIAveraged0_Low : 1;
+ unsigned Enable_AI0_High : 1;
+ unsigned Enable_AI0_Low : 1;
+ unsigned Pause : 1;
+#endif
+ };
+ struct{
+ unsigned value : 22;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ExternalClockSource_Channel : 4;
+ unsigned ExternalClockSource_Module : 1;
+ unsigned ExternalClockSource_AnalogTrigger : 1;
+ unsigned RisingEdge : 1;
+ unsigned FallingEdge : 1;
+#else
+ unsigned FallingEdge : 1;
+ unsigned RisingEdge : 1;
+ unsigned ExternalClockSource_AnalogTrigger : 1;
+ unsigned ExternalClockSource_Module : 1;
+ unsigned ExternalClockSource_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 8;
+ };
+ } tExternalTriggers;
+
+
+
+ typedef enum
+ {
+ } tRate_IfaceConstants;
+
+ virtual void writeRate(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readRate(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Pause(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI0_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI0_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged0_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged0_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI1_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI1_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged1_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged1_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Accumulator0(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Accumulator1(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_DI(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AnalogTriggers(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Counters_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Counters_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_CounterTimers_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_CounterTimers_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Encoders_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Encoders_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_EncoderTimers_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_EncoderTimers_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ExternalClock(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Pause(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI0_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI0_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged0_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged0_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI1_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI1_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged1_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged1_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Accumulator0(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Accumulator1(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_DI(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AnalogTriggers(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Counters_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Counters_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_CounterTimers_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_CounterTimers_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Encoders_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Encoders_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_EncoderTimers_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_EncoderTimers_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ExternalClock(tRioStatusCode *status) = 0;
+
+
+
+
+ typedef enum
+ {
+ kNumExternalTriggersRegisters = 2,
+ kNumExternalTriggersElements = 4,
+ } tExternalTriggers_IfaceConstants;
+
+ virtual void writeExternalTriggers(unsigned char reg_index, unsigned char bitfield_index, tExternalTriggers value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_Channel(unsigned char reg_index, unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_Module(unsigned char reg_index, unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char reg_index, unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_RisingEdge(unsigned char reg_index, unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_FallingEdge(unsigned char reg_index, unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual tExternalTriggers readExternalTriggers(unsigned char reg_index, unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual unsigned char readExternalTriggers_ExternalClockSource_Channel(unsigned char reg_index, unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual unsigned char readExternalTriggers_ExternalClockSource_Module(unsigned char reg_index, unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char reg_index, unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_RisingEdge(unsigned char reg_index, unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_FallingEdge(unsigned char reg_index, unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+private:
+ tDMA(const tDMA&);
+ void operator=(const tDMA&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_DMA_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h
new file mode 100644
index 0000000..8db77c2
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h
@@ -0,0 +1,199 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Encoder_h__
+#define __nFRC_2016_16_1_0_Encoder_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tEncoder
+{
+public:
+ tEncoder(){}
+ virtual ~tEncoder(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tEncoder* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Direction : 1;
+ signed Value : 31;
+#else
+ signed Value : 31;
+ unsigned Direction : 1;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ASource_Channel : 4;
+ unsigned ASource_Module : 1;
+ unsigned ASource_AnalogTrigger : 1;
+ unsigned BSource_Channel : 4;
+ unsigned BSource_Module : 1;
+ unsigned BSource_AnalogTrigger : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned IndexEdgeSensitive : 1;
+ unsigned Reverse : 1;
+#else
+ unsigned Reverse : 1;
+ unsigned IndexEdgeSensitive : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned BSource_AnalogTrigger : 1;
+ unsigned BSource_Module : 1;
+ unsigned BSource_Channel : 4;
+ unsigned ASource_AnalogTrigger : 1;
+ unsigned ASource_Module : 1;
+ unsigned ASource_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 21;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Period : 23;
+ signed Count : 8;
+ unsigned Stalled : 1;
+#else
+ unsigned Stalled : 1;
+ signed Count : 8;
+ unsigned Period : 23;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned StallPeriod : 24;
+ unsigned AverageSize : 7;
+ unsigned UpdateWhenEmpty : 1;
+#else
+ unsigned UpdateWhenEmpty : 1;
+ unsigned AverageSize : 7;
+ unsigned StallPeriod : 24;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerConfig;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual bool readOutput_Direction(tRioStatusCode *status) = 0;
+ virtual signed int readOutput_Value(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexEdgeSensitive(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Reverse(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ASource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ASource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ASource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_BSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexEdgeSensitive(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Reverse(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerOutput_IfaceConstants;
+
+ virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;
+ virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;
+ virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerConfig_IfaceConstants;
+
+ virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;
+ virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;
+ virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;
+ virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tEncoder(const tEncoder&);
+ void operator=(const tEncoder&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Encoder_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h
new file mode 100644
index 0000000..737a241
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h
@@ -0,0 +1,104 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Global_h__
+#define __nFRC_2016_16_1_0_Global_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tGlobal
+{
+public:
+ tGlobal(){}
+ virtual ~tGlobal(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tGlobal* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Radio : 8;
+ unsigned Comm : 8;
+ unsigned Mode : 8;
+ unsigned RSL : 1;
+#else
+ unsigned RSL : 1;
+ unsigned Mode : 8;
+ unsigned Comm : 8;
+ unsigned Radio : 8;
+#endif
+ };
+ struct{
+ unsigned value : 25;
+ };
+ } tLEDs;
+
+
+
+ typedef enum
+ {
+ } tLEDs_IfaceConstants;
+
+ virtual void writeLEDs(tLEDs value, tRioStatusCode *status) = 0;
+ virtual void writeLEDs_Radio(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeLEDs_Comm(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeLEDs_Mode(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeLEDs_RSL(bool value, tRioStatusCode *status) = 0;
+ virtual tLEDs readLEDs(tRioStatusCode *status) = 0;
+ virtual unsigned char readLEDs_Radio(tRioStatusCode *status) = 0;
+ virtual unsigned char readLEDs_Comm(tRioStatusCode *status) = 0;
+ virtual unsigned char readLEDs_Mode(tRioStatusCode *status) = 0;
+ virtual bool readLEDs_RSL(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tVersion_IfaceConstants;
+
+ virtual unsigned short readVersion(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLocalTime_IfaceConstants;
+
+ virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUserButton_IfaceConstants;
+
+ virtual bool readUserButton(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tRevision_IfaceConstants;
+
+ virtual unsigned int readRevision(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tGlobal(const tGlobal&);
+ void operator=(const tGlobal&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Global_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h
new file mode 100644
index 0000000..e2f69a2
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h
@@ -0,0 +1,100 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Interrupt_h__
+#define __nFRC_2016_16_1_0_Interrupt_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tInterrupt
+{
+public:
+ tInterrupt(){}
+ virtual ~tInterrupt(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tInterrupt* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Source_Channel : 4;
+ unsigned Source_Module : 1;
+ unsigned Source_AnalogTrigger : 1;
+ unsigned RisingEdge : 1;
+ unsigned FallingEdge : 1;
+ unsigned WaitForAck : 1;
+#else
+ unsigned WaitForAck : 1;
+ unsigned FallingEdge : 1;
+ unsigned RisingEdge : 1;
+ unsigned Source_AnalogTrigger : 1;
+ unsigned Source_Module : 1;
+ unsigned Source_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 9;
+ };
+ } tConfig;
+
+
+ typedef enum
+ {
+ } tFallingTimeStamp_IfaceConstants;
+
+ virtual unsigned int readFallingTimeStamp(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_RisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_FallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_WaitForAck(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Source_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Source_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Source_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_RisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_FallingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_WaitForAck(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tRisingTimeStamp_IfaceConstants;
+
+ virtual unsigned int readRisingTimeStamp(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tInterrupt(const tInterrupt&);
+ void operator=(const tInterrupt&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Interrupt_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h
new file mode 100644
index 0000000..73c82a7
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h
@@ -0,0 +1,120 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_PWM_h__
+#define __nFRC_2016_16_1_0_PWM_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tPWM
+{
+public:
+ tPWM(){}
+ virtual ~tPWM(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tPWM* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Period : 16;
+ unsigned MinHigh : 16;
+#else
+ unsigned MinHigh : 16;
+ unsigned Period : 16;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tConfig;
+
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Period(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_MinHigh(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned short readConfig_Period(tRioStatusCode *status) = 0;
+ virtual unsigned short readConfig_MinHigh(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLoopTiming_IfaceConstants;
+
+ virtual unsigned short readLoopTiming(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPeriodScaleMXPElements = 10,
+ } tPeriodScaleMXP_IfaceConstants;
+
+ virtual void writePeriodScaleMXP(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPeriodScaleMXP(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPeriodScaleHdrElements = 10,
+ } tPeriodScaleHdr_IfaceConstants;
+
+ virtual void writePeriodScaleHdr(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPeriodScaleHdr(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumZeroLatchElements = 20,
+ } tZeroLatch_IfaceConstants;
+
+ virtual void writeZeroLatch(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual bool readZeroLatch(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+ typedef enum
+ {
+ kNumHdrRegisters = 10,
+ } tHdr_IfaceConstants;
+
+ virtual void writeHdr(unsigned char reg_index, unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readHdr(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumMXPRegisters = 10,
+ } tMXP_IfaceConstants;
+
+ virtual void writeMXP(unsigned char reg_index, unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readMXP(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+private:
+ tPWM(const tPWM&);
+ void operator=(const tPWM&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_PWM_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h
new file mode 100644
index 0000000..6e72979
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h
@@ -0,0 +1,220 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Power_h__
+#define __nFRC_2016_16_1_0_Power_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tPower
+{
+public:
+ tPower(){}
+ virtual ~tPower(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tPower* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned User3V3 : 8;
+ unsigned User5V : 8;
+ unsigned User6V : 8;
+#else
+ unsigned User6V : 8;
+ unsigned User5V : 8;
+ unsigned User3V3 : 8;
+#endif
+ };
+ struct{
+ unsigned value : 24;
+ };
+ } tStatus;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned OverCurrentFaultCount3V3 : 8;
+ unsigned OverCurrentFaultCount5V : 8;
+ unsigned OverCurrentFaultCount6V : 8;
+ unsigned UnderVoltageFaultCount5V : 8;
+#else
+ unsigned UnderVoltageFaultCount5V : 8;
+ unsigned OverCurrentFaultCount6V : 8;
+ unsigned OverCurrentFaultCount5V : 8;
+ unsigned OverCurrentFaultCount3V3 : 8;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tFaultCounts;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned User3V3 : 1;
+ unsigned User5V : 1;
+ unsigned User6V : 1;
+#else
+ unsigned User6V : 1;
+ unsigned User5V : 1;
+ unsigned User3V3 : 1;
+#endif
+ };
+ struct{
+ unsigned value : 3;
+ };
+ } tDisable;
+
+
+
+ typedef enum
+ {
+ } tUserVoltage3V3_IfaceConstants;
+
+ virtual unsigned short readUserVoltage3V3(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tStatus_IfaceConstants;
+
+ virtual tStatus readStatus(tRioStatusCode *status) = 0;
+ virtual unsigned char readStatus_User3V3(tRioStatusCode *status) = 0;
+ virtual unsigned char readStatus_User5V(tRioStatusCode *status) = 0;
+ virtual unsigned char readStatus_User6V(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUserVoltage6V_IfaceConstants;
+
+ virtual unsigned short readUserVoltage6V(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tOnChipTemperature_IfaceConstants;
+
+ virtual unsigned short readOnChipTemperature(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUserVoltage5V_IfaceConstants;
+
+ virtual unsigned short readUserVoltage5V(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tResetFaultCounts_IfaceConstants;
+
+ virtual void strobeResetFaultCounts(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tIntegratedIO_IfaceConstants;
+
+ virtual unsigned short readIntegratedIO(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tMXP_DIOVoltage_IfaceConstants;
+
+ virtual unsigned short readMXP_DIOVoltage(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUserCurrent3V3_IfaceConstants;
+
+ virtual unsigned short readUserCurrent3V3(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tVinVoltage_IfaceConstants;
+
+ virtual unsigned short readVinVoltage(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUserCurrent6V_IfaceConstants;
+
+ virtual unsigned short readUserCurrent6V(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUserCurrent5V_IfaceConstants;
+
+ virtual unsigned short readUserCurrent5V(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tAOVoltage_IfaceConstants;
+
+ virtual unsigned short readAOVoltage(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tFaultCounts_IfaceConstants;
+
+ virtual tFaultCounts readFaultCounts(tRioStatusCode *status) = 0;
+ virtual unsigned char readFaultCounts_OverCurrentFaultCount3V3(tRioStatusCode *status) = 0;
+ virtual unsigned char readFaultCounts_OverCurrentFaultCount5V(tRioStatusCode *status) = 0;
+ virtual unsigned char readFaultCounts_OverCurrentFaultCount6V(tRioStatusCode *status) = 0;
+ virtual unsigned char readFaultCounts_UnderVoltageFaultCount5V(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tVinCurrent_IfaceConstants;
+
+ virtual unsigned short readVinCurrent(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDisable_IfaceConstants;
+
+ virtual void writeDisable(tDisable value, tRioStatusCode *status) = 0;
+ virtual void writeDisable_User3V3(bool value, tRioStatusCode *status) = 0;
+ virtual void writeDisable_User5V(bool value, tRioStatusCode *status) = 0;
+ virtual void writeDisable_User6V(bool value, tRioStatusCode *status) = 0;
+ virtual tDisable readDisable(tRioStatusCode *status) = 0;
+ virtual bool readDisable_User3V3(tRioStatusCode *status) = 0;
+ virtual bool readDisable_User5V(tRioStatusCode *status) = 0;
+ virtual bool readDisable_User6V(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tPower(const tPower&);
+ void operator=(const tPower&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Power_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h
new file mode 100644
index 0000000..e1d9345
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h
@@ -0,0 +1,68 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_Relay_h__
+#define __nFRC_2016_16_1_0_Relay_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tRelay
+{
+public:
+ tRelay(){}
+ virtual ~tRelay(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tRelay* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Forward : 4;
+ unsigned Reverse : 4;
+#else
+ unsigned Reverse : 4;
+ unsigned Forward : 4;
+#endif
+ };
+ struct{
+ unsigned value : 8;
+ };
+ } tValue;
+
+
+
+ typedef enum
+ {
+ } tValue_IfaceConstants;
+
+ virtual void writeValue(tValue value, tRioStatusCode *status) = 0;
+ virtual void writeValue_Forward(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeValue_Reverse(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tValue readValue(tRioStatusCode *status) = 0;
+ virtual unsigned char readValue_Forward(tRioStatusCode *status) = 0;
+ virtual unsigned char readValue_Reverse(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tRelay(const tRelay&);
+ void operator=(const tRelay&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_Relay_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h
new file mode 100644
index 0000000..2c17607
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h
@@ -0,0 +1,68 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_SPI_h__
+#define __nFRC_2016_16_1_0_SPI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tSPI
+{
+public:
+ tSPI(){}
+ virtual ~tSPI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSPI* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Hdr : 4;
+ unsigned MXP : 1;
+#else
+ unsigned MXP : 1;
+ unsigned Hdr : 4;
+#endif
+ };
+ struct{
+ unsigned value : 5;
+ };
+ } tChipSelectActiveHigh;
+
+
+
+ typedef enum
+ {
+ } tChipSelectActiveHigh_IfaceConstants;
+
+ virtual void writeChipSelectActiveHigh(tChipSelectActiveHigh value, tRioStatusCode *status) = 0;
+ virtual void writeChipSelectActiveHigh_Hdr(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChipSelectActiveHigh_MXP(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tChipSelectActiveHigh readChipSelectActiveHigh(tRioStatusCode *status) = 0;
+ virtual unsigned char readChipSelectActiveHigh_Hdr(tRioStatusCode *status) = 0;
+ virtual unsigned char readChipSelectActiveHigh_MXP(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSPI(const tSPI&);
+ void operator=(const tSPI&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_SPI_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h
new file mode 100644
index 0000000..08c7a23
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h
@@ -0,0 +1,108 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2016_16_1_0_SysWatchdog_h__
+#define __nFRC_2016_16_1_0_SysWatchdog_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2016_16_1_0
+{
+
+class tSysWatchdog
+{
+public:
+ tSysWatchdog(){}
+ virtual ~tSysWatchdog(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSysWatchdog* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned SystemActive : 1;
+ unsigned PowerAlive : 1;
+ unsigned SysDisableCount : 15;
+ unsigned PowerDisableCount : 15;
+#else
+ unsigned PowerDisableCount : 15;
+ unsigned SysDisableCount : 15;
+ unsigned PowerAlive : 1;
+ unsigned SystemActive : 1;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tStatus;
+
+
+
+ typedef enum
+ {
+ } tStatus_IfaceConstants;
+
+ virtual tStatus readStatus(tRioStatusCode *status) = 0;
+ virtual bool readStatus_SystemActive(tRioStatusCode *status) = 0;
+ virtual bool readStatus_PowerAlive(tRioStatusCode *status) = 0;
+ virtual unsigned short readStatus_SysDisableCount(tRioStatusCode *status) = 0;
+ virtual unsigned short readStatus_PowerDisableCount(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCommand_IfaceConstants;
+
+ virtual void writeCommand(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readCommand(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tChallenge_IfaceConstants;
+
+ virtual unsigned char readChallenge(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tActive_IfaceConstants;
+
+ virtual void writeActive(bool value, tRioStatusCode *status) = 0;
+ virtual bool readActive(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimer_IfaceConstants;
+
+ virtual unsigned int readTimer(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tForcedKills_IfaceConstants;
+
+ virtual unsigned short readForcedKills(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSysWatchdog(const tSysWatchdog&);
+ void operator=(const tSysWatchdog&);
+};
+
+}
+}
+
+#endif // __nFRC_2016_16_1_0_SysWatchdog_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/nInterfaceGlobals.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/nInterfaceGlobals.h
new file mode 100644
index 0000000..f34cc74
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/nInterfaceGlobals.h
@@ -0,0 +1,15 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_nInterfaceGlobals_h__
+#define __nFRC_2012_1_6_4_nInterfaceGlobals_h__
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+ extern unsigned int g_currentTargetClass;
+}
+}
+
+#endif // __nFRC_2012_1_6_4_nInterfaceGlobals_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAI.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAI.h
new file mode 100644
index 0000000..78c423a
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAI.h
@@ -0,0 +1,149 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_AI_h__
+#define __nFRC_2012_1_6_4_AI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAI
+{
+public:
+ tAI(){}
+ virtual ~tAI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAI* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Channel : 3;
+ unsigned Module : 1;
+ unsigned Averaged : 1;
+#else
+ unsigned Averaged : 1;
+ unsigned Module : 1;
+ unsigned Channel : 3;
+#endif
+ };
+ struct{
+ unsigned value : 5;
+ };
+ } tReadSelect;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ScanSize : 3;
+ unsigned ConvertRate : 26;
+#else
+ unsigned ConvertRate : 26;
+ unsigned ScanSize : 3;
+#endif
+ };
+ struct{
+ unsigned value : 29;
+ };
+ } tConfig;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ScanSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ConvertRate(unsigned int value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ScanSize(tRioStatusCode *status) = 0;
+ virtual unsigned int readConfig_ConvertRate(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLoopTiming_IfaceConstants;
+
+ virtual unsigned int readLoopTiming(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumOversampleBitsElements = 8,
+ } tOversampleBits_IfaceConstants;
+
+ virtual void writeOversampleBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readOversampleBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumAverageBitsElements = 8,
+ } tAverageBits_IfaceConstants;
+
+ virtual void writeAverageBits(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readAverageBits(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumScanListElements = 8,
+ } tScanList_IfaceConstants;
+
+ virtual void writeScanList(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readScanList(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual signed int readOutput(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLatchOutput_IfaceConstants;
+
+ virtual void strobeLatchOutput(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReadSelect_IfaceConstants;
+
+ virtual void writeReadSelect(tReadSelect value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeReadSelect_Averaged(bool value, tRioStatusCode *status) = 0;
+ virtual tReadSelect readReadSelect(tRioStatusCode *status) = 0;
+ virtual unsigned char readReadSelect_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readReadSelect_Module(tRioStatusCode *status) = 0;
+ virtual bool readReadSelect_Averaged(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAI(const tAI&);
+ void operator=(const tAI&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_AI_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAccumulator.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAccumulator.h
new file mode 100644
index 0000000..1a0972a
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAccumulator.h
@@ -0,0 +1,87 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Accumulator_h__
+#define __nFRC_2012_1_6_4_Accumulator_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAccumulator
+{
+public:
+ tAccumulator(){}
+ virtual ~tAccumulator(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAccumulator* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+ signed long long Value;
+ unsigned Count : 32;
+ };
+ struct{
+ unsigned value : 32;
+ unsigned value2 : 32;
+ unsigned value3 : 32;
+ };
+ } tOutput;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual signed long long readOutput_Value(tRioStatusCode *status) = 0;
+ virtual unsigned int readOutput_Count(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tCenter_IfaceConstants;
+
+ virtual void writeCenter(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readCenter(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDeadband_IfaceConstants;
+
+ virtual void writeDeadband(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readDeadband(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tAccumulator(const tAccumulator&);
+ void operator=(const tAccumulator&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Accumulator_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAlarm.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAlarm.h
new file mode 100644
index 0000000..f3eb33f
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAlarm.h
@@ -0,0 +1,57 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Alarm_h__
+#define __nFRC_2012_1_6_4_Alarm_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAlarm
+{
+public:
+ tAlarm(){}
+ virtual ~tAlarm(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAlarm* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tEnable_IfaceConstants;
+
+ virtual void writeEnable(bool value, tRioStatusCode *status) = 0;
+ virtual bool readEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTriggerTime_IfaceConstants;
+
+ virtual void writeTriggerTime(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readTriggerTime(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAlarm(const tAlarm&);
+ void operator=(const tAlarm&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Alarm_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAnalogTrigger.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAnalogTrigger.h
new file mode 100644
index 0000000..43150f7
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tAnalogTrigger.h
@@ -0,0 +1,133 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_AnalogTrigger_h__
+#define __nFRC_2012_1_6_4_AnalogTrigger_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tAnalogTrigger
+{
+public:
+ tAnalogTrigger(){}
+ virtual ~tAnalogTrigger(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tAnalogTrigger* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned InHysteresis : 1;
+ unsigned OverLimit : 1;
+ unsigned Rising : 1;
+ unsigned Falling : 1;
+#else
+ unsigned Falling : 1;
+ unsigned Rising : 1;
+ unsigned OverLimit : 1;
+ unsigned InHysteresis : 1;
+#endif
+ };
+ struct{
+ unsigned value : 4;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Channel : 3;
+ unsigned Module : 1;
+ unsigned Averaged : 1;
+ unsigned Filter : 1;
+ unsigned FloatingRollover : 1;
+ signed RolloverLimit : 8;
+#else
+ signed RolloverLimit : 8;
+ unsigned FloatingRollover : 1;
+ unsigned Filter : 1;
+ unsigned Averaged : 1;
+ unsigned Module : 1;
+ unsigned Channel : 3;
+#endif
+ };
+ struct{
+ unsigned value : 15;
+ };
+ } tSourceSelect;
+
+
+ typedef enum
+ {
+ } tSourceSelect_IfaceConstants;
+
+ virtual void writeSourceSelect(tSourceSelect value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Averaged(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_Filter(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_FloatingRollover(bool value, tRioStatusCode *status) = 0;
+ virtual void writeSourceSelect_RolloverLimit(signed short value, tRioStatusCode *status) = 0;
+ virtual tSourceSelect readSourceSelect(tRioStatusCode *status) = 0;
+ virtual unsigned char readSourceSelect_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readSourceSelect_Module(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_Averaged(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_Filter(tRioStatusCode *status) = 0;
+ virtual bool readSourceSelect_FloatingRollover(tRioStatusCode *status) = 0;
+ virtual signed short readSourceSelect_RolloverLimit(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tUpperLimit_IfaceConstants;
+
+ virtual void writeUpperLimit(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readUpperLimit(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLowerLimit_IfaceConstants;
+
+ virtual void writeLowerLimit(signed int value, tRioStatusCode *status) = 0;
+ virtual signed int readLowerLimit(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ kNumOutputElements = 8,
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_InHysteresis(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_OverLimit(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_Rising(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readOutput_Falling(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tAnalogTrigger(const tAnalogTrigger&);
+ void operator=(const tAnalogTrigger&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_AnalogTrigger_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tCounter.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tCounter.h
new file mode 100644
index 0000000..b23a7f0
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tCounter.h
@@ -0,0 +1,219 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Counter_h__
+#define __nFRC_2012_1_6_4_Counter_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tCounter
+{
+public:
+ tCounter(){}
+ virtual ~tCounter(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tCounter* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Direction : 1;
+ signed Value : 31;
+#else
+ signed Value : 31;
+ unsigned Direction : 1;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned UpSource_Channel : 4;
+ unsigned UpSource_Module : 1;
+ unsigned UpSource_AnalogTrigger : 1;
+ unsigned DownSource_Channel : 4;
+ unsigned DownSource_Module : 1;
+ unsigned DownSource_AnalogTrigger : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned UpRisingEdge : 1;
+ unsigned UpFallingEdge : 1;
+ unsigned DownRisingEdge : 1;
+ unsigned DownFallingEdge : 1;
+ unsigned Mode : 2;
+ unsigned PulseLengthThreshold : 6;
+ unsigned Enable : 1;
+#else
+ unsigned Enable : 1;
+ unsigned PulseLengthThreshold : 6;
+ unsigned Mode : 2;
+ unsigned DownFallingEdge : 1;
+ unsigned DownRisingEdge : 1;
+ unsigned UpFallingEdge : 1;
+ unsigned UpRisingEdge : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned DownSource_AnalogTrigger : 1;
+ unsigned DownSource_Module : 1;
+ unsigned DownSource_Channel : 4;
+ unsigned UpSource_AnalogTrigger : 1;
+ unsigned UpSource_Module : 1;
+ unsigned UpSource_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Period : 23;
+ signed Count : 8;
+ unsigned Stalled : 1;
+#else
+ unsigned Stalled : 1;
+ signed Count : 8;
+ unsigned Period : 23;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned StallPeriod : 24;
+ unsigned AverageSize : 7;
+ unsigned UpdateWhenEmpty : 1;
+#else
+ unsigned UpdateWhenEmpty : 1;
+ unsigned AverageSize : 7;
+ unsigned StallPeriod : 24;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerConfig;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual bool readOutput_Direction(tRioStatusCode *status) = 0;
+ virtual signed int readOutput_Value(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpRisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_UpFallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownRisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DownFallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Mode(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_PulseLengthThreshold(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_UpSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_UpSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_DownSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_DownSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpRisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_UpFallingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownRisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DownFallingEdge(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Mode(tRioStatusCode *status) = 0;
+ virtual unsigned short readConfig_PulseLengthThreshold(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerOutput_IfaceConstants;
+
+ virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;
+ virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;
+ virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerConfig_IfaceConstants;
+
+ virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;
+ virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;
+ virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;
+ virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tCounter(const tCounter&);
+ void operator=(const tCounter&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Counter_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDIO.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDIO.h
new file mode 100644
index 0000000..babb691
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDIO.h
@@ -0,0 +1,330 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_DIO_h__
+#define __nFRC_2012_1_6_4_DIO_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tDIO
+{
+public:
+ tDIO(){}
+ virtual ~tDIO(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tDIO* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 2,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Period : 16;
+ unsigned MinHigh : 16;
+#else
+ unsigned MinHigh : 16;
+ unsigned Period : 16;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tPWMConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned RelayFwd : 8;
+ unsigned RelayRev : 8;
+ unsigned I2CHeader : 4;
+#else
+ unsigned I2CHeader : 4;
+ unsigned RelayRev : 8;
+ unsigned RelayFwd : 8;
+#endif
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tSlowValue;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Transaction : 1;
+ unsigned Done : 1;
+ unsigned Aborted : 1;
+ unsigned DataReceivedHigh : 24;
+#else
+ unsigned DataReceivedHigh : 24;
+ unsigned Aborted : 1;
+ unsigned Done : 1;
+ unsigned Transaction : 1;
+#endif
+ };
+ struct{
+ unsigned value : 27;
+ };
+ } tI2CStatus;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Address : 8;
+ unsigned BytesToRead : 3;
+ unsigned BytesToWrite : 3;
+ unsigned DataToSendHigh : 16;
+ unsigned BitwiseHandshake : 1;
+#else
+ unsigned BitwiseHandshake : 1;
+ unsigned DataToSendHigh : 16;
+ unsigned BytesToWrite : 3;
+ unsigned BytesToRead : 3;
+ unsigned Address : 8;
+#endif
+ };
+ struct{
+ unsigned value : 31;
+ };
+ } tI2CConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned PeriodPower : 4;
+ unsigned OutputSelect_0 : 4;
+ unsigned OutputSelect_1 : 4;
+ unsigned OutputSelect_2 : 4;
+ unsigned OutputSelect_3 : 4;
+#else
+ unsigned OutputSelect_3 : 4;
+ unsigned OutputSelect_2 : 4;
+ unsigned OutputSelect_1 : 4;
+ unsigned OutputSelect_0 : 4;
+ unsigned PeriodPower : 4;
+#endif
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tDO_PWMConfig;
+
+
+ typedef enum
+ {
+ kNumFilterSelectElements = 16,
+ } tFilterSelect_IfaceConstants;
+
+ virtual void writeFilterSelect(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readFilterSelect(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CDataToSend_IfaceConstants;
+
+ virtual void writeI2CDataToSend(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readI2CDataToSend(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO_IfaceConstants;
+
+ virtual void writeDO(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readDO(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumFilterPeriodElements = 3,
+ } tFilterPeriod_IfaceConstants;
+
+ virtual void writeFilterPeriod(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readFilterPeriod(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tOutputEnable_IfaceConstants;
+
+ virtual void writeOutputEnable(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readOutputEnable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPulse_IfaceConstants;
+
+ virtual void writePulse(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readPulse(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tSlowValue_IfaceConstants;
+
+ virtual void writeSlowValue(tSlowValue value, tRioStatusCode *status) = 0;
+ virtual void writeSlowValue_RelayFwd(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSlowValue_RelayRev(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeSlowValue_I2CHeader(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tSlowValue readSlowValue(tRioStatusCode *status) = 0;
+ virtual unsigned char readSlowValue_RelayFwd(tRioStatusCode *status) = 0;
+ virtual unsigned char readSlowValue_RelayRev(tRioStatusCode *status) = 0;
+ virtual unsigned char readSlowValue_I2CHeader(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CStatus_IfaceConstants;
+
+ virtual tI2CStatus readI2CStatus(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CStatus_Transaction(tRioStatusCode *status) = 0;
+ virtual bool readI2CStatus_Done(tRioStatusCode *status) = 0;
+ virtual bool readI2CStatus_Aborted(tRioStatusCode *status) = 0;
+ virtual unsigned int readI2CStatus_DataReceivedHigh(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CDataReceived_IfaceConstants;
+
+ virtual unsigned int readI2CDataReceived(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDI_IfaceConstants;
+
+ virtual unsigned short readDI(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPulseLength_IfaceConstants;
+
+ virtual void writePulseLength(unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPulseLength(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumPWMPeriodScaleElements = 10,
+ } tPWMPeriodScale_IfaceConstants;
+
+ virtual void writePWMPeriodScale(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMPeriodScale(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumDO_PWMDutyCycleElements = 4,
+ } tDO_PWMDutyCycle_IfaceConstants;
+
+ virtual void writeDO_PWMDutyCycle(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMDutyCycle(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tBFL_IfaceConstants;
+
+ virtual void writeBFL(bool value, tRioStatusCode *status) = 0;
+ virtual bool readBFL(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CConfig_IfaceConstants;
+
+ virtual void writeI2CConfig(tI2CConfig value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_Address(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_BytesToRead(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_BytesToWrite(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_DataToSendHigh(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writeI2CConfig_BitwiseHandshake(bool value, tRioStatusCode *status) = 0;
+ virtual tI2CConfig readI2CConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CConfig_Address(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CConfig_BytesToRead(tRioStatusCode *status) = 0;
+ virtual unsigned char readI2CConfig_BytesToWrite(tRioStatusCode *status) = 0;
+ virtual unsigned short readI2CConfig_DataToSendHigh(tRioStatusCode *status) = 0;
+ virtual bool readI2CConfig_BitwiseHandshake(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDO_PWMConfig_IfaceConstants;
+
+ virtual void writeDO_PWMConfig(tDO_PWMConfig value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_PeriodPower(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_0(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_1(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_2(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeDO_PWMConfig_OutputSelect_3(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tDO_PWMConfig readDO_PWMConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_PeriodPower(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_0(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_1(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_2(tRioStatusCode *status) = 0;
+ virtual unsigned char readDO_PWMConfig_OutputSelect_3(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tI2CStart_IfaceConstants;
+
+ virtual void strobeI2CStart(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ } tLoopTiming_IfaceConstants;
+
+ virtual unsigned short readLoopTiming(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tPWMConfig_IfaceConstants;
+
+ virtual void writePWMConfig(tPWMConfig value, tRioStatusCode *status) = 0;
+ virtual void writePWMConfig_Period(unsigned short value, tRioStatusCode *status) = 0;
+ virtual void writePWMConfig_MinHigh(unsigned short value, tRioStatusCode *status) = 0;
+ virtual tPWMConfig readPWMConfig(tRioStatusCode *status) = 0;
+ virtual unsigned short readPWMConfig_Period(tRioStatusCode *status) = 0;
+ virtual unsigned short readPWMConfig_MinHigh(tRioStatusCode *status) = 0;
+
+
+
+ typedef enum
+ {
+ kNumPWMValueRegisters = 10,
+ } tPWMValue_IfaceConstants;
+
+ virtual void writePWMValue(unsigned char reg_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readPWMValue(unsigned char reg_index, tRioStatusCode *status) = 0;
+
+
+
+private:
+ tDIO(const tDIO&);
+ void operator=(const tDIO&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_DIO_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDMA.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDMA.h
new file mode 100644
index 0000000..006ec60
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tDMA.h
@@ -0,0 +1,188 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_DMA_h__
+#define __nFRC_2012_1_6_4_DMA_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tDMA
+{
+public:
+ tDMA(){}
+ virtual ~tDMA(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tDMA* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Pause : 1;
+ unsigned Enable_AI0_Low : 1;
+ unsigned Enable_AI0_High : 1;
+ unsigned Enable_AIAveraged0_Low : 1;
+ unsigned Enable_AIAveraged0_High : 1;
+ unsigned Enable_AI1_Low : 1;
+ unsigned Enable_AI1_High : 1;
+ unsigned Enable_AIAveraged1_Low : 1;
+ unsigned Enable_AIAveraged1_High : 1;
+ unsigned Enable_Accumulator0 : 1;
+ unsigned Enable_Accumulator1 : 1;
+ unsigned Enable_DI : 1;
+ unsigned Enable_AnalogTriggers : 1;
+ unsigned Enable_Counters_Low : 1;
+ unsigned Enable_Counters_High : 1;
+ unsigned Enable_CounterTimers_Low : 1;
+ unsigned Enable_CounterTimers_High : 1;
+ unsigned Enable_Encoders : 1;
+ unsigned Enable_EncoderTimers : 1;
+ unsigned ExternalClock : 1;
+#else
+ unsigned ExternalClock : 1;
+ unsigned Enable_EncoderTimers : 1;
+ unsigned Enable_Encoders : 1;
+ unsigned Enable_CounterTimers_High : 1;
+ unsigned Enable_CounterTimers_Low : 1;
+ unsigned Enable_Counters_High : 1;
+ unsigned Enable_Counters_Low : 1;
+ unsigned Enable_AnalogTriggers : 1;
+ unsigned Enable_DI : 1;
+ unsigned Enable_Accumulator1 : 1;
+ unsigned Enable_Accumulator0 : 1;
+ unsigned Enable_AIAveraged1_High : 1;
+ unsigned Enable_AIAveraged1_Low : 1;
+ unsigned Enable_AI1_High : 1;
+ unsigned Enable_AI1_Low : 1;
+ unsigned Enable_AIAveraged0_High : 1;
+ unsigned Enable_AIAveraged0_Low : 1;
+ unsigned Enable_AI0_High : 1;
+ unsigned Enable_AI0_Low : 1;
+ unsigned Pause : 1;
+#endif
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ExternalClockSource_Channel : 4;
+ unsigned ExternalClockSource_Module : 1;
+ unsigned ExternalClockSource_AnalogTrigger : 1;
+ unsigned RisingEdge : 1;
+ unsigned FallingEdge : 1;
+#else
+ unsigned FallingEdge : 1;
+ unsigned RisingEdge : 1;
+ unsigned ExternalClockSource_AnalogTrigger : 1;
+ unsigned ExternalClockSource_Module : 1;
+ unsigned ExternalClockSource_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 8;
+ };
+ } tExternalTriggers;
+
+
+
+ typedef enum
+ {
+ } tRate_IfaceConstants;
+
+ virtual void writeRate(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readRate(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Pause(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI0_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI0_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged0_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged0_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI1_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AI1_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged1_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AIAveraged1_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Accumulator0(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Accumulator1(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_DI(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_AnalogTriggers(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Counters_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Counters_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_CounterTimers_Low(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_CounterTimers_High(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_Encoders(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable_EncoderTimers(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ExternalClock(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Pause(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI0_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI0_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged0_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged0_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI1_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AI1_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged1_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AIAveraged1_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Accumulator0(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Accumulator1(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_DI(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_AnalogTriggers(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Counters_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Counters_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_CounterTimers_Low(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_CounterTimers_High(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_Encoders(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable_EncoderTimers(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ExternalClock(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ kNumExternalTriggersElements = 4,
+ } tExternalTriggers_IfaceConstants;
+
+ virtual void writeExternalTriggers(unsigned char bitfield_index, tExternalTriggers value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_RisingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual void writeExternalTriggers_FallingEdge(unsigned char bitfield_index, bool value, tRioStatusCode *status) = 0;
+ virtual tExternalTriggers readExternalTriggers(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual unsigned char readExternalTriggers_ExternalClockSource_Channel(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual unsigned char readExternalTriggers_ExternalClockSource_Module(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_ExternalClockSource_AnalogTrigger(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_RisingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+ virtual bool readExternalTriggers_FallingEdge(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tDMA(const tDMA&);
+ void operator=(const tDMA&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_DMA_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tEncoder.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tEncoder.h
new file mode 100644
index 0000000..7255920
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tEncoder.h
@@ -0,0 +1,199 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Encoder_h__
+#define __nFRC_2012_1_6_4_Encoder_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tEncoder
+{
+public:
+ tEncoder(){}
+ virtual ~tEncoder(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tEncoder* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 4,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Direction : 1;
+ signed Value : 31;
+#else
+ signed Value : 31;
+ unsigned Direction : 1;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ASource_Channel : 4;
+ unsigned ASource_Module : 1;
+ unsigned ASource_AnalogTrigger : 1;
+ unsigned BSource_Channel : 4;
+ unsigned BSource_Module : 1;
+ unsigned BSource_AnalogTrigger : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned Reverse : 1;
+ unsigned Enable : 1;
+#else
+ unsigned Enable : 1;
+ unsigned Reverse : 1;
+ unsigned IndexActiveHigh : 1;
+ unsigned IndexSource_AnalogTrigger : 1;
+ unsigned IndexSource_Module : 1;
+ unsigned IndexSource_Channel : 4;
+ unsigned BSource_AnalogTrigger : 1;
+ unsigned BSource_Module : 1;
+ unsigned BSource_Channel : 4;
+ unsigned ASource_AnalogTrigger : 1;
+ unsigned ASource_Module : 1;
+ unsigned ASource_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 21;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Period : 23;
+ signed Count : 8;
+ unsigned Stalled : 1;
+#else
+ unsigned Stalled : 1;
+ signed Count : 8;
+ unsigned Period : 23;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerOutput;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned StallPeriod : 24;
+ unsigned AverageSize : 7;
+ unsigned UpdateWhenEmpty : 1;
+#else
+ unsigned UpdateWhenEmpty : 1;
+ unsigned AverageSize : 7;
+ unsigned StallPeriod : 24;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tTimerConfig;
+
+
+ typedef enum
+ {
+ } tOutput_IfaceConstants;
+
+ virtual tOutput readOutput(tRioStatusCode *status) = 0;
+ virtual bool readOutput_Direction(tRioStatusCode *status) = 0;
+ virtual signed int readOutput_Value(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ASource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexSource_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_IndexActiveHigh(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Reverse(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Enable(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ASource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ASource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ASource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_BSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_IndexSource_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexSource_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_IndexActiveHigh(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Reverse(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Enable(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerOutput_IfaceConstants;
+
+ virtual tTimerOutput readTimerOutput(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerOutput_Period(tRioStatusCode *status) = 0;
+ virtual signed char readTimerOutput_Count(tRioStatusCode *status) = 0;
+ virtual bool readTimerOutput_Stalled(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimerConfig_IfaceConstants;
+
+ virtual void writeTimerConfig(tTimerConfig value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_StallPeriod(unsigned int value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_AverageSize(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeTimerConfig_UpdateWhenEmpty(bool value, tRioStatusCode *status) = 0;
+ virtual tTimerConfig readTimerConfig(tRioStatusCode *status) = 0;
+ virtual unsigned int readTimerConfig_StallPeriod(tRioStatusCode *status) = 0;
+ virtual unsigned char readTimerConfig_AverageSize(tRioStatusCode *status) = 0;
+ virtual bool readTimerConfig_UpdateWhenEmpty(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tEncoder(const tEncoder&);
+ void operator=(const tEncoder&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Encoder_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tGlobal.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tGlobal.h
new file mode 100644
index 0000000..0782f35
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tGlobal.h
@@ -0,0 +1,70 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Global_h__
+#define __nFRC_2012_1_6_4_Global_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tGlobal
+{
+public:
+ tGlobal(){}
+ virtual ~tGlobal(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tGlobal* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tVersion_IfaceConstants;
+
+ virtual unsigned short readVersion(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLocalTime_IfaceConstants;
+
+ virtual unsigned int readLocalTime(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tFPGA_LED_IfaceConstants;
+
+ virtual void writeFPGA_LED(bool value, tRioStatusCode *status) = 0;
+ virtual bool readFPGA_LED(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tRevision_IfaceConstants;
+
+ virtual unsigned int readRevision(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tGlobal(const tGlobal&);
+ void operator=(const tGlobal&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Global_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tInterrupt.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tInterrupt.h
new file mode 100644
index 0000000..40186e5
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tInterrupt.h
@@ -0,0 +1,93 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Interrupt_h__
+#define __nFRC_2012_1_6_4_Interrupt_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tInterrupt
+{
+public:
+ tInterrupt(){}
+ virtual ~tInterrupt(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tInterrupt* create(unsigned char sys_index, tRioStatusCode *status);
+ virtual unsigned char getSystemIndex() = 0;
+
+
+ typedef enum
+ {
+ kNumSystems = 8,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned Source_Channel : 4;
+ unsigned Source_Module : 1;
+ unsigned Source_AnalogTrigger : 1;
+ unsigned RisingEdge : 1;
+ unsigned FallingEdge : 1;
+ unsigned WaitForAck : 1;
+#else
+ unsigned WaitForAck : 1;
+ unsigned FallingEdge : 1;
+ unsigned RisingEdge : 1;
+ unsigned Source_AnalogTrigger : 1;
+ unsigned Source_Module : 1;
+ unsigned Source_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 9;
+ };
+ } tConfig;
+
+
+ typedef enum
+ {
+ } tTimeStamp_IfaceConstants;
+
+ virtual unsigned int readTimeStamp(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_Source_AnalogTrigger(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_RisingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_FallingEdge(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_WaitForAck(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Source_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_Source_Module(tRioStatusCode *status) = 0;
+ virtual bool readConfig_Source_AnalogTrigger(tRioStatusCode *status) = 0;
+ virtual bool readConfig_RisingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_FallingEdge(tRioStatusCode *status) = 0;
+ virtual bool readConfig_WaitForAck(tRioStatusCode *status) = 0;
+
+
+
+
+
+private:
+ tInterrupt(const tInterrupt&);
+ void operator=(const tInterrupt&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Interrupt_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSPI.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSPI.h
new file mode 100644
index 0000000..45c208c
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSPI.h
@@ -0,0 +1,228 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_SPI_h__
+#define __nFRC_2012_1_6_4_SPI_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tSPI
+{
+public:
+ tSPI(){}
+ virtual ~tSPI(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSPI* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned ReceivedDataOverflow : 1;
+ unsigned Idle : 1;
+#else
+ unsigned Idle : 1;
+ unsigned ReceivedDataOverflow : 1;
+#endif
+ };
+ struct{
+ unsigned value : 2;
+ };
+ } tStatus;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned BusBitWidth : 8;
+ unsigned ClockHalfPeriodDelay : 8;
+ unsigned MSBfirst : 1;
+ unsigned DataOnFalling : 1;
+ unsigned LatchFirst : 1;
+ unsigned LatchLast : 1;
+ unsigned FramePolarity : 1;
+ unsigned WriteOnly : 1;
+ unsigned ClockPolarity : 1;
+#else
+ unsigned ClockPolarity : 1;
+ unsigned WriteOnly : 1;
+ unsigned FramePolarity : 1;
+ unsigned LatchLast : 1;
+ unsigned LatchFirst : 1;
+ unsigned DataOnFalling : 1;
+ unsigned MSBfirst : 1;
+ unsigned ClockHalfPeriodDelay : 8;
+ unsigned BusBitWidth : 8;
+#endif
+ };
+ struct{
+ unsigned value : 23;
+ };
+ } tConfig;
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned SCLK_Channel : 4;
+ unsigned SCLK_Module : 1;
+ unsigned MOSI_Channel : 4;
+ unsigned MOSI_Module : 1;
+ unsigned MISO_Channel : 4;
+ unsigned MISO_Module : 1;
+ unsigned SS_Channel : 4;
+ unsigned SS_Module : 1;
+#else
+ unsigned SS_Module : 1;
+ unsigned SS_Channel : 4;
+ unsigned MISO_Module : 1;
+ unsigned MISO_Channel : 4;
+ unsigned MOSI_Module : 1;
+ unsigned MOSI_Channel : 4;
+ unsigned SCLK_Module : 1;
+ unsigned SCLK_Channel : 4;
+#endif
+ };
+ struct{
+ unsigned value : 20;
+ };
+ } tChannels;
+
+
+
+ typedef enum
+ {
+ } tStatus_IfaceConstants;
+
+ virtual tStatus readStatus(tRioStatusCode *status) = 0;
+ virtual bool readStatus_ReceivedDataOverflow(tRioStatusCode *status) = 0;
+ virtual bool readStatus_Idle(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReceivedData_IfaceConstants;
+
+ virtual unsigned int readReceivedData(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tDataToLoad_IfaceConstants;
+
+ virtual void writeDataToLoad(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readDataToLoad(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tConfig_IfaceConstants;
+
+ virtual void writeConfig(tConfig value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_BusBitWidth(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ClockHalfPeriodDelay(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_MSBfirst(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_DataOnFalling(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_LatchFirst(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_LatchLast(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_FramePolarity(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_WriteOnly(bool value, tRioStatusCode *status) = 0;
+ virtual void writeConfig_ClockPolarity(bool value, tRioStatusCode *status) = 0;
+ virtual tConfig readConfig(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_BusBitWidth(tRioStatusCode *status) = 0;
+ virtual unsigned char readConfig_ClockHalfPeriodDelay(tRioStatusCode *status) = 0;
+ virtual bool readConfig_MSBfirst(tRioStatusCode *status) = 0;
+ virtual bool readConfig_DataOnFalling(tRioStatusCode *status) = 0;
+ virtual bool readConfig_LatchFirst(tRioStatusCode *status) = 0;
+ virtual bool readConfig_LatchLast(tRioStatusCode *status) = 0;
+ virtual bool readConfig_FramePolarity(tRioStatusCode *status) = 0;
+ virtual bool readConfig_WriteOnly(tRioStatusCode *status) = 0;
+ virtual bool readConfig_ClockPolarity(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tClearReceivedData_IfaceConstants;
+
+ virtual void strobeClearReceivedData(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReceivedElements_IfaceConstants;
+
+ virtual unsigned short readReceivedElements(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tLoad_IfaceConstants;
+
+ virtual void strobeLoad(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReset_IfaceConstants;
+
+ virtual void strobeReset(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tChannels_IfaceConstants;
+
+ virtual void writeChannels(tChannels value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SCLK_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SCLK_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MOSI_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MOSI_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MISO_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_MISO_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SS_Channel(unsigned char value, tRioStatusCode *status) = 0;
+ virtual void writeChannels_SS_Module(unsigned char value, tRioStatusCode *status) = 0;
+ virtual tChannels readChannels(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SCLK_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SCLK_Module(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MOSI_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MOSI_Module(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MISO_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_MISO_Module(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SS_Channel(tRioStatusCode *status) = 0;
+ virtual unsigned char readChannels_SS_Module(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tAvailableToLoad_IfaceConstants;
+
+ virtual unsigned short readAvailableToLoad(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tReadReceivedData_IfaceConstants;
+
+ virtual void strobeReadReceivedData(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSPI(const tSPI&);
+ void operator=(const tSPI&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_SPI_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSolenoid.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSolenoid.h
new file mode 100644
index 0000000..8627eea
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSolenoid.h
@@ -0,0 +1,50 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Solenoid_h__
+#define __nFRC_2012_1_6_4_Solenoid_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tSolenoid
+{
+public:
+ tSolenoid(){}
+ virtual ~tSolenoid(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSolenoid* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ kNumDO7_0Elements = 2,
+ } tDO7_0_IfaceConstants;
+
+ virtual void writeDO7_0(unsigned char bitfield_index, unsigned char value, tRioStatusCode *status) = 0;
+ virtual unsigned char readDO7_0(unsigned char bitfield_index, tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSolenoid(const tSolenoid&);
+ void operator=(const tSolenoid&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Solenoid_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSysWatchdog.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSysWatchdog.h
new file mode 100644
index 0000000..2ef01ff
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tSysWatchdog.h
@@ -0,0 +1,71 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_SysWatchdog_h__
+#define __nFRC_2012_1_6_4_SysWatchdog_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tSysWatchdog
+{
+public:
+ tSysWatchdog(){}
+ virtual ~tSysWatchdog(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tSysWatchdog* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+
+
+
+ typedef enum
+ {
+ } tCommand_IfaceConstants;
+
+ virtual void writeCommand(unsigned short value, tRioStatusCode *status) = 0;
+ virtual unsigned short readCommand(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tChallenge_IfaceConstants;
+
+ virtual unsigned char readChallenge(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tActive_IfaceConstants;
+
+ virtual void writeActive(bool value, tRioStatusCode *status) = 0;
+ virtual bool readActive(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimer_IfaceConstants;
+
+ virtual unsigned int readTimer(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tSysWatchdog(const tSysWatchdog&);
+ void operator=(const tSysWatchdog&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_SysWatchdog_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tWatchdog.h b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tWatchdog.h
new file mode 100644
index 0000000..a589eda
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/nRuntimeFPGANamespace/tWatchdog.h
@@ -0,0 +1,108 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+// Do Not Edit... this file is generated!
+
+#ifndef __nFRC_2012_1_6_4_Watchdog_h__
+#define __nFRC_2012_1_6_4_Watchdog_h__
+
+#include "tSystemInterface.h"
+
+namespace nFPGA
+{
+namespace nFRC_2012_1_6_4
+{
+
+class tWatchdog
+{
+public:
+ tWatchdog(){}
+ virtual ~tWatchdog(){}
+
+ virtual tSystemInterface* getSystemInterface() = 0;
+ static tWatchdog* create(tRioStatusCode *status);
+
+ typedef enum
+ {
+ kNumSystems = 1,
+ } tIfaceConstants;
+
+ typedef
+ union{
+ struct{
+#ifdef __vxworks
+ unsigned SystemActive : 1;
+ unsigned Alive : 1;
+ unsigned SysDisableCount : 15;
+ unsigned DisableCount : 15;
+#else
+ unsigned DisableCount : 15;
+ unsigned SysDisableCount : 15;
+ unsigned Alive : 1;
+ unsigned SystemActive : 1;
+#endif
+ };
+ struct{
+ unsigned value : 32;
+ };
+ } tStatus;
+
+
+
+ typedef enum
+ {
+ } tStatus_IfaceConstants;
+
+ virtual tStatus readStatus(tRioStatusCode *status) = 0;
+ virtual bool readStatus_SystemActive(tRioStatusCode *status) = 0;
+ virtual bool readStatus_Alive(tRioStatusCode *status) = 0;
+ virtual unsigned short readStatus_SysDisableCount(tRioStatusCode *status) = 0;
+ virtual unsigned short readStatus_DisableCount(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tKill_IfaceConstants;
+
+ virtual void strobeKill(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tFeed_IfaceConstants;
+
+ virtual void strobeFeed(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tTimer_IfaceConstants;
+
+ virtual unsigned int readTimer(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tExpiration_IfaceConstants;
+
+ virtual void writeExpiration(unsigned int value, tRioStatusCode *status) = 0;
+ virtual unsigned int readExpiration(tRioStatusCode *status) = 0;
+
+
+ typedef enum
+ {
+ } tImmortal_IfaceConstants;
+
+ virtual void writeImmortal(bool value, tRioStatusCode *status) = 0;
+ virtual bool readImmortal(tRioStatusCode *status) = 0;
+
+
+
+
+private:
+ tWatchdog(const tWatchdog&);
+ void operator=(const tWatchdog&);
+};
+
+}
+}
+
+#endif // __nFRC_2012_1_6_4_Watchdog_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/printFpgaVersion.h b/hal/lib/Athena/FRC_FPGA_ChipObject/printFpgaVersion.h
new file mode 100644
index 0000000..788f1df
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/printFpgaVersion.h
@@ -0,0 +1,42 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __printFPGAVersion_h__
+#define __printFPGAVersion_h__
+
+namespace nFPGA
+{
+
+template<typename ttGlobal>
+inline void printFPGAVersion(ttGlobal &global)
+{
+ tRioStatusCode cleanStatus=0;
+ uint32_t hardwareGuid[4];
+ tSystemInterface &system = *global.getSystemInterface();
+ system.getHardwareFpgaSignature(hardwareGuid, &cleanStatus);
+ const uint32_t *softwareGuid = system.getExpectedFPGASignature();
+ printf("FPGA Hardware GUID: 0x");
+ for(int i=0; i<4; i++)
+ {
+ printf("%08X", hardwareGuid[i]);
+ }
+ printf("\n");
+ printf("FPGA Software GUID: 0x");
+ for(int i=0; i<4; i++)
+ {
+ printf("%08X", softwareGuid[i]);
+ }
+ printf("\n");
+ uint16_t fpgaHardwareVersion = global.readVersion(&cleanStatus);
+ uint16_t fpgaSoftwareVersion = system.getExpectedFPGAVersion();
+ printf("FPGA Hardware Version: %X\n", fpgaHardwareVersion);
+ printf("FPGA Software Version: %X\n", fpgaSoftwareVersion);
+ uint32_t fpgaHardwareRevision = global.readRevision(&cleanStatus);
+ uint32_t fpgaSoftwareRevision = system.getExpectedFPGARevision();
+ printf("FPGA Hardware Revision: %X.%X.%X\n", (fpgaHardwareRevision >> 20) & 0xFFF, (fpgaHardwareRevision >> 12) & 0xFF, fpgaHardwareRevision & 0xFFF);
+ printf("FPGA Software Revision: %X.%X.%X\n", (fpgaSoftwareRevision >> 20) & 0xFFF, (fpgaSoftwareRevision >> 12) & 0xFF, fpgaSoftwareRevision & 0xFFF);
+}
+
+}
+
+#endif // __printFPGAVersion_h__
+
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAChannelDescriptor.h b/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAChannelDescriptor.h
new file mode 100644
index 0000000..8fa5935
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAChannelDescriptor.h
@@ -0,0 +1,17 @@
+// Describes the information needed to configure a DMA channel.
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#include <stdint.h>
+
+#ifndef __tDMAChannelDescriptor_h__
+#define __tDMAChannelDescriptor_h__
+
+struct tDMAChannelDescriptor
+{
+ uint32_t channel;
+ uint32_t baseAddress;
+ uint32_t depth;
+ bool targetToHost;
+};
+
+#endif // __tDMAChannelDescriptor_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAManager.h b/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAManager.h
new file mode 100644
index 0000000..cb95203
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/tDMAManager.h
@@ -0,0 +1,41 @@
+// Class for handling DMA transfers.
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tDMAManager_h__
+#define __tDMAManager_h__
+
+#include "tSystem.h"
+#include <stdint.h>
+
+namespace nFPGA
+{
+class tDMAManager : public tSystem
+{
+public:
+ tDMAManager(uint32_t dmaChannel, uint32_t hostBufferSize, tRioStatusCode *status);
+ ~tDMAManager();
+ void start(tRioStatusCode *status);
+ void stop(tRioStatusCode *status);
+ bool isStarted() {return _started;}
+ void read(
+ uint32_t* buf,
+ size_t num,
+ uint32_t timeout,
+ size_t* remaining,
+ tRioStatusCode *status);
+ void write(
+ uint32_t* buf,
+ size_t num,
+ uint32_t timeout,
+ size_t* remaining,
+ tRioStatusCode *status);
+private:
+ bool _started;
+ uint32_t _dmaChannel;
+ uint32_t _hostBufferSize;
+
+};
+
+}
+
+#endif // __tDMAManager_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/tInterruptManager.h b/hal/lib/Athena/FRC_FPGA_ChipObject/tInterruptManager.h
new file mode 100644
index 0000000..cb6783d
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/tInterruptManager.h
@@ -0,0 +1,61 @@
+// Class for handling interrupts.
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tInterruptManager_h__
+#define __tInterruptManager_h__
+
+#include "tSystem.h"
+
+namespace ni
+{
+ namespace dsc
+ {
+ namespace osdep
+ {
+ class CriticalSection;
+ }
+ }
+}
+
+namespace nFPGA
+{
+
+typedef void (*tInterruptHandler)(uint32_t interruptAssertedMask, void *param);
+
+class tInterruptManager : public tSystem
+{
+public:
+ tInterruptManager(uint32_t interruptMask, bool watcher, tRioStatusCode *status);
+ ~tInterruptManager();
+ void registerHandler(tInterruptHandler handler, void *param, tRioStatusCode *status);
+ uint32_t watch(int32_t timeoutInMs, bool ignorePrevious, tRioStatusCode *status);
+ void enable(tRioStatusCode *status);
+ void disable(tRioStatusCode *status);
+ bool isEnabled(tRioStatusCode *status);
+private:
+ class tInterruptThread;
+ friend class tInterruptThread;
+ void handler();
+ static int handlerWrapper(tInterruptManager *pInterrupt);
+
+ void acknowledge(tRioStatusCode *status);
+ void reserve(tRioStatusCode *status);
+ void unreserve(tRioStatusCode *status);
+ tInterruptHandler _handler;
+ uint32_t _interruptMask;
+ tInterruptThread *_thread;
+ NiFpga_IrqContext _rioContext;
+ bool _watcher;
+ bool _enabled;
+ void *_userParam;
+
+ // maintain the interrupts that are already dealt with.
+ static uint32_t _globalInterruptMask;
+ static ni::dsc::osdep::CriticalSection *_globalInterruptMaskSemaphore;
+};
+
+}
+
+
+#endif // __tInterruptManager_h__
+
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/tSystem.h b/hal/lib/Athena/FRC_FPGA_ChipObject/tSystem.h
new file mode 100644
index 0000000..b059e51
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/tSystem.h
@@ -0,0 +1,48 @@
+// Base class for generated chip objects
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tSystem_h__
+#define __tSystem_h__
+
+#include "fpgainterfacecapi/NiFpga.h"
+typedef NiFpga_Status tRioStatusCode;
+
+#define FRC_FPGA_PRELOAD_BITFILE
+
+typedef uint32_t NiFpga_Session;
+
+namespace nFPGA
+{
+
+class tSystem
+{
+public:
+ tSystem(tRioStatusCode *status);
+ ~tSystem();
+ void getFpgaGuid(uint32_t *guid_ptr, tRioStatusCode *status);
+ void reset(tRioStatusCode *status);
+
+protected:
+ static NiFpga_Session _DeviceHandle;
+
+#ifdef FRC_FPGA_PRELOAD_BITFILE
+ void NiFpga_SharedOpen_common(const char* bitfile);
+ NiFpga_Status NiFpga_SharedOpen(const char* bitfile,
+ const char* signature,
+ const char* resource,
+ uint32_t attribute,
+ NiFpga_Session* session);
+ NiFpga_Status NiFpgaLv_SharedOpen(const char* const bitfile,
+ const char* const apiSignature,
+ const char* const resource,
+ const uint32_t attribute,
+ NiFpga_Session* const session);
+private:
+ static char *_FileName;
+ static char *_Bitfile;
+#endif
+};
+
+}
+
+#endif // __tSystem_h__
diff --git a/hal/lib/Athena/FRC_FPGA_ChipObject/tSystemInterface.h b/hal/lib/Athena/FRC_FPGA_ChipObject/tSystemInterface.h
new file mode 100644
index 0000000..8594187
--- /dev/null
+++ b/hal/lib/Athena/FRC_FPGA_ChipObject/tSystemInterface.h
@@ -0,0 +1,27 @@
+// Copyright (c) National Instruments 2008. All Rights Reserved.
+
+#ifndef __tSystemInterface_h__
+#define __tSystemInterface_h__
+
+namespace nFPGA
+{
+
+class tSystemInterface
+{
+public:
+ tSystemInterface(){}
+ virtual ~tSystemInterface(){}
+
+ virtual const uint16_t getExpectedFPGAVersion()=0;
+ virtual const uint32_t getExpectedFPGARevision()=0;
+ virtual const uint32_t * const getExpectedFPGASignature()=0;
+ virtual void getHardwareFpgaSignature(uint32_t *guid_ptr, tRioStatusCode *status)=0;
+ virtual uint32_t getLVHandle(tRioStatusCode *status)=0;
+ virtual uint32_t getHandle()=0;
+ virtual void reset(tRioStatusCode *status)=0;
+};
+
+}
+
+#endif // __tSystemInterface_h__
+
diff --git a/hal/lib/Athena/FRC_NetworkCommunication/AICalibration.h b/hal/lib/Athena/FRC_NetworkCommunication/AICalibration.h
new file mode 100644
index 0000000..b2f366c
--- /dev/null
+++ b/hal/lib/Athena/FRC_NetworkCommunication/AICalibration.h
@@ -0,0 +1,19 @@
+
+#ifndef __AICalibration_h__
+#define __AICalibration_h__
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+ uint32_t FRC_NetworkCommunication_nAICalibration_getLSBWeight(const uint32_t aiSystemIndex, const uint32_t channel, int32_t *status);
+ int32_t FRC_NetworkCommunication_nAICalibration_getOffset(const uint32_t aiSystemIndex, const uint32_t channel, int32_t *status);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __AICalibration_h__
diff --git a/hal/lib/Athena/FRC_NetworkCommunication/CANInterfacePlugin.h b/hal/lib/Athena/FRC_NetworkCommunication/CANInterfacePlugin.h
new file mode 100644
index 0000000..77d992c
--- /dev/null
+++ b/hal/lib/Athena/FRC_NetworkCommunication/CANInterfacePlugin.h
@@ -0,0 +1,82 @@
+// CANInterfacePlugin.h
+//
+// Defines the API for building a CAN Interface Plugin to support
+// PWM-cable-free CAN motor control on FRC robots. This allows you
+// to connect any CAN interface to the secure Jaguar CAN driver.
+//
+
+#ifndef __CANInterfacePlugin_h__
+#define __CANInterfacePlugin_h__
+
+#include <stdint.h>
+
+#define CAN_IS_FRAME_REMOTE 0x80000000
+#define CAN_IS_FRAME_11BIT 0x40000000
+#define CAN_29BIT_MESSAGE_ID_MASK 0x1FFFFFFF
+#define CAN_11BIT_MESSAGE_ID_MASK 0x000007FF
+
+class CANInterfacePlugin
+{
+public:
+ CANInterfacePlugin() {}
+ virtual ~CANInterfacePlugin() {}
+
+ /**
+ * This entry-point of the CANInterfacePlugin is passed a message that the driver needs to send to
+ * a device on the CAN bus.
+ *
+ * This function may be called from multiple contexts and must therefore be reentrant.
+ *
+ * @param messageID The 29-bit CAN message ID in the lsbs. The msb can indicate a remote frame.
+ * @param data A pointer to a buffer containing between 0 and 8 bytes to send with the message. May be NULL if dataSize is 0.
+ * @param dataSize The number of bytes to send with the message.
+ * @return Return any error code. On success return 0.
+ */
+ virtual int32_t sendMessage(uint32_t messageID, const uint8_t *data, uint8_t dataSize) = 0;
+
+ /**
+ * This entry-point of the CANInterfacePlugin is passed buffers which should be populated with
+ * any received messages from devices on the CAN bus.
+ *
+ * This function is always called by a single task in the Jaguar driver, so it need not be reentrant.
+ *
+ * This function is expected to block for some period of time waiting for a message from the CAN bus.
+ * It may timeout periodically (returning non-zero to indicate no message was populated) to allow for
+ * shutdown and unloading of the plugin.
+ *
+ * @param messageID A reference to be populated with a received 29-bit CAN message ID in the lsbs.
+ * @param data A pointer to a buffer of 8 bytes to be populated with data received with the message.
+ * @param dataSize A reference to be populated with the size of the data received (0 - 8 bytes).
+ * @return This should return 0 if a message was populated, non-0 if no message was not populated.
+ */
+ virtual int32_t receiveMessage(uint32_t &messageID, uint8_t *data, uint8_t &dataSize) = 0;
+
+#if defined(__linux)
+ /**
+ * This entry-point of the CANInterfacePlugin returns status of the CAN bus.
+ *
+ * This function may be called from multiple contexts and must therefore be reentrant.
+ *
+ * This function will return detailed hardware status if available for diagnostics of the CAN interface.
+ *
+ * @param busOffCount The number of times that sendMessage failed with a busOff error indicating that messages
+ * are not successfully transmitted on the bus.
+ * @param txFullCount The number of times that sendMessage failed with a txFifoFull error indicating that messages
+ * are not successfully received by any CAN device.
+ * @param receiveErrorCount The count of receive errors as reported by the CAN driver.
+ * @param transmitErrorCount The count of transmit errors as reported by the CAN driver.
+ * @return This should return 0 if all status was retrieved successfully or an error code if not.
+ */
+ virtual int32_t getStatus(uint32_t &busOffCount, uint32_t &txFullCount, uint32_t &receiveErrorCount, uint32_t &transmitErrorCount) {return 0;}
+#endif
+};
+
+/**
+ * This function allows you to register a CANInterfacePlugin to provide access a CAN bus.
+ *
+ * @param interface A pointer to an object that inherits from CANInterfacePlugin and implements
+ * the pure virtual interface. If NULL, unregister the current plugin.
+ */
+void FRC_NetworkCommunication_CANSessionMux_registerInterface(CANInterfacePlugin* interface);
+
+#endif // __CANInterfacePlugin_h__
diff --git a/hal/lib/Athena/FRC_NetworkCommunication/CANSessionMux.h b/hal/lib/Athena/FRC_NetworkCommunication/CANSessionMux.h
new file mode 100644
index 0000000..d6fa822
--- /dev/null
+++ b/hal/lib/Athena/FRC_NetworkCommunication/CANSessionMux.h
@@ -0,0 +1,66 @@
+// CANSessionMux.h
+//
+// Defines the API for building a CAN Interface Plugin to support
+// PWM-cable-free CAN motor control on FRC robots. This allows you
+// to connect any CAN interface to the secure Jaguar CAN driver.
+//
+
+#ifndef __CANSessionMux_h__
+#define __CANSessionMux_h__
+
+#if defined(__vxworks)
+#include <vxWorks.h>
+#else
+#include <stdint.h>
+#endif
+
+#define CAN_SEND_PERIOD_NO_REPEAT 0
+#define CAN_SEND_PERIOD_STOP_REPEATING -1
+
+/* Flags in the upper bits of the messageID */
+#define CAN_IS_FRAME_REMOTE 0x80000000
+#define CAN_IS_FRAME_11BIT 0x40000000
+
+#define ERR_CANSessionMux_InvalidBuffer -44086
+#define ERR_CANSessionMux_MessageNotFound -44087
+#define WARN_CANSessionMux_NoToken 44087
+#define ERR_CANSessionMux_NotAllowed -44088
+#define ERR_CANSessionMux_NotInitialized -44089
+#define ERR_CANSessionMux_SessionOverrun 44050
+
+struct tCANStreamMessage{
+ uint32_t messageID;
+ uint32_t timeStamp;
+ uint8_t data[8];
+ uint8_t dataSize;
+};
+
+#ifdef __cplusplus
+namespace nCANSessionMux
+{
+ void sendMessage_wrapper(uint32_t messageID, const uint8_t *data, uint8_t dataSize, int32_t periodMs, int32_t *status);
+ void receiveMessage_wrapper(uint32_t *messageID, uint32_t messageIDMask, uint8_t *data, uint8_t *dataSize, uint32_t *timeStamp, int32_t *status);
+ void openStreamSession(uint32_t *sessionHandle, uint32_t messageID, uint32_t messageIDMask, uint32_t maxMessages, int32_t *status);
+ void closeStreamSession(uint32_t sessionHandle);
+ void readStreamSession(uint32_t sessionHandle, struct tCANStreamMessage *messages, uint32_t messagesToRead, uint32_t *messagesRead, int32_t *status);
+ void getCANStatus(float *percentBusUtilization, uint32_t *busOffCount, uint32_t *txFullCount, uint32_t *receiveErrorCount, uint32_t *transmitErrorCount, int32_t *status);
+}
+#endif
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+ void FRC_NetworkCommunication_CANSessionMux_sendMessage(uint32_t messageID, const uint8_t *data, uint8_t dataSize, int32_t periodMs, int32_t *status);
+ void FRC_NetworkCommunication_CANSessionMux_receiveMessage(uint32_t *messageID, uint32_t messageIDMask, uint8_t *data, uint8_t *dataSize, uint32_t *timeStamp, int32_t *status);
+ void FRC_NetworkCommunication_CANSessionMux_openStreamSession(uint32_t *sessionHandle, uint32_t messageID, uint32_t messageIDMask, uint32_t maxMessages, int32_t *status);
+ void FRC_NetworkCommunication_CANSessionMux_closeStreamSession(uint32_t sessionHandle);
+ void FRC_NetworkCommunication_CANSessionMux_readStreamSession(uint32_t sessionHandle, struct tCANStreamMessage *messages, uint32_t messagesToRead, uint32_t *messagesRead, int32_t *status);
+ void FRC_NetworkCommunication_CANSessionMux_getCANStatus(float *percentBusUtilization, uint32_t *busOffCount, uint32_t *txFullCount, uint32_t *receiveErrorCount, uint32_t *transmitErrorCount, int32_t *status);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __CANSessionMux_h__
diff --git a/hal/lib/Athena/FRC_NetworkCommunication/FRCComm.h b/hal/lib/Athena/FRC_NetworkCommunication/FRCComm.h
new file mode 100644
index 0000000..b0bd83f
--- /dev/null
+++ b/hal/lib/Athena/FRC_NetworkCommunication/FRCComm.h
@@ -0,0 +1,163 @@
+/*************************************************************
+ * NOTICE
+ *
+ * These are the only externally exposed functions to the
+ * NetworkCommunication library
+ *
+ * This is an implementation of FRC Spec for Comm Protocol
+ * Revision 4.5, June 30, 2008
+ *
+ * Copyright (c) National Instruments 2008. All Rights Reserved.
+ *
+ *************************************************************/
+
+#ifndef __FRC_COMM_H__
+#define __FRC_COMM_H__
+
+#ifdef WIN32
+# include <vxWorks_compat.h>
+#ifdef USE_THRIFT
+# define EXPORT_FUNC
+# else
+# define EXPORT_FUNC __declspec(dllexport) __cdecl
+# endif
+#elif defined(__vxworks)
+# include <vxWorks.h>
+# define EXPORT_FUNC
+#elif defined(__linux)
+# include <stdint.h>
+# include <pthread.h>
+# define EXPORT_FUNC
+#endif
+
+#define ERR_FRCSystem_NetCommNotResponding -44049
+#define ERR_FRCSystem_NoDSConnection -44018
+
+#ifdef WIN32
+# define __DEPRECATED__ __declspec(deprecated)
+#else
+# define __DEPRECATED__ __attribute__((__deprecated__))
+#endif
+
+enum AllianceStationID_t {
+ kAllianceStationID_red1,
+ kAllianceStationID_red2,
+ kAllianceStationID_red3,
+ kAllianceStationID_blue1,
+ kAllianceStationID_blue2,
+ kAllianceStationID_blue3,
+};
+
+enum MatchType_t {
+ kMatchType_none,
+ kMatchType_practice,
+ kMatchType_qualification,
+ kMatchType_elimination,
+};
+
+struct ControlWord_t {
+#ifndef __vxworks
+ uint32_t enabled : 1;
+ uint32_t autonomous : 1;
+ uint32_t test :1;
+ uint32_t eStop : 1;
+ uint32_t fmsAttached:1;
+ uint32_t dsAttached:1;
+ uint32_t control_reserved : 26;
+#else
+ uint32_t control_reserved : 26;
+ uint32_t dsAttached:1;
+ uint32_t fmsAttached:1;
+ uint32_t eStop : 1;
+ uint32_t test :1;
+ uint32_t autonomous : 1;
+ uint32_t enabled : 1;
+#endif
+};
+
+struct JoystickAxes_t {
+ uint16_t count;
+ int16_t axes[1];
+};
+
+struct JoystickPOV_t {
+ uint16_t count;
+ int16_t povs[1];
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+ int EXPORT_FUNC FRC_NetworkCommunication_Reserve(void *instance);
+#ifndef SIMULATION
+ void EXPORT_FUNC getFPGAHardwareVersion(uint16_t *fpgaVersion, uint32_t *fpgaRevision);
+#endif
+ /**
+ * Safely copy data into the status packet to be sent back to the driver station.
+ * @deprecated battery is the only parameter to this function that is still used, and only on cRIO / simulation.
+ */
+ __DEPRECATED__ int EXPORT_FUNC setStatusData(float battery, uint8_t dsDigitalOut, uint8_t updateNumber,
+ const char *userDataHigh, int userDataHighLength,
+ const char *userDataLow, int userDataLowLength, int wait_ms);
+ /**
+ * Send error data to the DS
+ * @deprecated This old method is hard to parse on the DS side. It will be removed soon. Use FRC_NetworkCommunication_sendError instead.
+ * @param errorData is a cstr of the error message
+ * @param errorDataLength is the length of the errorData
+ * @param wait_ms is ignored (included for binary compatibility)
+ * @return 0 on success, 1 on no DS connection
+ */
+ __DEPRECATED__ int EXPORT_FUNC setErrorData(const char *errors, int errorsLength, int wait_ms);
+
+ /**
+ * Send a console output line to the Driver Station
+ * @param line a null-terminated string
+ * @return 0 on success, other on failure
+ */
+ int EXPORT_FUNC FRC_NetworkCommunication_sendConsoleLine(const char *line);
+
+ /**
+ * Send an error to the Driver Station
+ * @param isError true if error, false if warning
+ * @param errorCode value of error condition
+ * @param isLVCode true if error code is defined in errors.txt, false if not (i.e. made up for C++)
+ * @param details error description that contains details such as which resource number caused the failure
+ * @param location Source file, function, and line number that the error was generated - optional
+ * @param callStack The details about what functions were called through before the error was reported - optional
+ * @return 0 on success, other on failure
+ */
+ int EXPORT_FUNC FRC_NetworkCommunication_sendError(int isError, int32_t errorCode, int isLVCode,
+ const char *details, const char *location, const char *callStack);
+
+#ifdef WIN32
+ void EXPORT_FUNC setNewDataSem(HANDLE);
+#elif defined (__vxworks)
+ void EXPORT_FUNC setNewDataSem(SEM_ID);
+#else
+ void EXPORT_FUNC setNewDataSem(pthread_cond_t *);
+#endif
+
+ // this uint32_t is really a LVRefNum
+ int EXPORT_FUNC setNewDataOccurRef(uint32_t refnum);
+
+ int EXPORT_FUNC FRC_NetworkCommunication_getControlWord(struct ControlWord_t *controlWord);
+ int EXPORT_FUNC FRC_NetworkCommunication_getAllianceStation(enum AllianceStationID_t *allianceStation);
+ int EXPORT_FUNC FRC_NetworkCommunication_getMatchTime(float *matchTime);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickAxes(uint8_t joystickNum, struct JoystickAxes_t *axes, uint8_t maxAxes);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickButtons(uint8_t joystickNum, uint32_t *buttons, uint8_t *count);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickPOVs(uint8_t joystickNum, struct JoystickPOV_t *povs, uint8_t maxPOVs);
+ int EXPORT_FUNC FRC_NetworkCommunication_setJoystickOutputs(uint8_t joystickNum, uint32_t hidOutputs, uint16_t leftRumble, uint16_t rightRumble);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickDesc(uint8_t joystickNum, uint8_t *isXBox, uint8_t *type, char *name,
+ uint8_t *axisCount, uint8_t *axisTypes, uint8_t *buttonCount, uint8_t *povCount);
+
+ void EXPORT_FUNC FRC_NetworkCommunication_getVersionString(char *version);
+ int EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramStarting(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramDisabled(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramAutonomous(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramTeleop(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramTest(void);
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/hal/lib/Athena/FRC_NetworkCommunication/LoadOut.h b/hal/lib/Athena/FRC_NetworkCommunication/LoadOut.h
new file mode 100644
index 0000000..cd02537
--- /dev/null
+++ b/hal/lib/Athena/FRC_NetworkCommunication/LoadOut.h
@@ -0,0 +1,58 @@
+
+#ifndef __LoadOut_h__
+#define __LoadOut_h__
+
+#ifdef WIN32
+#include <vxWorks_compat.h>
+#define EXPORT_FUNC __declspec(dllexport) __cdecl
+#elif defined (__vxworks)
+#include <vxWorks.h>
+#define EXPORT_FUNC
+#else
+#include <stdint.h>
+#define EXPORT_FUNC
+#endif
+
+#define kMaxModuleNumber 2
+namespace nLoadOut
+{
+#if defined(__vxworks) || defined(SIMULATION)
+ typedef enum {
+ kModuleType_Unknown = 0x00,
+ kModuleType_Analog = 0x01,
+ kModuleType_Digital = 0x02,
+ kModuleType_Solenoid = 0x03,
+ } tModuleType;
+ bool EXPORT_FUNC getModulePresence(tModuleType moduleType, uint8_t moduleNumber);
+#endif
+ typedef enum {
+ kTargetClass_Unknown = 0x00,
+ kTargetClass_FRC1 = 0x10,
+ kTargetClass_FRC2 = 0x20,
+ kTargetClass_FRC3 = 0x30,
+ kTargetClass_RoboRIO = 0x40,
+#if defined(__vxworks) || defined(SIMULATION)
+ kTargetClass_FRC2_Analog = kTargetClass_FRC2 | kModuleType_Analog,
+ kTargetClass_FRC2_Digital = kTargetClass_FRC2 | kModuleType_Digital,
+ kTargetClass_FRC2_Solenoid = kTargetClass_FRC2 | kModuleType_Solenoid,
+#endif
+ kTargetClass_FamilyMask = 0xF0,
+ kTargetClass_ModuleMask = 0x0F,
+ } tTargetClass;
+ tTargetClass EXPORT_FUNC getTargetClass();
+}
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#if defined(__vxworks) || defined(SIMULATION)
+ uint32_t EXPORT_FUNC FRC_NetworkCommunication_nLoadOut_getModulePresence(uint32_t moduleType, uint8_t moduleNumber);
+#endif
+ uint32_t EXPORT_FUNC FRC_NetworkCommunication_nLoadOut_getTargetClass();
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __LoadOut_h__
diff --git a/hal/lib/Athena/FRC_NetworkCommunication/UsageReporting.h b/hal/lib/Athena/FRC_NetworkCommunication/UsageReporting.h
new file mode 100644
index 0000000..17d5874
--- /dev/null
+++ b/hal/lib/Athena/FRC_NetworkCommunication/UsageReporting.h
@@ -0,0 +1,149 @@
+
+#ifndef __UsageReporting_h__
+#define __UsageReporting_h__
+
+#ifdef WIN32
+#include <vxWorks_compat.h>
+#define EXPORT_FUNC __declspec(dllexport) __cdecl
+#elif defined (__vxworks)
+#include <vxWorks.h>
+#define EXPORT_FUNC
+#else
+#include <stdint.h>
+#include <stdlib.h>
+#define EXPORT_FUNC
+#endif
+
+#define kUsageReporting_version 1
+
+namespace nUsageReporting
+{
+ typedef enum
+ {
+ kResourceType_Controller,
+ kResourceType_Module,
+ kResourceType_Language,
+ kResourceType_CANPlugin,
+ kResourceType_Accelerometer,
+ kResourceType_ADXL345,
+ kResourceType_AnalogChannel,
+ kResourceType_AnalogTrigger,
+ kResourceType_AnalogTriggerOutput,
+ kResourceType_CANJaguar,
+ kResourceType_Compressor,
+ kResourceType_Counter,
+ kResourceType_Dashboard,
+ kResourceType_DigitalInput,
+ kResourceType_DigitalOutput,
+ kResourceType_DriverStationCIO,
+ kResourceType_DriverStationEIO,
+ kResourceType_DriverStationLCD,
+ kResourceType_Encoder,
+ kResourceType_GearTooth,
+ kResourceType_Gyro,
+ kResourceType_I2C,
+ kResourceType_Framework,
+ kResourceType_Jaguar,
+ kResourceType_Joystick,
+ kResourceType_Kinect,
+ kResourceType_KinectStick,
+ kResourceType_PIDController,
+ kResourceType_Preferences,
+ kResourceType_PWM,
+ kResourceType_Relay,
+ kResourceType_RobotDrive,
+ kResourceType_SerialPort,
+ kResourceType_Servo,
+ kResourceType_Solenoid,
+ kResourceType_SPI,
+ kResourceType_Task,
+ kResourceType_Ultrasonic,
+ kResourceType_Victor,
+ kResourceType_Button,
+ kResourceType_Command,
+ kResourceType_AxisCamera,
+ kResourceType_PCVideoServer,
+ kResourceType_SmartDashboard,
+ kResourceType_Talon,
+ kResourceType_HiTechnicColorSensor,
+ kResourceType_HiTechnicAccel,
+ kResourceType_HiTechnicCompass,
+ kResourceType_SRF08,
+ kResourceType_AnalogOutput,
+ kResourceType_VictorSP,
+ kResourceType_TalonSRX,
+ kResourceType_CANTalonSRX,
+ kResourceType_ADXL362,
+ kResourceType_ADXRS450,
+ kResourceType_RevSPARK,
+ kResourceType_MindsensorsSD540,
+ kResourceType_DigitalFilter,
+ } tResourceType;
+
+ typedef enum
+ {
+ kLanguage_LabVIEW = 1,
+ kLanguage_CPlusPlus = 2,
+ kLanguage_Java = 3,
+ kLanguage_Python = 4,
+
+ kCANPlugin_BlackJagBridge = 1,
+ kCANPlugin_2CAN = 2,
+
+ kFramework_Iterative = 1,
+ kFramework_Simple = 2,
+ kFramework_CommandControl = 3,
+
+ kRobotDrive_ArcadeStandard = 1,
+ kRobotDrive_ArcadeButtonSpin = 2,
+ kRobotDrive_ArcadeRatioCurve = 3,
+ kRobotDrive_Tank = 4,
+ kRobotDrive_MecanumPolar = 5,
+ kRobotDrive_MecanumCartesian = 6,
+
+ kDriverStationCIO_Analog = 1,
+ kDriverStationCIO_DigitalIn = 2,
+ kDriverStationCIO_DigitalOut = 3,
+
+ kDriverStationEIO_Acceleration = 1,
+ kDriverStationEIO_AnalogIn = 2,
+ kDriverStationEIO_AnalogOut = 3,
+ kDriverStationEIO_Button = 4,
+ kDriverStationEIO_LED = 5,
+ kDriverStationEIO_DigitalIn = 6,
+ kDriverStationEIO_DigitalOut = 7,
+ kDriverStationEIO_FixedDigitalOut = 8,
+ kDriverStationEIO_PWM = 9,
+ kDriverStationEIO_Encoder = 10,
+ kDriverStationEIO_TouchSlider = 11,
+
+ kADXL345_SPI = 1,
+ kADXL345_I2C = 2,
+
+ kCommand_Scheduler = 1,
+
+ kSmartDashboard_Instance = 1,
+ } tInstances;
+
+ /**
+ * Report the usage of a resource of interest.
+ *
+ * @param resource one of the values in the tResourceType above (max value 51).
+ * @param instanceNumber an index that identifies the resource instance.
+ * @param context an optional additional context number for some cases (such as module number). Set to 0 to omit.
+ * @param feature a string to be included describing features in use on a specific resource. Setting the same resource more than once allows you to change the feature string.
+ */
+ uint32_t EXPORT_FUNC report(tResourceType resource, uint8_t instanceNumber, uint8_t context = 0, const char *feature = NULL);
+}
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+ uint32_t EXPORT_FUNC FRC_NetworkCommunication_nUsageReporting_report(uint8_t resource, uint8_t instanceNumber, uint8_t context, const char *feature);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif // __UsageReporting_h__
diff --git a/hal/lib/Athena/HALAthena.cpp b/hal/lib/Athena/HALAthena.cpp
new file mode 100644
index 0000000..b1ffcb1
--- /dev/null
+++ b/hal/lib/Athena/HALAthena.cpp
@@ -0,0 +1,339 @@
+#include "HAL/HAL.hpp"
+
+#include "HAL/Port.h"
+#include "HAL/Errors.hpp"
+#include "ctre/ctre.h"
+#include "visa/visa.h"
+#include "ChipObject.h"
+#include "FRC_NetworkCommunication/FRCComm.h"
+#include "FRC_NetworkCommunication/UsageReporting.h"
+#include "FRC_NetworkCommunication/LoadOut.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h"
+#include <cstdlib>
+#include <fstream>
+#include <iostream>
+#include <unistd.h>
+#include <sys/prctl.h>
+#include <signal.h> // linux for kill
+const uint32_t solenoid_kNumDO7_0Elements = 8;
+const uint32_t dio_kNumSystems = tDIO::kNumSystems;
+const uint32_t interrupt_kNumSystems = tInterrupt::kNumSystems;
+const uint32_t kSystemClockTicksPerMicrosecond = 40;
+
+static tGlobal *global = nullptr;
+static tSysWatchdog *watchdog = nullptr;
+
+void* getPort(uint8_t pin)
+{
+ Port* port = new Port();
+ port->pin = pin;
+ port->module = 1;
+ return port;
+}
+
+/**
+ * @deprecated Uses module numbers
+ */
+void* getPortWithModule(uint8_t module, uint8_t pin)
+{
+ Port* port = new Port();
+ port->pin = pin;
+ port->module = module;
+ return port;
+}
+
+void freePort(void* port_pointer)
+{
+ Port* port = (Port*) port_pointer;
+ delete port;
+}
+
+const char* getHALErrorMessage(int32_t code)
+{
+ switch(code) {
+ case 0:
+ return "";
+ case CTR_RxTimeout:
+ return CTR_RxTimeout_MESSAGE;
+ case CTR_TxTimeout:
+ return CTR_TxTimeout_MESSAGE;
+ case CTR_InvalidParamValue:
+ return CTR_InvalidParamValue_MESSAGE;
+ case CTR_UnexpectedArbId:
+ return CTR_UnexpectedArbId_MESSAGE;
+ case CTR_TxFailed:
+ return CTR_TxFailed_MESSAGE;
+ case CTR_SigNotUpdated:
+ return CTR_SigNotUpdated_MESSAGE;
+ case NiFpga_Status_FifoTimeout:
+ return NiFpga_Status_FifoTimeout_MESSAGE;
+ case NiFpga_Status_TransferAborted:
+ return NiFpga_Status_TransferAborted_MESSAGE;
+ case NiFpga_Status_MemoryFull:
+ return NiFpga_Status_MemoryFull_MESSAGE;
+ case NiFpga_Status_SoftwareFault:
+ return NiFpga_Status_SoftwareFault_MESSAGE;
+ case NiFpga_Status_InvalidParameter:
+ return NiFpga_Status_InvalidParameter_MESSAGE;
+ case NiFpga_Status_ResourceNotFound:
+ return NiFpga_Status_ResourceNotFound_MESSAGE;
+ case NiFpga_Status_ResourceNotInitialized:
+ return NiFpga_Status_ResourceNotInitialized_MESSAGE;
+ case NiFpga_Status_HardwareFault:
+ return NiFpga_Status_HardwareFault_MESSAGE;
+ case NiFpga_Status_IrqTimeout:
+ return NiFpga_Status_IrqTimeout_MESSAGE;
+ case SAMPLE_RATE_TOO_HIGH:
+ return SAMPLE_RATE_TOO_HIGH_MESSAGE;
+ case VOLTAGE_OUT_OF_RANGE:
+ return VOLTAGE_OUT_OF_RANGE_MESSAGE;
+ case LOOP_TIMING_ERROR:
+ return LOOP_TIMING_ERROR_MESSAGE;
+ case SPI_WRITE_NO_MOSI:
+ return SPI_WRITE_NO_MOSI_MESSAGE;
+ case SPI_READ_NO_MISO:
+ return SPI_READ_NO_MISO_MESSAGE;
+ case SPI_READ_NO_DATA:
+ return SPI_READ_NO_DATA_MESSAGE;
+ case INCOMPATIBLE_STATE:
+ return INCOMPATIBLE_STATE_MESSAGE;
+ case NO_AVAILABLE_RESOURCES:
+ return NO_AVAILABLE_RESOURCES_MESSAGE;
+ case NULL_PARAMETER:
+ return NULL_PARAMETER_MESSAGE;
+ case ANALOG_TRIGGER_LIMIT_ORDER_ERROR:
+ return ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE;
+ case ANALOG_TRIGGER_PULSE_OUTPUT_ERROR:
+ return ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE;
+ case PARAMETER_OUT_OF_RANGE:
+ return PARAMETER_OUT_OF_RANGE_MESSAGE;
+ case ERR_CANSessionMux_InvalidBuffer:
+ return ERR_CANSessionMux_InvalidBuffer_MESSAGE;
+ case ERR_CANSessionMux_MessageNotFound:
+ return ERR_CANSessionMux_MessageNotFound_MESSAGE;
+ case WARN_CANSessionMux_NoToken:
+ return WARN_CANSessionMux_NoToken_MESSAGE;
+ case ERR_CANSessionMux_NotAllowed:
+ return ERR_CANSessionMux_NotAllowed_MESSAGE;
+ case ERR_CANSessionMux_NotInitialized:
+ return ERR_CANSessionMux_NotInitialized_MESSAGE;
+ case VI_ERROR_SYSTEM_ERROR:
+ return VI_ERROR_SYSTEM_ERROR_MESSAGE;
+ case VI_ERROR_INV_OBJECT:
+ return VI_ERROR_INV_OBJECT_MESSAGE;
+ case VI_ERROR_RSRC_LOCKED:
+ return VI_ERROR_RSRC_LOCKED_MESSAGE;
+ case VI_ERROR_RSRC_NFOUND:
+ return VI_ERROR_RSRC_NFOUND_MESSAGE;
+ case VI_ERROR_INV_RSRC_NAME:
+ return VI_ERROR_INV_RSRC_NAME_MESSAGE;
+ case VI_ERROR_QUEUE_OVERFLOW:
+ return VI_ERROR_QUEUE_OVERFLOW_MESSAGE;
+ case VI_ERROR_IO:
+ return VI_ERROR_IO_MESSAGE;
+ case VI_ERROR_ASRL_PARITY:
+ return VI_ERROR_ASRL_PARITY_MESSAGE;
+ case VI_ERROR_ASRL_FRAMING:
+ return VI_ERROR_ASRL_FRAMING_MESSAGE;
+ case VI_ERROR_ASRL_OVERRUN:
+ return VI_ERROR_ASRL_OVERRUN_MESSAGE;
+ case VI_ERROR_RSRC_BUSY:
+ return VI_ERROR_RSRC_BUSY_MESSAGE;
+ case VI_ERROR_INV_PARAMETER:
+ return VI_ERROR_INV_PARAMETER_MESSAGE;
+ default:
+ return "Unknown error status";
+ }
+}
+
+/**
+ * Return the FPGA Version number.
+ * For now, expect this to be competition year.
+ * @return FPGA Version number.
+ */
+uint16_t getFPGAVersion(int32_t *status)
+{
+ if (!global) {
+ *status = NiFpga_Status_ResourceNotInitialized;
+ return 0;
+ }
+ return global->readVersion(status);
+}
+
+/**
+ * Return the FPGA Revision number.
+ * The format of the revision is 3 numbers.
+ * The 12 most significant bits are the Major Revision.
+ * the next 8 bits are the Minor Revision.
+ * The 12 least significant bits are the Build Number.
+ * @return FPGA Revision number.
+ */
+uint32_t getFPGARevision(int32_t *status)
+{
+ if (!global) {
+ *status = NiFpga_Status_ResourceNotInitialized;
+ return 0;
+ }
+ return global->readRevision(status);
+}
+
+/**
+ * Read the microsecond-resolution timer on the FPGA.
+ *
+ * @return The current time in microseconds according to the FPGA (since FPGA reset).
+ */
+uint32_t getFPGATime(int32_t *status)
+{
+ if (!global) {
+ *status = NiFpga_Status_ResourceNotInitialized;
+ return 0;
+ }
+ return global->readLocalTime(status);
+}
+
+/**
+ * Get the state of the "USER" button on the RoboRIO
+ * @return true if the button is currently pressed down
+ */
+bool getFPGAButton(int32_t *status)
+{
+ if (!global) {
+ *status = NiFpga_Status_ResourceNotInitialized;
+ return false;
+ }
+ return global->readUserButton(status);
+}
+
+int HALSetErrorData(const char *errors, int errorsLength, int wait_ms)
+{
+ return setErrorData(errors, errorsLength, wait_ms);
+}
+
+
+bool HALGetSystemActive(int32_t *status)
+{
+ if (!watchdog) {
+ *status = NiFpga_Status_ResourceNotInitialized;
+ return false;
+ }
+ return watchdog->readStatus_SystemActive(status);
+}
+
+bool HALGetBrownedOut(int32_t *status)
+{
+ if (!watchdog) {
+ *status = NiFpga_Status_ResourceNotInitialized;
+ return false;
+ }
+ return !(watchdog->readStatus_PowerAlive(status));
+}
+
+static void HALCleanupAtExit() {
+ global = nullptr;
+ watchdog = nullptr;
+}
+
+/**
+ * Call this to start up HAL. This is required for robot programs.
+ */
+int HALInitialize(int mode)
+{
+ setlinebuf(stdin);
+ setlinebuf(stdout);
+
+ prctl(PR_SET_PDEATHSIG, SIGTERM);
+
+ FRC_NetworkCommunication_Reserve(nullptr);
+ // image 4; Fixes errors caused by multiple processes. Talk to NI about this
+ nFPGA::nRoboRIO_FPGANamespace::g_currentTargetClass =
+ nLoadOut::kTargetClass_RoboRIO;
+
+ int32_t status = 0;
+ global = tGlobal::create(&status);
+ watchdog = tSysWatchdog::create(&status);
+
+ std::atexit(HALCleanupAtExit);
+
+ // Kill any previous robot programs
+ std::fstream fs;
+ // By making this both in/out, it won't give us an error if it doesnt exist
+ fs.open("/var/lock/frc.pid", std::fstream::in | std::fstream::out);
+ if (fs.bad())
+ return 0;
+
+ pid_t pid = 0;
+ if (!fs.eof() && !fs.fail())
+ {
+ fs >> pid;
+ //see if the pid is around, but we don't want to mess with init id=1, or ourselves
+ if (pid >= 2 && kill(pid, 0) == 0 && pid != getpid())
+ {
+ std::cout << "Killing previously running FRC program..."
+ << std::endl;
+ kill(pid, SIGTERM); // try to kill it
+ delayMillis(100);
+ if (kill(pid, 0) == 0)
+ {
+ // still not successfull
+ if (mode == 0)
+ {
+ std::cout << "FRC pid " << pid
+ << " did not die within 110ms. Aborting"
+ << std::endl;
+ return 0; // just fail
+ }
+ else if (mode == 1) // kill -9 it
+ kill(pid, SIGKILL);
+ else
+ {
+ std::cout << "WARNING: FRC pid " << pid
+ << " did not die within 110ms." << std::endl;
+ }
+ }
+
+ }
+ }
+ fs.close();
+ // we will re-open it write only to truncate the file
+ fs.open("/var/lock/frc.pid", std::fstream::out | std::fstream::trunc);
+ fs.seekp(0);
+ pid = getpid();
+ fs << pid << std::endl;
+ fs.close();
+ return 1;
+}
+
+uint32_t HALReport(uint8_t resource, uint8_t instanceNumber, uint8_t context,
+ const char *feature)
+{
+ if(feature == NULL)
+ {
+ feature = "";
+ }
+
+ return FRC_NetworkCommunication_nUsageReporting_report(resource, instanceNumber, context, feature);
+}
+
+// TODO: HACKS
+void NumericArrayResize()
+{
+}
+void RTSetCleanupProc()
+{
+}
+void EDVR_CreateReference()
+{
+}
+void Occur()
+{
+}
+
+void imaqGetErrorText()
+{
+}
+void imaqGetLastError()
+{
+}
+void niTimestamp64()
+{
+}
diff --git a/hal/lib/Athena/Interrupts.cpp b/hal/lib/Athena/Interrupts.cpp
new file mode 100644
index 0000000..e5ad2af
--- /dev/null
+++ b/hal/lib/Athena/Interrupts.cpp
@@ -0,0 +1,123 @@
+#include "HAL/Interrupts.hpp"
+#include "ChipObject.h"
+
+extern void remapDigitalSource(bool analogTrigger, uint32_t &pin, uint8_t &module);
+
+struct Interrupt // FIXME: why is this internal?
+{
+ tInterrupt *anInterrupt;
+ tInterruptManager *manager;
+};
+
+void* initializeInterrupts(uint32_t interruptIndex, bool watcher, int32_t *status)
+{
+ Interrupt* anInterrupt = new Interrupt();
+ // Expects the calling leaf class to allocate an interrupt index.
+ anInterrupt->anInterrupt = tInterrupt::create(interruptIndex, status);
+ anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
+ anInterrupt->manager = new tInterruptManager(
+ (1 << interruptIndex) | (1 << (interruptIndex + 8)), watcher, status);
+ return anInterrupt;
+}
+
+void cleanInterrupts(void* interrupt_pointer, int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ delete anInterrupt->anInterrupt;
+ delete anInterrupt->manager;
+ anInterrupt->anInterrupt = NULL;
+ anInterrupt->manager = NULL;
+}
+
+/**
+ * In synchronous mode, wait for the defined interrupt to occur.
+ * @param timeout Timeout in seconds
+ * @param ignorePrevious If true, ignore interrupts that happened before
+ * waitForInterrupt was called.
+ * @return The mask of interrupts that fired.
+ */
+uint32_t waitForInterrupt(void* interrupt_pointer, double timeout, bool ignorePrevious, int32_t *status)
+{
+ uint32_t result;
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+
+ result = anInterrupt->manager->watch((int32_t)(timeout * 1e3), ignorePrevious, status);
+
+ // Don't report a timeout as an error - the return code is enough to tell
+ // that a timeout happened.
+ if(*status == -NiFpga_Status_IrqTimeout) {
+ *status = NiFpga_Status_Success;
+ }
+
+ return result;
+}
+
+/**
+ * Enable interrupts to occur on this input.
+ * Interrupts are disabled when the RequestInterrupt call is made. This gives time to do the
+ * setup of the other options before starting to field interrupts.
+ */
+void enableInterrupts(void* interrupt_pointer, int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ anInterrupt->manager->enable(status);
+}
+
+/**
+ * Disable Interrupts without without deallocating structures.
+ */
+void disableInterrupts(void* interrupt_pointer, int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ anInterrupt->manager->disable(status);
+}
+
+/**
+ * Return the timestamp for the rising interrupt that occurred most recently.
+ * This is in the same time domain as GetClock().
+ * @return Timestamp in seconds since boot.
+ */
+double readRisingTimestamp(void* interrupt_pointer, int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ uint32_t timestamp = anInterrupt->anInterrupt->readRisingTimeStamp(status);
+ return timestamp * 1e-6;
+}
+
+/**
+* Return the timestamp for the falling interrupt that occurred most recently.
+* This is in the same time domain as GetClock().
+* @return Timestamp in seconds since boot.
+*/
+double readFallingTimestamp(void* interrupt_pointer, int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ uint32_t timestamp = anInterrupt->anInterrupt->readFallingTimeStamp(status);
+ return timestamp * 1e-6;
+}
+
+void requestInterrupts(void* interrupt_pointer, uint8_t routing_module, uint32_t routing_pin,
+ bool routing_analog_trigger, int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
+ remapDigitalSource(routing_analog_trigger, routing_pin, routing_module);
+ anInterrupt->anInterrupt->writeConfig_Source_AnalogTrigger(routing_analog_trigger, status);
+ anInterrupt->anInterrupt->writeConfig_Source_Channel(routing_pin, status);
+ anInterrupt->anInterrupt->writeConfig_Source_Module(routing_module, status);
+}
+
+void attachInterruptHandler(void* interrupt_pointer, InterruptHandlerFunction handler, void* param,
+ int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ anInterrupt->manager->registerHandler(handler, param, status);
+}
+
+void setInterruptUpSourceEdge(void* interrupt_pointer, bool risingEdge, bool fallingEdge,
+ int32_t *status)
+{
+ Interrupt* anInterrupt = (Interrupt*)interrupt_pointer;
+ anInterrupt->anInterrupt->writeConfig_RisingEdge(risingEdge, status);
+ anInterrupt->anInterrupt->writeConfig_FallingEdge(fallingEdge, status);
+}
diff --git a/hal/lib/Athena/Notifier.cpp b/hal/lib/Athena/Notifier.cpp
new file mode 100644
index 0000000..c2c6c4c
--- /dev/null
+++ b/hal/lib/Athena/Notifier.cpp
@@ -0,0 +1,143 @@
+#include "HAL/Notifier.hpp"
+#include "ChipObject.h"
+#include "HAL/HAL.hpp"
+#include "HAL/cpp/priority_mutex.h"
+#include <atomic>
+#include <cstdlib>
+#include <mutex>
+
+static const uint32_t kTimerInterruptNumber = 28;
+
+static priority_mutex notifierInterruptMutex;
+static priority_recursive_mutex notifierMutex;
+static tAlarm *notifierAlarm = nullptr;
+static tInterruptManager *notifierManager = nullptr;
+static uint32_t closestTrigger = UINT32_MAX;
+struct Notifier {
+ Notifier *prev, *next;
+ void *param;
+ void (*process)(uint32_t, void*);
+ uint32_t triggerTime = UINT32_MAX;
+};
+static Notifier *notifiers = nullptr;
+static std::atomic_flag notifierAtexitRegistered = ATOMIC_FLAG_INIT;
+static std::atomic_int notifierRefCount{0};
+
+static void alarmCallback(uint32_t, void*)
+{
+ std::unique_lock<priority_recursive_mutex> sync(notifierMutex);
+
+ int32_t status = 0;
+ uint32_t currentTime = 0;
+
+ // the hardware disables itself after each alarm
+ closestTrigger = UINT32_MAX;
+
+ // process all notifiers
+ Notifier *notifier = notifiers;
+ while (notifier) {
+ if (notifier->triggerTime != UINT32_MAX) {
+ if (currentTime == 0)
+ currentTime = getFPGATime(&status);
+ if (notifier->triggerTime < currentTime) {
+ notifier->triggerTime = UINT32_MAX;
+ auto process = notifier->process;
+ auto param = notifier->param;
+ sync.unlock();
+ process(currentTime, param);
+ sync.lock();
+ } else if (notifier->triggerTime < closestTrigger) {
+ updateNotifierAlarm(notifier, notifier->triggerTime, &status);
+ }
+ }
+ notifier = notifier->next;
+ }
+}
+
+static void cleanupNotifierAtExit() {
+ notifierAlarm = nullptr;
+ notifierManager = nullptr;
+}
+
+void* initializeNotifier(void (*ProcessQueue)(uint32_t, void*), void *param, int32_t *status)
+{
+ if (!ProcessQueue) {
+ *status = NULL_PARAMETER;
+ return nullptr;
+ }
+ if (!notifierAtexitRegistered.test_and_set())
+ std::atexit(cleanupNotifierAtExit);
+ if (notifierRefCount.fetch_add(1) == 0) {
+ std::lock_guard<priority_mutex> sync(notifierInterruptMutex);
+ // create manager and alarm if not already created
+ if (!notifierManager) {
+ notifierManager = new tInterruptManager(1 << kTimerInterruptNumber, false, status);
+ notifierManager->registerHandler(alarmCallback, NULL, status);
+ notifierManager->enable(status);
+ }
+ if (!notifierAlarm) notifierAlarm = tAlarm::create(status);
+ }
+
+ std::lock_guard<priority_recursive_mutex> sync(notifierMutex);
+ // create notifier structure and add to list
+ Notifier* notifier = new Notifier();
+ notifier->prev = nullptr;
+ notifier->next = notifiers;
+ if (notifier->next) notifier->next->prev = notifier;
+ notifier->param = param;
+ notifier->process = ProcessQueue;
+ notifiers = notifier;
+ return notifier;
+}
+
+void cleanNotifier(void* notifier_pointer, int32_t *status)
+{
+ {
+ std::lock_guard<priority_recursive_mutex> sync(notifierMutex);
+ Notifier* notifier = (Notifier*)notifier_pointer;
+
+ // remove from list and delete
+ if (notifier->prev) notifier->prev->next = notifier->next;
+ if (notifier->next) notifier->next->prev = notifier->prev;
+ if (notifiers == notifier) notifiers = notifier->next;
+ delete notifier;
+ }
+
+ if (notifierRefCount.fetch_sub(1) == 1) {
+ std::lock_guard<priority_mutex> sync(notifierInterruptMutex);
+ // if this was the last notifier, clean up alarm and manager
+ if (notifierAlarm) {
+ notifierAlarm->writeEnable(false, status);
+ delete notifierAlarm;
+ notifierAlarm = nullptr;
+ }
+ if (notifierManager) {
+ notifierManager->disable(status);
+ delete notifierManager;
+ notifierManager = nullptr;
+ }
+ }
+}
+
+void updateNotifierAlarm(void* notifier_pointer, uint32_t triggerTime, int32_t *status)
+{
+ std::lock_guard<priority_recursive_mutex> sync(notifierMutex);
+
+ Notifier* notifier = (Notifier*)notifier_pointer;
+ notifier->triggerTime = triggerTime;
+ bool wasActive = (closestTrigger != UINT32_MAX);
+
+ if (!notifierInterruptMutex.try_lock() || notifierRefCount == 0 ||
+ !notifierAlarm)
+ return;
+
+ // Update alarm time if closer than current.
+ if (triggerTime < closestTrigger) {
+ closestTrigger = triggerTime;
+ notifierAlarm->writeTriggerTime(triggerTime, status);
+ }
+ // Enable the alarm. The hardware disables itself after each alarm.
+ if (!wasActive) notifierAlarm->writeEnable(true, status);
+
+ notifierInterruptMutex.unlock();
+}
diff --git a/hal/lib/Athena/PDP.cpp b/hal/lib/Athena/PDP.cpp
new file mode 100644
index 0000000..26fb4f6
--- /dev/null
+++ b/hal/lib/Athena/PDP.cpp
@@ -0,0 +1,71 @@
+#include "HAL/PDP.hpp"
+#include "ctre/PDP.h"
+//static PDP pdp;
+
+static const int NUM_MODULE_NUMBERS = 63;
+
+static PDP *pdp[NUM_MODULE_NUMBERS] = { NULL };
+
+void initializePDP(uint8_t module) {
+ if(!pdp[module]) {
+ pdp[module] = new PDP(module);
+ }
+}
+
+double getPDPTemperature(uint8_t module, int32_t *status) {
+ double temperature;
+
+ *status = pdp[module]->GetTemperature(temperature);
+
+ return temperature;
+}
+
+double getPDPVoltage(uint8_t module, int32_t *status) {
+ double voltage;
+
+ *status = pdp[module]->GetVoltage(voltage);
+
+ return voltage;
+}
+
+double getPDPChannelCurrent(uint8_t module, uint8_t channel, int32_t *status) {
+ double current;
+
+ *status = pdp[module]->GetChannelCurrent(channel, current);
+
+ return current;
+}
+
+double getPDPTotalCurrent(uint8_t module, int32_t *status) {
+ double current;
+
+ *status = pdp[module]->GetTotalCurrent(current);
+
+ return current;
+}
+
+double getPDPTotalPower(uint8_t module, int32_t *status) {
+ double power;
+
+ *status = pdp[module]->GetTotalPower(power);
+
+ return power;
+}
+
+double getPDPTotalEnergy(uint8_t module, int32_t *status) {
+ double energy;
+
+ *status = pdp[module]->GetTotalEnergy(energy);
+
+ return energy;
+}
+
+void resetPDPTotalEnergy(uint8_t module, int32_t *status) {
+ *status = pdp[module]->ResetEnergy();
+}
+
+void clearPDPStickyFaults(uint8_t module, int32_t *status) {
+ *status = pdp[module]->ClearStickyFaults();
+}
+
+
diff --git a/hal/lib/Athena/Power.cpp b/hal/lib/Athena/Power.cpp
new file mode 100644
index 0000000..cde96ea
--- /dev/null
+++ b/hal/lib/Athena/Power.cpp
@@ -0,0 +1,127 @@
+#include "HAL/Power.hpp"
+#include "ChipObject.h"
+
+static tPower *power = NULL;
+
+static void initializePower(int32_t *status) {
+ if(power == NULL) {
+ power = tPower::create(status);
+ }
+}
+
+/**
+ * Get the roboRIO input voltage
+ */
+float getVinVoltage(int32_t *status) {
+ initializePower(status);
+ return power->readVinVoltage(status) / 4.096f * 0.025733f - 0.029f;
+}
+
+/**
+ * Get the roboRIO input current
+ */
+float getVinCurrent(int32_t *status) {
+ initializePower(status);
+ return power->readVinCurrent(status) / 4.096f * 0.017042 - 0.071f;
+}
+
+/**
+ * Get the 6V rail voltage
+ */
+float getUserVoltage6V(int32_t *status) {
+ initializePower(status);
+ return power->readUserVoltage6V(status) / 4.096f * 0.007019f - 0.014f;
+}
+
+/**
+ * Get the 6V rail current
+ */
+float getUserCurrent6V(int32_t *status) {
+ initializePower(status);
+ return power->readUserCurrent6V(status) / 4.096f * 0.005566f - 0.009f;
+}
+
+/**
+ * Get the active state of the 6V rail
+ */
+bool getUserActive6V(int32_t *status) {
+ initializePower(status);
+ return power->readStatus_User6V(status) == 4;
+}
+
+/**
+ * Get the fault count for the 6V rail
+ */
+int getUserCurrentFaults6V(int32_t *status) {
+ initializePower(status);
+ return (int)power->readFaultCounts_OverCurrentFaultCount6V(status);
+}
+
+/**
+ * Get the 5V rail voltage
+ */
+float getUserVoltage5V(int32_t *status) {
+ initializePower(status);
+ return power->readUserVoltage5V(status) / 4.096f * 0.005962f - 0.013f;
+}
+
+/**
+ * Get the 5V rail current
+ */
+float getUserCurrent5V(int32_t *status) {
+ initializePower(status);
+ return power->readUserCurrent5V(status) / 4.096f * 0.001996f - 0.002f;
+}
+
+/**
+ * Get the active state of the 5V rail
+ */
+bool getUserActive5V(int32_t *status) {
+ initializePower(status);
+ return power->readStatus_User5V(status) == 4;
+}
+
+/**
+ * Get the fault count for the 5V rail
+ */
+int getUserCurrentFaults5V(int32_t *status) {
+ initializePower(status);
+ return (int)power->readFaultCounts_OverCurrentFaultCount5V(status);
+}
+
+unsigned char getUserStatus5V(int32_t *status) {
+ initializePower(status);
+ return power->readStatus_User5V(status);
+}
+
+/**
+ * Get the 3.3V rail voltage
+ */
+float getUserVoltage3V3(int32_t *status) {
+ initializePower(status);
+ return power->readUserVoltage3V3(status) / 4.096f * 0.004902f - 0.01f;
+}
+
+/**
+ * Get the 3.3V rail current
+ */
+float getUserCurrent3V3(int32_t *status) {
+ initializePower(status);
+ return power->readUserCurrent3V3(status) / 4.096f * 0.002486f - 0.003f;
+}
+
+/**
+ * Get the active state of the 3.3V rail
+ */
+bool getUserActive3V3(int32_t *status) {
+ initializePower(status);
+ return power->readStatus_User3V3(status) == 4;
+}
+
+/**
+ * Get the fault count for the 3.3V rail
+ */
+int getUserCurrentFaults3V3(int32_t *status) {
+ initializePower(status);
+ return (int)power->readFaultCounts_OverCurrentFaultCount3V3(status);
+}
diff --git a/hal/lib/Athena/Semaphore.cpp b/hal/lib/Athena/Semaphore.cpp
new file mode 100644
index 0000000..db9e9a3
--- /dev/null
+++ b/hal/lib/Athena/Semaphore.cpp
@@ -0,0 +1,42 @@
+#include "HAL/Semaphore.hpp"
+
+#include "Log.hpp"
+
+// set the logging level
+TLogLevel semaphoreLogLevel = logDEBUG;
+
+#define SEMAPHORE_LOG(level) \
+ if (level > semaphoreLogLevel) ; \
+ else Log().Get(level)
+
+MUTEX_ID initializeMutexNormal() { return new priority_mutex; }
+
+void deleteMutex(MUTEX_ID sem) { delete sem; }
+
+/**
+ * Lock the mutex, blocking until it's available.
+ */
+void takeMutex(MUTEX_ID mutex) { mutex->lock(); }
+
+/**
+ * Attempt to lock the mutex.
+ * @return true if succeeded in locking the mutex, false otherwise.
+ */
+bool tryTakeMutex(MUTEX_ID mutex) { return mutex->try_lock(); }
+
+/**
+ * Unlock the mutex.
+ * @return 0 for success, -1 for error. If -1, the error will be in errno.
+ */
+void giveMutex(MUTEX_ID mutex) { mutex->unlock(); }
+
+MULTIWAIT_ID initializeMultiWait() { return new priority_condition_variable; }
+
+void deleteMultiWait(MULTIWAIT_ID cond) { delete cond; }
+
+void takeMultiWait(MULTIWAIT_ID cond, MUTEX_ID m) {
+ std::unique_lock<priority_mutex> lock(*m);
+ cond->wait(lock);
+}
+
+void giveMultiWait(MULTIWAIT_ID cond) { cond->notify_all(); }
diff --git a/hal/lib/Athena/SerialPort.cpp b/hal/lib/Athena/SerialPort.cpp
new file mode 100644
index 0000000..7393e2c
--- /dev/null
+++ b/hal/lib/Athena/SerialPort.cpp
@@ -0,0 +1,148 @@
+#include "HAL/SerialPort.hpp"
+#include "visa/visa.h"
+
+
+uint32_t m_resourceManagerHandle;
+uint32_t m_portHandle[2];
+
+void serialInitializePort(uint8_t port, int32_t *status) {
+ char const * portName;
+
+ if (m_resourceManagerHandle ==0)
+ viOpenDefaultRM((ViSession*)&m_resourceManagerHandle);
+
+ if(port == 0)
+ portName = "ASRL1::INSTR";
+ else if (port == 1)
+ portName = "ASRL2::INSTR";
+ else
+ portName = "ASRL3::INSTR";
+
+ *status = viOpen(m_resourceManagerHandle, const_cast<char*>(portName), VI_NULL, VI_NULL, (ViSession*)&m_portHandle[port]);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetBaudRate(uint8_t port, uint32_t baud, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_BAUD, baud);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetDataBits(uint8_t port, uint8_t bits, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_DATA_BITS, bits);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetParity(uint8_t port, uint8_t parity, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_PARITY, parity);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetStopBits(uint8_t port, uint8_t stopBits, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_STOP_BITS, stopBits);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetWriteMode(uint8_t port, uint8_t mode, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_WR_BUF_OPER_MODE, mode);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetFlowControl(uint8_t port, uint8_t flow, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_FLOW_CNTRL, flow);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetTimeout(uint8_t port, float timeout, int32_t *status) {
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_TMO_VALUE, (uint32_t)(timeout * 1e3));
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialEnableTermination(uint8_t port, char terminator, int32_t *status) {
+ viSetAttribute(m_portHandle[port], VI_ATTR_TERMCHAR_EN, VI_TRUE);
+ viSetAttribute(m_portHandle[port], VI_ATTR_TERMCHAR, terminator);
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_END_IN, VI_ASRL_END_TERMCHAR);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialDisableTermination(uint8_t port, int32_t *status) {
+ viSetAttribute(m_portHandle[port], VI_ATTR_TERMCHAR_EN, VI_FALSE);
+ *status = viSetAttribute(m_portHandle[port], VI_ATTR_ASRL_END_IN, VI_ASRL_END_NONE);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetReadBufferSize(uint8_t port, uint32_t size, int32_t *status) {
+ *status = viSetBuf(m_portHandle[port], VI_READ_BUF, size);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialSetWriteBufferSize(uint8_t port, uint32_t size, int32_t *status) {
+ *status = viSetBuf(m_portHandle[port], VI_WRITE_BUF, size);
+ if(*status > 0)
+ *status = 0;
+}
+
+int32_t serialGetBytesReceived(uint8_t port, int32_t *status) {
+ int32_t bytes = 0;
+
+ *status = viGetAttribute(m_portHandle[port], VI_ATTR_ASRL_AVAIL_NUM, &bytes);
+ if(*status > 0)
+ *status = 0;
+ return bytes;
+}
+
+uint32_t serialRead(uint8_t port, char* buffer, int32_t count, int32_t *status) {
+ uint32_t retCount = 0;
+
+ *status = viRead(m_portHandle[port], (ViPBuf)buffer, count, (ViPUInt32)&retCount);
+
+ if(*status == VI_ERROR_IO || *status == VI_ERROR_ASRL_OVERRUN || *status == VI_ERROR_ASRL_FRAMING || *status == VI_ERROR_ASRL_PARITY)
+ {
+ int32_t localStatus = 0;
+ serialClear(port, &localStatus);
+ }
+
+ if(*status == VI_ERROR_TMO || *status > 0)
+ *status = 0;
+ return retCount;
+}
+
+uint32_t serialWrite(uint8_t port, const char *buffer, int32_t count, int32_t *status) {
+ uint32_t retCount = 0;
+
+ *status = viWrite(m_portHandle[port], (ViPBuf)buffer, count, (ViPUInt32)&retCount);
+
+ if(*status > 0)
+ *status = 0;
+ return retCount;
+}
+
+void serialFlush(uint8_t port, int32_t *status) {
+ *status = viFlush(m_portHandle[port], VI_WRITE_BUF);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialClear(uint8_t port, int32_t *status) {
+ *status = viClear(m_portHandle[port]);
+ if(*status > 0)
+ *status = 0;
+}
+
+void serialClose(uint8_t port, int32_t *status) {
+ *status = viClose(m_portHandle[port]);
+ if(*status > 0)
+ *status = 0;
+}
+
+
\ No newline at end of file
diff --git a/hal/lib/Athena/Solenoid.cpp b/hal/lib/Athena/Solenoid.cpp
new file mode 100644
index 0000000..a95d836
--- /dev/null
+++ b/hal/lib/Athena/Solenoid.cpp
@@ -0,0 +1,97 @@
+
+#include "HAL/Solenoid.hpp"
+
+#include "HAL/Port.h"
+#include "HAL/Errors.hpp"
+#include "ChipObject.h"
+#include "FRC_NetworkCommunication/LoadOut.h"
+#include "ctre/PCM.h"
+
+static const int NUM_MODULE_NUMBERS = 63;
+
+PCM *modules[NUM_MODULE_NUMBERS] = { NULL };
+
+struct solenoid_port_t {
+ PCM *module;
+ uint32_t pin;
+};
+
+void initializePCM(int module) {
+ if(!modules[module]) {
+ modules[module] = new PCM(module);
+ }
+}
+
+void* initializeSolenoidPort(void *port_pointer, int32_t *status) {
+ Port* port = (Port*) port_pointer;
+ initializePCM(port->module);
+
+ solenoid_port_t *solenoid_port = new solenoid_port_t;
+ solenoid_port->module = modules[port->module];
+ solenoid_port->pin = port->pin;
+
+ return solenoid_port;
+}
+
+void freeSolenoidPort(void* solenoid_port_pointer) {
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+ delete port;
+}
+
+bool checkSolenoidModule(uint8_t module) {
+ return module < NUM_MODULE_NUMBERS;
+}
+
+bool getSolenoid(void* solenoid_port_pointer, int32_t *status) {
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+ bool value;
+
+ *status = port->module->GetSolenoid(port->pin, value);
+
+ return value;
+}
+
+uint8_t getAllSolenoids(void* solenoid_port_pointer, int32_t *status) {
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+ uint8_t value;
+
+ *status = port->module->GetAllSolenoids(value);
+
+ return value;
+}
+
+void setSolenoid(void* solenoid_port_pointer, bool value, int32_t *status) {
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+
+ *status = port->module->SetSolenoid(port->pin, value);
+}
+
+int getPCMSolenoidBlackList(void* solenoid_port_pointer, int32_t *status){
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+ UINT8 value;
+
+ *status = port->module->GetSolenoidBlackList(value);
+
+ return value;
+}
+bool getPCMSolenoidVoltageStickyFault(void* solenoid_port_pointer, int32_t *status){
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+ bool value;
+
+ *status = port->module->GetSolenoidStickyFault(value);
+
+ return value;
+}
+bool getPCMSolenoidVoltageFault(void* solenoid_port_pointer, int32_t *status){
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+ bool value;
+
+ *status = port->module->GetSolenoidFault(value);
+
+ return value;
+}
+void clearAllPCMStickyFaults_sol(void *solenoid_port_pointer, int32_t *status){
+ solenoid_port_t* port = (solenoid_port_t*) solenoid_port_pointer;
+
+ *status = port->module->ClearStickyFaults();
+}
diff --git a/hal/lib/Athena/Task.cpp b/hal/lib/Athena/Task.cpp
new file mode 100644
index 0000000..9e4b2e9
--- /dev/null
+++ b/hal/lib/Athena/Task.cpp
@@ -0,0 +1,51 @@
+#include "HAL/Task.hpp"
+
+#ifndef OK
+#define OK 0
+#endif /* OK */
+#ifndef ERROR
+#define ERROR (-1)
+#endif /* ERROR */
+
+#include <signal.h>
+
+STATUS verifyTaskID(TASK task) {
+ if (task != nullptr && pthread_kill(*task, 0) == 0) {
+ return OK;
+ } else {
+ return ERROR;
+ }
+}
+
+STATUS setTaskPriority(TASK task, int priority) {
+ int policy = 0;
+ struct sched_param param;
+
+ if (verifyTaskID(task) == OK &&
+ pthread_getschedparam(*task, &policy, ¶m) == 0) {
+ param.sched_priority = priority;
+ if (pthread_setschedparam(*task, SCHED_FIFO, ¶m) == 0) {
+ return OK;
+ }
+ else {
+ return ERROR;
+ }
+ }
+ else {
+ return ERROR;
+ }
+}
+
+STATUS getTaskPriority(TASK task, int* priority) {
+ int policy = 0;
+ struct sched_param param;
+
+ if (verifyTaskID(task) == OK &&
+ pthread_getschedparam(*task, &policy, ¶m) == 0) {
+ *priority = param.sched_priority;
+ return OK;
+ }
+ else {
+ return ERROR;
+ }
+}
diff --git a/hal/lib/Athena/Utilities.cpp b/hal/lib/Athena/Utilities.cpp
new file mode 100644
index 0000000..b34677f
--- /dev/null
+++ b/hal/lib/Athena/Utilities.cpp
@@ -0,0 +1,44 @@
+#include "HAL/Utilities.hpp"
+#include <time.h>
+
+const int32_t HAL_NO_WAIT = 0;
+const int32_t HAL_WAIT_FOREVER = -1;
+
+void delayTicks(int32_t ticks)
+{
+ struct timespec test, remaining;
+ test.tv_sec = 0;
+ test.tv_nsec = ticks * 3;
+
+ /* Sleep until the requested number of ticks has passed, with additional
+ time added if nanosleep is interrupted. */
+ while(nanosleep(&test, &remaining) == -1) {
+ test = remaining;
+ }
+}
+
+void delayMillis(double ms)
+{
+ struct timespec test, remaining;
+ test.tv_sec = ms / 1000;
+ test.tv_nsec = 1000 * (((uint64_t)ms) % 1000000);
+
+ /* Sleep until the requested number of milliseconds has passed, with
+ additional time added if nanosleep is interrupted. */
+ while(nanosleep(&test, &remaining) == -1) {
+ test = remaining;
+ }
+}
+
+void delaySeconds(double s)
+{
+ struct timespec test, remaining;
+ test.tv_sec = (int)s;
+ test.tv_nsec = (s - (int)s) * 1000000000.0;
+
+ /* Sleep until the requested number of seconds has passed, with additional
+ time added if nanosleep is interrupted. */
+ while(nanosleep(&test, &remaining) == -1) {
+ test = remaining;
+ }
+}
diff --git a/hal/lib/Athena/cpp/Resource.cpp b/hal/lib/Athena/cpp/Resource.cpp
new file mode 100644
index 0000000..3e7e86d
--- /dev/null
+++ b/hal/lib/Athena/cpp/Resource.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "HAL/cpp/Resource.hpp"
+#include "HAL/Errors.hpp"
+#include <cstddef>
+#include "HAL/cpp/priority_mutex.h"
+
+namespace hal {
+
+priority_recursive_mutex Resource::m_createLock;
+
+/**
+ * Allocate storage for a new instance of Resource.
+ * Allocate a bool array of values that will get initialized to indicate that no resources
+ * have been allocated yet. The indicies of the resources are [0 .. elements - 1].
+ */
+Resource::Resource(uint32_t elements) {
+ std::lock_guard<priority_recursive_mutex> sync(m_createLock);
+ m_isAllocated = std::vector<bool>(elements, false);
+}
+
+/**
+ * Factory method to create a Resource allocation-tracker *if* needed.
+ *
+ * @param r -- address of the caller's Resource pointer. If *r == NULL, this
+ * will construct a Resource and make *r point to it. If *r != NULL, i.e.
+ * the caller already has a Resource instance, this won't do anything.
+ * @param elements -- the number of elements for this Resource allocator to
+ * track, that is, it will allocate resource numbers in the range
+ * [0 .. elements - 1].
+ */
+/*static*/ void Resource::CreateResourceObject(Resource **r, uint32_t elements)
+{
+ std::lock_guard<priority_recursive_mutex> sync(m_createLock);
+ if (*r == NULL)
+ {
+ *r = new Resource(elements);
+ }
+}
+
+/**
+ * Allocate a resource.
+ * When a resource is requested, mark it allocated. In this case, a free resource value
+ * within the range is located and returned after it is marked allocated.
+ */
+uint32_t Resource::Allocate(const char *resourceDesc)
+{
+ std::lock_guard<priority_recursive_mutex> sync(m_allocateLock);
+ for (uint32_t i=0; i < m_isAllocated.size(); i++)
+ {
+ if (!m_isAllocated[i])
+ {
+ m_isAllocated[i] = true;
+ return i;
+ }
+ }
+ // TODO: wpi_setWPIErrorWithContext(NoAvailableResources, resourceDesc);
+ return ~0ul;
+}
+
+/**
+ * Allocate a specific resource value.
+ * The user requests a specific resource value, i.e. channel number and it is verified
+ * unallocated, then returned.
+ */
+uint32_t Resource::Allocate(uint32_t index, const char *resourceDesc)
+{
+ std::lock_guard<priority_recursive_mutex> sync(m_allocateLock);
+ if (index >= m_isAllocated.size())
+ {
+ // TODO: wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc);
+ return ~0ul;
+ }
+ if ( m_isAllocated[index] )
+ {
+ // TODO: wpi_setWPIErrorWithContext(ResourceAlreadyAllocated, resourceDesc);
+ return ~0ul;
+ }
+ m_isAllocated[index] = true;
+ return index;
+}
+
+
+/**
+ * Free an allocated resource.
+ * After a resource is no longer needed, for example a destructor is called for a channel assignment
+ * class, Free will release the resource value so it can be reused somewhere else in the program.
+ */
+void Resource::Free(uint32_t index)
+{
+ std::lock_guard<priority_recursive_mutex> sync(m_allocateLock);
+ if (index == ~0ul) return;
+ if (index >= m_isAllocated.size())
+ {
+ // TODO: wpi_setWPIError(NotAllocated);
+ return;
+ }
+ if (!m_isAllocated[index])
+ {
+ // TODO: wpi_setWPIError(NotAllocated);
+ return;
+ }
+ m_isAllocated[index] = false;
+}
+
+} // namespace hal
diff --git a/hal/lib/Athena/cpp/Semaphore.cpp b/hal/lib/Athena/cpp/Semaphore.cpp
new file mode 100644
index 0000000..458ca6e
--- /dev/null
+++ b/hal/lib/Athena/cpp/Semaphore.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. All Rights Reserved. */
+/* Open Source Software - may be modified and shared by FRC teams. The code */
+/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
+/*----------------------------------------------------------------------------*/
+
+#include "HAL/cpp/Semaphore.hpp"
+
+Semaphore::Semaphore(uint32_t count) {
+ m_count = count;
+}
+
+void Semaphore::give() {
+ std::lock_guard<priority_mutex> lock(m_mutex);
+ ++m_count;
+ m_condition.notify_one();
+}
+
+void Semaphore::take() {
+ std::unique_lock<priority_mutex> lock(m_mutex);
+ m_condition.wait(lock, [this] { return m_count; } );
+ --m_count;
+}
+
+bool Semaphore::tryTake() {
+ std::lock_guard<priority_mutex> lock(m_mutex);
+ if (m_count) {
+ --m_count;
+ return true;
+ }
+ else {
+ return false;
+ }
+}
diff --git a/hal/lib/Athena/cpp/priority_mutex.cpp b/hal/lib/Athena/cpp/priority_mutex.cpp
new file mode 100644
index 0000000..66d3dcc
--- /dev/null
+++ b/hal/lib/Athena/cpp/priority_mutex.cpp
@@ -0,0 +1,33 @@
+#include "HAL/cpp/priority_mutex.h"
+
+void priority_recursive_mutex::lock() {
+ pthread_mutex_lock(&m_mutex);
+}
+
+void priority_recursive_mutex::unlock() {
+ pthread_mutex_unlock(&m_mutex);
+}
+
+bool priority_recursive_mutex::try_lock() noexcept {
+ return !pthread_mutex_trylock(&m_mutex);
+}
+
+pthread_mutex_t* priority_recursive_mutex::native_handle() {
+ return &m_mutex;
+}
+
+void priority_mutex::lock() {
+ pthread_mutex_lock(&m_mutex);
+}
+
+void priority_mutex::unlock() {
+ pthread_mutex_unlock(&m_mutex);
+}
+
+bool priority_mutex::try_lock() noexcept {
+ return !pthread_mutex_trylock(&m_mutex);
+}
+
+pthread_mutex_t* priority_mutex::native_handle() {
+ return &m_mutex;
+}
diff --git a/hal/lib/Athena/ctre/CanTalonSRX.cpp b/hal/lib/Athena/ctre/CanTalonSRX.cpp
new file mode 100644
index 0000000..56e68e1
--- /dev/null
+++ b/hal/lib/Athena/ctre/CanTalonSRX.cpp
@@ -0,0 +1,1417 @@
+/**
+ * @brief CAN TALON SRX driver.
+ *
+ * The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs
+ * with 10ms update rate for control (throttle or setpoint). However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate
+ * The getters for these unsolicited signals are auto generated at the bottom of this module.
+ *
+ * Likewise most control signals are sent periodically using the fire-and-forget CAN API.
+ * The setters for these unsolicited signals are auto generated at the bottom of this module.
+ *
+ * Signals that are not available in an unsolicited fashion are the Close Loop gains.
+ * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once
+ * or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are
+ * loaded in the TALON, they will persist through power cycles and mode changes.
+ *
+ * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from
+ * and the ProfileSlotSelect is periodically sent in the 10 ms control frame.
+ *
+ * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely
+ * they will only need to set them in a periodic fashion as a function of what motion the application is attempting.
+ * If this API is used, be mindful of the CAN utilization reported in the driver station.
+ *
+ * If calling application has used the config routines to configure the selected feedback sensor, then all positions are measured in
+ * floating point precision rotations. All sensor velocities are specified in floating point precision RPM.
+ * @see ConfigPotentiometerTurns
+ * @see ConfigEncoderCodesPerRev
+ * HOWEVER, if calling application has not called the config routine for selected feedback sensor, then all getters/setters for
+ * position/velocity use the native engineering units of the Talon SRX firm (just like in 2015). Signals explained below.
+ *
+ * Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode).
+ * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V).
+ * Use SetFeedbackDeviceSelect to select which sensor type you need. Once you do that you can use GetSensorPosition()
+ * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by default).
+ * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition.
+ *
+ * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel.
+ * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation
+ * for "in the pits" checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor
+ * data for processing, not just instrumentation. Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms.
+ *
+ * Velocity is in position ticks / 100ms.
+ *
+ * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward).
+ * This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 10ms (if nonzero).
+ *
+ * Pos and velocity close loops are calc'd as
+ * err = target - posOrVel.
+ * iErr += err;
+ * if( (IZone!=0) and abs(err) > IZone)
+ * ClearIaccum()
+ * output = P X err + I X iErr + D X dErr + F X target
+ * dErr = err - lastErr
+ * P, I,and D gains are always positive. F can be negative.
+ * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase.
+ * Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted.
+ *
+ * P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1
+ * ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.
+ *
+ * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023)
+ * for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor.
+ * Close loop and integral accumulator runs every 1ms.
+ *
+ * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023)
+ * per change of 1 unit (ADC or encoder) per ms.
+ *
+ * I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of
+ * this value, the integrated error will auto-clear...
+ * if( (IZone!=0) and abs(err) > IZone)
+ * ClearIaccum()
+ * ...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low.
+ *
+ * CloseLoopRampRate is in throttle units per 1ms. Set to zero to disable ramping.
+ * Works the same as RampThrottle but only is in effect when a close loop mode and profile slot is selected.
+ *
+ * auto generated using spreadsheet and WpiClassGen.csproj
+ * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967
+ */
+#include "HAL/CanTalonSRX.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h" //CAN Comm
+#include <string.h> // memset
+#include <unistd.h> // usleep
+
+#define STATUS_1 0x02041400
+#define STATUS_2 0x02041440
+#define STATUS_3 0x02041480
+#define STATUS_4 0x020414C0
+#define STATUS_5 0x02041500
+#define STATUS_6 0x02041540
+#define STATUS_7 0x02041580
+#define STATUS_8 0x020415C0
+
+#define CONTROL_1 0x02040000
+#define CONTROL_2 0x02040040
+#define CONTROL_3 0x02040080
+
+#define EXPECTED_RESPONSE_TIMEOUT_MS (200)
+#define GET_STATUS1() CtreCanNode::recMsg<TALON_Status_1_General_10ms_t > rx = GetRx<TALON_Status_1_General_10ms_t>(STATUS_1 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS2() CtreCanNode::recMsg<TALON_Status_2_Feedback_20ms_t > rx = GetRx<TALON_Status_2_Feedback_20ms_t>(STATUS_2 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS3() CtreCanNode::recMsg<TALON_Status_3_Enc_100ms_t > rx = GetRx<TALON_Status_3_Enc_100ms_t>(STATUS_3 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS4() CtreCanNode::recMsg<TALON_Status_4_AinTempVbat_100ms_t> rx = GetRx<TALON_Status_4_AinTempVbat_100ms_t>(STATUS_4 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS5() CtreCanNode::recMsg<TALON_Status_5_Startup_OneShot_t > rx = GetRx<TALON_Status_5_Startup_OneShot_t>(STATUS_5 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS6() CtreCanNode::recMsg<TALON_Status_6_Eol_t > rx = GetRx<TALON_Status_6_Eol_t>(STATUS_6 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS7() CtreCanNode::recMsg<TALON_Status_7_Debug_200ms_t > rx = GetRx<TALON_Status_7_Debug_200ms_t>(STATUS_7 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS8() CtreCanNode::recMsg<TALON_Status_8_PulseWid_100ms_t > rx = GetRx<TALON_Status_8_PulseWid_100ms_t>(STATUS_8 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS)
+
+#define PARAM_REQUEST 0x02041800
+#define PARAM_RESPONSE 0x02041840
+#define PARAM_SET 0x02041880
+
+const int kParamArbIdValue = PARAM_RESPONSE;
+const int kParamArbIdMask = 0xFFFFFFFF;
+
+const double FLOAT_TO_FXP_10_22 = (double)0x400000;
+const double FXP_TO_FLOAT_10_22 = 0.0000002384185791015625;
+
+const double FLOAT_TO_FXP_0_8 = (double)0x100;
+const double FXP_TO_FLOAT_0_8 = 0.00390625;
+
+/* encoder/decoders */
+/** control */
+typedef struct _TALON_Control_1_General_10ms_t {
+ unsigned TokenH:8;
+ unsigned TokenL:8;
+ unsigned DemandH:8;
+ unsigned DemandM:8;
+ unsigned DemandL:8;
+ unsigned ProfileSlotSelect:1;
+ unsigned FeedbackDeviceSelect:4;
+ unsigned OverrideLimitSwitchEn:3;
+ unsigned RevFeedbackSensor:1;
+ unsigned RevMotDuringCloseLoopEn:1;
+ unsigned OverrideBrakeType:2;
+ unsigned ModeSelect:4;
+ unsigned RampThrottle:8;
+} TALON_Control_1_General_10ms_t ;
+typedef struct _TALON_Control_2_Rates_OneShot_t {
+ unsigned Status1Ms:8;
+ unsigned Status2Ms:8;
+ unsigned Status3Ms:8;
+ unsigned Status4Ms:8;
+ unsigned StatusPulWidMs:8; // TALON_Status_8_PulseWid_100ms_t
+} TALON_Control_2_Rates_OneShot_t ;
+typedef struct _TALON_Control_3_ClearFlags_OneShot_t {
+ unsigned ZeroFeedbackSensor:1;
+ unsigned ClearStickyFaults:1;
+} TALON_Control_3_ClearFlags_OneShot_t ;
+
+/** status */
+typedef struct _TALON_Status_1_General_10ms_t {
+ unsigned CloseLoopErrH:8;
+ unsigned CloseLoopErrM:8;
+ unsigned CloseLoopErrL:8;
+ unsigned AppliedThrottle_h3:3;
+ unsigned Fault_RevSoftLim:1;
+ unsigned Fault_ForSoftLim:1;
+ unsigned TokLocked:1;
+ unsigned LimitSwitchClosedRev:1;
+ unsigned LimitSwitchClosedFor:1;
+ unsigned AppliedThrottle_l8:8;
+ unsigned ModeSelect_h1:1;
+ unsigned FeedbackDeviceSelect:4;
+ unsigned LimitSwitchEn:3;
+ unsigned Fault_HardwareFailure:1;
+ unsigned Fault_RevLim:1;
+ unsigned Fault_ForLim:1;
+ unsigned Fault_UnderVoltage:1;
+ unsigned Fault_OverTemp:1;
+ unsigned ModeSelect_b3:3;
+ unsigned TokenSeed:8;
+} TALON_Status_1_General_10ms_t ;
+typedef struct _TALON_Status_2_Feedback_20ms_t {
+ unsigned SensorPositionH:8;
+ unsigned SensorPositionM:8;
+ unsigned SensorPositionL:8;
+ unsigned SensorVelocityH:8;
+ unsigned SensorVelocityL:8;
+ unsigned Current_h8:8;
+ unsigned StckyFault_RevSoftLim:1;
+ unsigned StckyFault_ForSoftLim:1;
+ unsigned StckyFault_RevLim:1;
+ unsigned StckyFault_ForLim:1;
+ unsigned StckyFault_UnderVoltage:1;
+ unsigned StckyFault_OverTemp:1;
+ unsigned Current_l2:2;
+ unsigned reserved2:4;
+ unsigned VelDiv4:1;
+ unsigned PosDiv8:1;
+ unsigned ProfileSlotSelect:1;
+ unsigned BrakeIsEnabled:1;
+} TALON_Status_2_Feedback_20ms_t ;
+typedef struct _TALON_Status_3_Enc_100ms_t {
+ unsigned EncPositionH:8;
+ unsigned EncPositionM:8;
+ unsigned EncPositionL:8;
+ unsigned EncVelH:8;
+ unsigned EncVelL:8;
+ unsigned EncIndexRiseEventsH:8;
+ unsigned EncIndexRiseEventsL:8;
+ unsigned reserved:3;
+ unsigned VelDiv4:1;
+ unsigned PosDiv8:1;
+ unsigned QuadIdxpin:1;
+ unsigned QuadBpin:1;
+ unsigned QuadApin:1;
+} TALON_Status_3_Enc_100ms_t ;
+typedef struct _TALON_Status_4_AinTempVbat_100ms_t {
+ unsigned AnalogInWithOvH:8;
+ unsigned AnalogInWithOvM:8;
+ unsigned AnalogInWithOvL:8;
+ unsigned AnalogInVelH:8;
+ unsigned AnalogInVelL:8;
+ unsigned Temp:8;
+ unsigned BatteryV:8;
+ unsigned reserved:6;
+ unsigned VelDiv4:1;
+ unsigned PosDiv8:1;
+} TALON_Status_4_AinTempVbat_100ms_t ;
+typedef struct _TALON_Status_5_Startup_OneShot_t {
+ unsigned ResetCountH:8;
+ unsigned ResetCountL:8;
+ unsigned ResetFlagsH:8;
+ unsigned ResetFlagsL:8;
+ unsigned FirmVersH:8;
+ unsigned FirmVersL:8;
+} TALON_Status_5_Startup_OneShot_t ;
+typedef struct _TALON_Status_6_Eol_t {
+ unsigned currentAdcUncal_h2:2;
+ unsigned reserved1:5;
+ unsigned SpiCsPin_GadgeteerPin6:1;
+ unsigned currentAdcUncal_l8:8;
+ unsigned tempAdcUncal_h2:2;
+ unsigned reserved2:6;
+ unsigned tempAdcUncal_l8:8;
+ unsigned vbatAdcUncal_h2:2;
+ unsigned reserved3:6;
+ unsigned vbatAdcUncal_l8:8;
+ unsigned analogAdcUncal_h2:2;
+ unsigned reserved4:6;
+ unsigned analogAdcUncal_l8:8;
+} TALON_Status_6_Eol_t ;
+typedef struct _TALON_Status_7_Debug_200ms_t {
+ unsigned TokenizationFails_h8:8;
+ unsigned TokenizationFails_l8:8;
+ unsigned LastFailedToken_h8:8;
+ unsigned LastFailedToken_l8:8;
+ unsigned TokenizationSucceses_h8:8;
+ unsigned TokenizationSucceses_l8:8;
+} TALON_Status_7_Debug_200ms_t ;
+typedef struct _TALON_Status_8_PulseWid_100ms_t {
+ unsigned PulseWidPositionH:8;
+ unsigned PulseWidPositionM:8;
+ unsigned PulseWidPositionL:8;
+ unsigned reserved:6;
+ unsigned VelDiv4:1;
+ unsigned PosDiv8:1;
+ unsigned PeriodUsM8:8;
+ unsigned PeriodUsL8:8;
+ unsigned PulseWidVelH:8;
+ unsigned PulseWidVelL:8;
+} TALON_Status_8_PulseWid_100ms_t ;
+typedef struct _TALON_Param_Request_t {
+ unsigned ParamEnum:8;
+} TALON_Param_Request_t ;
+typedef struct _TALON_Param_Response_t {
+ unsigned ParamEnum:8;
+ unsigned ParamValueL:8;
+ unsigned ParamValueML:8;
+ unsigned ParamValueMH:8;
+ unsigned ParamValueH:8;
+} TALON_Param_Response_t ;
+
+CanTalonSRX::CanTalonSRX(int deviceNumber,int controlPeriodMs): CtreCanNode(deviceNumber), _can_h(0), _can_stat(0)
+{
+ /* bound period to be within [1 ms,95 ms] */
+ if(controlPeriodMs < 1)
+ controlPeriodMs = 1;
+ else if(controlPeriodMs > 95)
+ controlPeriodMs = 95;
+ RegisterRx(STATUS_1 | (UINT8)deviceNumber );
+ RegisterRx(STATUS_2 | (UINT8)deviceNumber );
+ RegisterRx(STATUS_3 | (UINT8)deviceNumber );
+ RegisterRx(STATUS_4 | (UINT8)deviceNumber );
+ RegisterRx(STATUS_5 | (UINT8)deviceNumber );
+ RegisterRx(STATUS_6 | (UINT8)deviceNumber );
+ RegisterRx(STATUS_7 | (UINT8)deviceNumber );
+ RegisterTx(CONTROL_1 | (UINT8)deviceNumber, (UINT8)controlPeriodMs);
+ /* the only default param that is nonzero is limit switch.
+ * Default to using the flash settings. */
+ SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash);
+}
+/* CanTalonSRX D'tor
+ */
+CanTalonSRX::~CanTalonSRX()
+{
+ if (m_hasBeenMoved){
+ /* Another CANTalonSRX still exists, so
+ don't un-register the periodic control frame */
+ }else{
+ /* un-register the control frame so Talon is disabled */
+ RegisterTx(CONTROL_1 | (UINT8)GetDeviceNumber(), 0);
+ }
+ /* free the stream we used for SetParam/GetParamResponse */
+ if(_can_h){
+ FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h);
+ _can_h = 0;
+ }
+}
+void CanTalonSRX::OpenSessionIfNeedBe()
+{
+ _can_stat = 0;
+ if (_can_h == 0) {
+ /* bit30 - bit8 must match $000002XX. Top bit is not masked to get remote frames */
+ FRC_NetworkCommunication_CANSessionMux_openStreamSession(&_can_h,kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask, kMsgCapacity, &_can_stat);
+ if (_can_stat == 0) {
+ /* success */
+ } else {
+ /* something went wrong, try again later */
+ _can_h = 0;
+ }
+ }
+}
+void CanTalonSRX::ProcessStreamMessages()
+{
+ if(0 == _can_h)
+ OpenSessionIfNeedBe();
+ /* process receive messages */
+ uint32_t i;
+ uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]);
+ uint32_t messagesRead = 0;
+ /* read out latest bunch of messages */
+ _can_stat = 0;
+ if (_can_h){
+ FRC_NetworkCommunication_CANSessionMux_readStreamSession(_can_h,_msgBuff, messagesToRead, &messagesRead, &_can_stat);
+ }
+ /* loop thru each message of interest */
+ for (i = 0; i < messagesRead; ++i) {
+ tCANStreamMessage * msg = _msgBuff + i;
+ if(msg->messageID == (PARAM_RESPONSE | GetDeviceNumber()) ){
+ TALON_Param_Response_t * paramResp = (TALON_Param_Response_t*)msg->data;
+ /* decode value */
+ int32_t val = paramResp->ParamValueH;
+ val <<= 8;
+ val |= paramResp->ParamValueMH;
+ val <<= 8;
+ val |= paramResp->ParamValueML;
+ val <<= 8;
+ val |= paramResp->ParamValueL;
+ /* save latest signal */
+ _sigs[paramResp->ParamEnum] = val;
+ }else{
+ int brkpthere = 42;
+ ++brkpthere;
+ }
+ }
+}
+void CanTalonSRX::Set(double value)
+{
+ if(value > 1)
+ value = 1;
+ else if(value < -1)
+ value = -1;
+ SetDemand(1023*value); /* must be within [-1023,1023] */
+}
+/*---------------------setters and getters that use the param request/response-------------*/
+/**
+ * Send a one shot frame to set an arbitrary signal.
+ * Most signals are in the control frame so avoid using this API unless you have to.
+ * Use this api for...
+ * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically.
+ * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame.
+ * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms.
+ */
+CTR_Code CanTalonSRX::SetParamRaw(unsigned paramEnum, int rawBits)
+{
+ /* caller is using param API. Open session if it hasn'T been done. */
+ if(0 == _can_h)
+ OpenSessionIfNeedBe();
+ TALON_Param_Response_t frame;
+ memset(&frame,0,sizeof(frame));
+ frame.ParamEnum = paramEnum;
+ frame.ParamValueH = rawBits >> 0x18;
+ frame.ParamValueMH = rawBits >> 0x10;
+ frame.ParamValueML = rawBits >> 0x08;
+ frame.ParamValueL = rawBits;
+ int32_t status = 0;
+ FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_SET | GetDeviceNumber(), (const uint8_t*)&frame, 5, 0, &status);
+ if(status)
+ return CTR_TxFailed;
+ return CTR_OKAY;
+}
+/**
+ * Checks cached CAN frames and updating solicited signals.
+ */
+CTR_Code CanTalonSRX::GetParamResponseRaw(unsigned paramEnum, int & rawBits)
+{
+ CTR_Code retval = CTR_OKAY;
+ /* process received param events. We don't expect many since this API is not used often. */
+ ProcessStreamMessages();
+ /* grab the solicited signal value */
+ sigs_t::iterator i = _sigs.find(paramEnum);
+ if(i == _sigs.end()){
+ retval = CTR_SigNotUpdated;
+ }else{
+ rawBits = i->second;
+ }
+ return retval;
+}
+/**
+ * Asks TALON to immedietely respond with signal value. This API is only used for signals that are not sent periodically.
+ * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values.
+ * @param param to request.
+ */
+CTR_Code CanTalonSRX::RequestParam(param_t paramEnum)
+{
+ /* process received param events. We don't expect many since this API is not used often. */
+ ProcessStreamMessages();
+ TALON_Param_Request_t frame;
+ memset(&frame,0,sizeof(frame));
+ frame.ParamEnum = paramEnum;
+ int32_t status = 0;
+ FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_REQUEST | GetDeviceNumber(), (const uint8_t*)&frame, 1, 0, &status);
+ if(status)
+ return CTR_TxFailed;
+ return CTR_OKAY;
+}
+
+CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value)
+{
+ int32_t rawbits = 0;
+ switch(paramEnum){
+ case eProfileParamSlot0_P:/* unsigned 10.22 fixed pt value */
+ case eProfileParamSlot0_I:
+ case eProfileParamSlot0_D:
+ case eProfileParamSlot1_P:
+ case eProfileParamSlot1_I:
+ case eProfileParamSlot1_D:
+ {
+ uint32_t urawbits;
+ value = std::min(value,1023.0); /* bounds check doubles that are outside u10.22 */
+ value = std::max(value,0.0);
+ urawbits = value * FLOAT_TO_FXP_10_22; /* perform unsign arithmetic */
+ rawbits = urawbits; /* copy bits over. SetParamRaw just stuffs into CAN frame with no sense of signedness */
+ } break;
+ case eProfileParamSlot1_F: /* signed 10.22 fixed pt value */
+ case eProfileParamSlot0_F:
+ value = std::min(value, 512.0); /* bounds check doubles that are outside s10.22 */
+ value = std::max(value,-512.0);
+ rawbits = value * FLOAT_TO_FXP_10_22;
+ break;
+ case eProfileParamVcompRate: /* unsigned 0.8 fixed pt value volts per ms */
+ /* within [0,1) volts per ms.
+ Slowest ramp is 1/256 VperMilliSec or 3.072 seconds from 0-to-12V.
+ Fastest ramp is 255/256 VperMilliSec or 12.1ms from 0-to-12V.
+ */
+ if(value <= 0){
+ /* negative or zero (disable), send raw value of zero */
+ rawbits = 0;
+ }else{
+ /* nonzero ramping */
+ rawbits = value * FLOAT_TO_FXP_0_8;
+ /* since whole part is cleared, cap to just under whole unit */
+ if(rawbits > (FLOAT_TO_FXP_0_8-1) )
+ rawbits = (FLOAT_TO_FXP_0_8-1);
+ /* since ramping is nonzero, cap to smallest ramp rate possible */
+ if(rawbits == 0){
+ /* caller is providing a nonzero ramp rate that's too small
+ to serialize, so cap to smallest possible */
+ rawbits = 1;
+ }
+ }
+ break;
+ default: /* everything else is integral */
+ rawbits = (int32_t)value;
+ break;
+ }
+ return SetParamRaw(paramEnum,rawbits);
+}
+CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double & value)
+{
+ int32_t rawbits = 0;
+ CTR_Code retval = GetParamResponseRaw(paramEnum,rawbits);
+ switch(paramEnum){
+ case eProfileParamSlot0_P:/* 10.22 fixed pt value */
+ case eProfileParamSlot0_I:
+ case eProfileParamSlot0_D:
+ case eProfileParamSlot0_F:
+ case eProfileParamSlot1_P:
+ case eProfileParamSlot1_I:
+ case eProfileParamSlot1_D:
+ case eProfileParamSlot1_F:
+ case eCurrent:
+ case eTemp:
+ case eBatteryV:
+ value = ((double)rawbits) * FXP_TO_FLOAT_10_22;
+ break;
+ case eProfileParamVcompRate:
+ value = ((double)rawbits) * FXP_TO_FLOAT_0_8;
+ break;
+ default: /* everything else is integral */
+ value = (double)rawbits;
+ break;
+ }
+ return retval;
+}
+CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int & value)
+{
+ double dvalue = 0;
+ CTR_Code retval = GetParamResponse(paramEnum, dvalue);
+ value = (int32_t)dvalue;
+ return retval;
+}
+/*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/
+/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/
+/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/
+/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/
+CTR_Code CanTalonSRX::SetPgain(unsigned slotIdx,double gain)
+{
+ if(slotIdx == 0)
+ return SetParam(eProfileParamSlot0_P, gain);
+ return SetParam(eProfileParamSlot1_P, gain);
+}
+CTR_Code CanTalonSRX::SetIgain(unsigned slotIdx,double gain)
+{
+ if(slotIdx == 0)
+ return SetParam(eProfileParamSlot0_I, gain);
+ return SetParam(eProfileParamSlot1_I, gain);
+}
+CTR_Code CanTalonSRX::SetDgain(unsigned slotIdx,double gain)
+{
+ if(slotIdx == 0)
+ return SetParam(eProfileParamSlot0_D, gain);
+ return SetParam(eProfileParamSlot1_D, gain);
+}
+CTR_Code CanTalonSRX::SetFgain(unsigned slotIdx,double gain)
+{
+ if(slotIdx == 0)
+ return SetParam(eProfileParamSlot0_F, gain);
+ return SetParam(eProfileParamSlot1_F, gain);
+}
+CTR_Code CanTalonSRX::SetIzone(unsigned slotIdx,int zone)
+{
+ if(slotIdx == 0)
+ return SetParam(eProfileParamSlot0_IZone, zone);
+ return SetParam(eProfileParamSlot1_IZone, zone);
+}
+CTR_Code CanTalonSRX::SetCloseLoopRampRate(unsigned slotIdx,int closeLoopRampRate)
+{
+ if(slotIdx == 0)
+ return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);
+ return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);
+}
+CTR_Code CanTalonSRX::SetVoltageCompensationRate(double voltagePerMs)
+{
+ return SetParam(eProfileParamVcompRate, voltagePerMs);
+}
+CTR_Code CanTalonSRX::GetPgain(unsigned slotIdx,double & gain)
+{
+ if(slotIdx == 0)
+ return GetParamResponse(eProfileParamSlot0_P, gain);
+ return GetParamResponse(eProfileParamSlot1_P, gain);
+}
+CTR_Code CanTalonSRX::GetIgain(unsigned slotIdx,double & gain)
+{
+ if(slotIdx == 0)
+ return GetParamResponse(eProfileParamSlot0_I, gain);
+ return GetParamResponse(eProfileParamSlot1_I, gain);
+}
+CTR_Code CanTalonSRX::GetDgain(unsigned slotIdx,double & gain)
+{
+ if(slotIdx == 0)
+ return GetParamResponse(eProfileParamSlot0_D, gain);
+ return GetParamResponse(eProfileParamSlot1_D, gain);
+}
+CTR_Code CanTalonSRX::GetFgain(unsigned slotIdx,double & gain)
+{
+ if(slotIdx == 0)
+ return GetParamResponse(eProfileParamSlot0_F, gain);
+ return GetParamResponse(eProfileParamSlot1_F, gain);
+}
+CTR_Code CanTalonSRX::GetIzone(unsigned slotIdx,int & zone)
+{
+ if(slotIdx == 0)
+ return GetParamResponseInt32(eProfileParamSlot0_IZone, zone);
+ return GetParamResponseInt32(eProfileParamSlot1_IZone, zone);
+}
+CTR_Code CanTalonSRX::GetCloseLoopRampRate(unsigned slotIdx,int & closeLoopRampRate)
+{
+ if(slotIdx == 0)
+ return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate);
+ return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate);
+}
+CTR_Code CanTalonSRX::GetVoltageCompensationRate(double & voltagePerMs)
+{
+ return GetParamResponse(eProfileParamVcompRate, voltagePerMs);
+}
+CTR_Code CanTalonSRX::SetSensorPosition(int pos)
+{
+ return SetParam(eSensorPosition, pos);
+}
+CTR_Code CanTalonSRX::SetForwardSoftLimit(int forwardLimit)
+{
+ return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit);
+}
+CTR_Code CanTalonSRX::SetReverseSoftLimit(int reverseLimit)
+{
+ return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit);
+}
+CTR_Code CanTalonSRX::SetForwardSoftEnable(int enable)
+{
+ return SetParam(eProfileParamSoftLimitForEnable, enable);
+}
+CTR_Code CanTalonSRX::SetReverseSoftEnable(int enable)
+{
+ return SetParam(eProfileParamSoftLimitRevEnable, enable);
+}
+CTR_Code CanTalonSRX::GetForwardSoftLimit(int & forwardLimit)
+{
+ return GetParamResponseInt32(eProfileParamSoftLimitForThreshold, forwardLimit);
+}
+CTR_Code CanTalonSRX::GetReverseSoftLimit(int & reverseLimit)
+{
+ return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold, reverseLimit);
+}
+CTR_Code CanTalonSRX::GetForwardSoftEnable(int & enable)
+{
+ return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable);
+}
+CTR_Code CanTalonSRX::GetReverseSoftEnable(int & enable)
+{
+ return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable);
+}
+/**
+ * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for what's available.
+ */
+CTR_Code CanTalonSRX::SetStatusFrameRate(unsigned frameEnum, unsigned periodMs)
+{
+ CTR_Code retval = CTR_OKAY;
+ int32_t paramEnum = 0;
+ /* bounds check the period */
+ if(periodMs < 1)
+ periodMs = 1;
+ else if (periodMs > 255)
+ periodMs = 255;
+ uint8_t period = (uint8_t)periodMs;
+ /* lookup the correct param enum based on what frame to rate-change */
+ switch(frameEnum){
+ case kStatusFrame_General:
+ paramEnum = eStatus1FrameRate;
+ break;
+ case kStatusFrame_Feedback:
+ paramEnum = eStatus2FrameRate;
+ break;
+ case kStatusFrame_Encoder:
+ paramEnum = eStatus3FrameRate;
+ break;
+ case kStatusFrame_AnalogTempVbat:
+ paramEnum = eStatus4FrameRate;
+ break;
+ case kStatusFrame_PulseWidthMeas:
+ paramEnum = eStatus8FrameRate;
+ break;
+ default:
+ /* caller's request is not support, return an error code */
+ retval = CTR_InvalidParamValue;
+ break;
+ }
+ /* if lookup was succesful, send set-request out */
+ if(retval == CTR_OKAY){
+ /* paramEnum is updated, sent it out */
+ retval = SetParamRaw(paramEnum, period);
+ }
+ return retval;
+}
+/**
+ * Clear all sticky faults in TALON.
+ */
+CTR_Code CanTalonSRX::ClearStickyFaults()
+{
+ int32_t status = 0;
+ /* build request frame */
+ TALON_Control_3_ClearFlags_OneShot_t frame;
+ memset(&frame,0,sizeof(frame));
+ frame.ClearStickyFaults = 1;
+ FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_3 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status);
+ if(status)
+ return CTR_TxFailed;
+ return CTR_OKAY;
+}
+/*------------------------ auto generated. This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/
+/*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/
+CTR_Code CanTalonSRX::GetFault_OverTemp(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_OverTemp;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_UnderVoltage(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_UnderVoltage;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_ForLim(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_ForLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_RevLim(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_RevLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_HardwareFailure(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_HardwareFailure;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_ForSoftLim(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_ForSoftLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFault_RevSoftLim(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->Fault_RevSoftLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_OverTemp(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->StckyFault_OverTemp;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_UnderVoltage(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->StckyFault_UnderVoltage;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_ForLim(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->StckyFault_ForLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_RevLim(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->StckyFault_RevLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_ForSoftLim(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->StckyFault_ForSoftLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->StckyFault_RevSoftLim;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetAppliedThrottle(int ¶m)
+{
+ GET_STATUS1();
+ int32_t raw = 0;
+ raw |= rx->AppliedThrottle_h3;
+ raw <<= 8;
+ raw |= rx->AppliedThrottle_l8;
+ raw <<= (32-11); /* sign extend */
+ raw >>= (32-11); /* sign extend */
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetCloseLoopErr(int ¶m)
+{
+ GET_STATUS1();
+ int32_t raw = 0;
+ raw |= rx->CloseLoopErrH;
+ raw <<= 8;
+ raw |= rx->CloseLoopErrM;
+ raw <<= 8;
+ raw |= rx->CloseLoopErrL;
+ raw <<= (32-24); /* sign extend */
+ raw >>= (32-24); /* sign extend */
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->FeedbackDeviceSelect;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetModeSelect(int ¶m)
+{
+ GET_STATUS1();
+ uint32_t raw = 0;
+ raw |= rx->ModeSelect_h1;
+ raw <<= 3;
+ raw |= rx->ModeSelect_b3;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetLimitSwitchEn(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->LimitSwitchEn;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetLimitSwitchClosedFor(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->LimitSwitchClosedFor;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int ¶m)
+{
+ GET_STATUS1();
+ param = rx->LimitSwitchClosedRev;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetSensorPosition(int ¶m)
+{
+ GET_STATUS2();
+ int32_t raw = 0;
+ raw |= rx->SensorPositionH;
+ raw <<= 8;
+ raw |= rx->SensorPositionM;
+ raw <<= 8;
+ raw |= rx->SensorPositionL;
+ raw <<= (32-24); /* sign extend */
+ raw >>= (32-24); /* sign extend */
+ if(rx->PosDiv8)
+ raw *= 8;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetSensorVelocity(int ¶m)
+{
+ GET_STATUS2();
+ int32_t raw = 0;
+ raw |= rx->SensorVelocityH;
+ raw <<= 8;
+ raw |= rx->SensorVelocityL;
+ raw <<= (32-16); /* sign extend */
+ raw >>= (32-16); /* sign extend */
+ if(rx->VelDiv4)
+ raw *= 4;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetCurrent(double ¶m)
+{
+ GET_STATUS2();
+ uint32_t raw = 0;
+ raw |= rx->Current_h8;
+ raw <<= 2;
+ raw |= rx->Current_l2;
+ param = (double)raw * 0.125 + 0;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetBrakeIsEnabled(int ¶m)
+{
+ GET_STATUS2();
+ param = rx->BrakeIsEnabled;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetEncPosition(int ¶m)
+{
+ GET_STATUS3();
+ int32_t raw = 0;
+ raw |= rx->EncPositionH;
+ raw <<= 8;
+ raw |= rx->EncPositionM;
+ raw <<= 8;
+ raw |= rx->EncPositionL;
+ raw <<= (32-24); /* sign extend */
+ raw >>= (32-24); /* sign extend */
+ if(rx->PosDiv8)
+ raw *= 8;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetEncVel(int ¶m)
+{
+ GET_STATUS3();
+ int32_t raw = 0;
+ raw |= rx->EncVelH;
+ raw <<= 8;
+ raw |= rx->EncVelL;
+ raw <<= (32-16); /* sign extend */
+ raw >>= (32-16); /* sign extend */
+ if(rx->VelDiv4)
+ raw *= 4;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetEncIndexRiseEvents(int ¶m)
+{
+ GET_STATUS3();
+ uint32_t raw = 0;
+ raw |= rx->EncIndexRiseEventsH;
+ raw <<= 8;
+ raw |= rx->EncIndexRiseEventsL;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetQuadApin(int ¶m)
+{
+ GET_STATUS3();
+ param = rx->QuadApin;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetQuadBpin(int ¶m)
+{
+ GET_STATUS3();
+ param = rx->QuadBpin;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetQuadIdxpin(int ¶m)
+{
+ GET_STATUS3();
+ param = rx->QuadIdxpin;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetAnalogInWithOv(int ¶m)
+{
+ GET_STATUS4();
+ int32_t raw = 0;
+ raw |= rx->AnalogInWithOvH;
+ raw <<= 8;
+ raw |= rx->AnalogInWithOvM;
+ raw <<= 8;
+ raw |= rx->AnalogInWithOvL;
+ raw <<= (32-24); /* sign extend */
+ raw >>= (32-24); /* sign extend */
+ if(rx->PosDiv8)
+ raw *= 8;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetAnalogInVel(int ¶m)
+{
+ GET_STATUS4();
+ int32_t raw = 0;
+ raw |= rx->AnalogInVelH;
+ raw <<= 8;
+ raw |= rx->AnalogInVelL;
+ raw <<= (32-16); /* sign extend */
+ raw >>= (32-16); /* sign extend */
+ if(rx->VelDiv4)
+ raw *= 4;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetTemp(double ¶m)
+{
+ GET_STATUS4();
+ uint32_t raw = rx->Temp;
+ param = (double)raw * 0.6451612903 + -50;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetBatteryV(double ¶m)
+{
+ GET_STATUS4();
+ uint32_t raw = rx->BatteryV;
+ param = (double)raw * 0.05 + 4;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetResetCount(int ¶m)
+{
+ GET_STATUS5();
+ uint32_t raw = 0;
+ raw |= rx->ResetCountH;
+ raw <<= 8;
+ raw |= rx->ResetCountL;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetResetFlags(int ¶m)
+{
+ GET_STATUS5();
+ uint32_t raw = 0;
+ raw |= rx->ResetFlagsH;
+ raw <<= 8;
+ raw |= rx->ResetFlagsL;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetFirmVers(int ¶m)
+{
+ GET_STATUS5();
+ uint32_t raw = 0;
+ raw |= rx->FirmVersH;
+ raw <<= 8;
+ raw |= rx->FirmVersL;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::SetDemand(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->DemandH = param>>16;
+ toFill->DemandM = param>>8;
+ toFill->DemandL = param>>0;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->OverrideLimitSwitchEn = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->FeedbackDeviceSelect = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->RevMotDuringCloseLoopEn = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetOverrideBrakeType(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->OverrideBrakeType = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetModeSelect(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->ModeSelect = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+/**
+ * @param modeSelect selects which mode.
+ * @param demand setpt or throttle or masterId to follow.
+ * @return error code, 0 iff successful.
+ * This function has the advantage of atomically setting mode and demand.
+ */
+CTR_Code CanTalonSRX::SetModeSelect(int modeSelect,int demand)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->ModeSelect = modeSelect;
+ toFill->DemandH = demand>>16;
+ toFill->DemandM = demand>>8;
+ toFill->DemandL = demand>>0;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetProfileSlotSelect(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->ProfileSlotSelect = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetRampThrottle(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->RampThrottle = param;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param)
+{
+ CtreCanNode::txTask<TALON_Control_1_General_10ms_t> toFill = GetTx<TALON_Control_1_General_10ms_t>(CONTROL_1 | GetDeviceNumber());
+ if (toFill.IsEmpty()) return CTR_UnexpectedArbId;
+ toFill->RevFeedbackSensor = param ? 1 : 0;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+CTR_Code CanTalonSRX::GetPulseWidthPosition(int ¶m)
+{
+ GET_STATUS8();
+ int32_t raw = 0;
+ raw |= rx->PulseWidPositionH;
+ raw <<= 8;
+ raw |= rx->PulseWidPositionM;
+ raw <<= 8;
+ raw |= rx->PulseWidPositionL;
+ raw <<= (32-24); /* sign extend */
+ raw >>= (32-24); /* sign extend */
+ if(rx->PosDiv8)
+ raw *= 8;
+ param = (int)raw;
+ return rx.err;
+}
+CTR_Code CanTalonSRX::GetPulseWidthVelocity(int ¶m)
+{
+ GET_STATUS8();
+ int32_t raw = 0;
+ raw |= rx->PulseWidVelH;
+ raw <<= 8;
+ raw |= rx->PulseWidVelL;
+ raw <<= (32-16); /* sign extend */
+ raw >>= (32-16); /* sign extend */
+ if(rx->VelDiv4)
+ raw *= 4;
+ param = (int)raw;
+ return rx.err;
+}
+/**
+ * @param param [out] Rise to rise timeperiod in microseconds.
+ */
+CTR_Code CanTalonSRX::GetPulseWidthRiseToRiseUs(int ¶m)
+{
+ GET_STATUS8();
+ uint32_t raw = 0;
+ raw |= rx->PeriodUsM8;
+ raw <<= 8;
+ raw |= rx->PeriodUsL8;
+ param = (int)raw;
+ return rx.err;
+}
+/**
+ * @param param [out] Rise to fall time period in microseconds.
+ */
+CTR_Code CanTalonSRX::GetPulseWidthRiseToFallUs(int ¶m)
+{
+ int temp = 0;
+ int periodUs = 0;
+ /* first grab our 12.12 position */
+ CTR_Code retval1 = GetPulseWidthPosition(temp);
+ /* mask off number of turns */
+ temp &= 0xFFF;
+ /* next grab the waveform period. This value
+ * will be zero if we stop getting pulses **/
+ CTR_Code retval2 = GetPulseWidthRiseToRiseUs(periodUs);
+ /* now we have 0.12 position that is scaled to the waveform period.
+ Use fixed pt multiply to scale our 0.16 period into us.*/
+ param = (temp * periodUs) / BIT12;
+ /* pass the worst error code to caller.
+ Assume largest value is the most pressing error code.*/
+ return (CTR_Code)std::max((int)retval1, (int)retval2);
+}
+CTR_Code CanTalonSRX::IsPulseWidthSensorPresent(int ¶m)
+{
+ int periodUs = 0;
+ CTR_Code retval = GetPulseWidthRiseToRiseUs(periodUs);
+ /* if a nonzero period is present, we are getting good pules.
+ Otherwise the sensor is not present. */
+ if(periodUs != 0)
+ param = 1;
+ else
+ param = 0;
+ return retval;
+}
+//------------------ C interface --------------------------------------------//
+extern "C" {
+void *c_TalonSRX_Create(int deviceNumber, int controlPeriodMs)
+{
+ return new CanTalonSRX(deviceNumber, controlPeriodMs);
+}
+void c_TalonSRX_Destroy(void *handle)
+{
+ delete (CanTalonSRX*)handle;
+}
+CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value)
+{
+ return ((CanTalonSRX*)handle)->SetParam((CanTalonSRX::param_t)paramEnum, value);
+}
+CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum)
+{
+ return ((CanTalonSRX*)handle)->RequestParam((CanTalonSRX::param_t)paramEnum);
+}
+CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value)
+{
+ return ((CanTalonSRX*)handle)->GetParamResponse((CanTalonSRX::param_t)paramEnum, *value);
+}
+CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value)
+{
+ return ((CanTalonSRX*)handle)->GetParamResponseInt32((CanTalonSRX::param_t)paramEnum, *value);
+}
+CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, unsigned frameEnum, unsigned periodMs)
+{
+ return ((CanTalonSRX*)handle)->SetStatusFrameRate(frameEnum, periodMs);
+}
+CTR_Code c_TalonSRX_ClearStickyFaults(void *handle)
+{
+ return ((CanTalonSRX*)handle)->ClearStickyFaults();
+}
+CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_OverTemp(*param);
+}
+CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_UnderVoltage(*param);
+}
+CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_ForLim(*param);
+}
+CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_RevLim(*param);
+}
+CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_HardwareFailure(*param);
+}
+CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_ForSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFault_RevSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetStckyFault_OverTemp(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetStckyFault_UnderVoltage(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetStckyFault_ForLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetStckyFault_RevLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetStckyFault_ForSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetStckyFault_RevSoftLim(*param);
+}
+CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetAppliedThrottle(*param);
+}
+CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetCloseLoopErr(*param);
+}
+CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFeedbackDeviceSelect(*param);
+}
+CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetModeSelect(*param);
+}
+CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetLimitSwitchEn(*param);
+}
+CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetLimitSwitchClosedFor(*param);
+}
+CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetLimitSwitchClosedRev(*param);
+}
+CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetSensorPosition(*param);
+}
+CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetSensorVelocity(*param);
+}
+CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param)
+{
+ return ((CanTalonSRX*)handle)->GetCurrent(*param);
+}
+CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetBrakeIsEnabled(*param);
+}
+CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetEncPosition(*param);
+}
+CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetEncVel(*param);
+}
+CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetEncIndexRiseEvents(*param);
+}
+CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetQuadApin(*param);
+}
+CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetQuadBpin(*param);
+}
+CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetQuadIdxpin(*param);
+}
+CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetAnalogInWithOv(*param);
+}
+CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetAnalogInVel(*param);
+}
+CTR_Code c_TalonSRX_GetTemp(void *handle, double *param)
+{
+ return ((CanTalonSRX*)handle)->GetTemp(*param);
+}
+CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param)
+{
+ return ((CanTalonSRX*)handle)->GetBatteryV(*param);
+}
+CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetResetCount(*param);
+}
+CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetResetFlags(*param);
+}
+CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetFirmVers(*param);
+}
+CTR_Code c_TalonSRX_SetDemand(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetDemand(param);
+}
+CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetOverrideLimitSwitchEn(param);
+}
+CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetFeedbackDeviceSelect(param);
+}
+CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetRevMotDuringCloseLoopEn(param);
+}
+CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetOverrideBrakeType(param);
+}
+CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetModeSelect(param);
+}
+CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand)
+{
+ return ((CanTalonSRX*)handle)->SetModeSelect(modeSelect, demand);
+}
+CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetProfileSlotSelect(param);
+}
+CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetRampThrottle(param);
+}
+CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param)
+{
+ return ((CanTalonSRX*)handle)->SetRevFeedbackSensor(param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetPulseWidthPosition(*param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetPulseWidthVelocity(*param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetPulseWidthRiseToFallUs(*param);
+}
+CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->GetPulseWidthRiseToRiseUs(*param);
+}
+CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param)
+{
+ return ((CanTalonSRX*)handle)->IsPulseWidthSensorPresent(*param);
+}
+}
diff --git a/hal/lib/Athena/ctre/CtreCanNode.cpp b/hal/lib/Athena/ctre/CtreCanNode.cpp
new file mode 100644
index 0000000..18cd24b
--- /dev/null
+++ b/hal/lib/Athena/ctre/CtreCanNode.cpp
@@ -0,0 +1,101 @@
+#pragma GCC diagnostic ignored "-Wmissing-field-initializers"
+
+#include "ctre/CtreCanNode.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h"
+#include <string.h> // memset
+#include <unistd.h> // usleep
+
+static const UINT32 kFullMessageIDMask = 0x1fffffff;
+
+CtreCanNode::CtreCanNode(UINT8 deviceNumber)
+{
+ _deviceNumber = deviceNumber;
+}
+CtreCanNode::~CtreCanNode()
+{
+}
+void CtreCanNode::RegisterRx(uint32_t arbId)
+{
+ /* no need to do anything, we just use new API to poll last received message */
+}
+void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs)
+{
+ int32_t status = 0;
+
+ txJob_t job = {0};
+ job.arbId = arbId;
+ job.periodMs = periodMs;
+ _txJobs[arbId] = job;
+ FRC_NetworkCommunication_CANSessionMux_sendMessage( job.arbId,
+ job.toSend,
+ 8,
+ job.periodMs,
+ &status);
+}
+timespec diff(const timespec & start, const timespec & end)
+{
+ timespec temp;
+ if ((end.tv_nsec-start.tv_nsec)<0) {
+ temp.tv_sec = end.tv_sec-start.tv_sec-1;
+ temp.tv_nsec = 1000000000+end.tv_nsec-start.tv_nsec;
+ } else {
+ temp.tv_sec = end.tv_sec-start.tv_sec;
+ temp.tv_nsec = end.tv_nsec-start.tv_nsec;
+ }
+ return temp;
+}
+CTR_Code CtreCanNode::GetRx(uint32_t arbId,uint8_t * dataBytes, uint32_t timeoutMs)
+{
+ CTR_Code retval = CTR_OKAY;
+ int32_t status = 0;
+ uint8_t len = 0;
+ uint32_t timeStamp;
+ /* cap timeout at 999ms */
+ if(timeoutMs > 999)
+ timeoutMs = 999;
+ FRC_NetworkCommunication_CANSessionMux_receiveMessage(&arbId,kFullMessageIDMask,dataBytes,&len,&timeStamp,&status);
+ if(status == 0){
+ /* fresh update */
+ rxEvent_t & r = _rxRxEvents[arbId]; /* lookup entry or make a default new one with all zeroes */
+ clock_gettime(2,&r.time); /* fill in time */
+ memcpy(r.bytes, dataBytes, 8); /* fill in databytes */
+ }else{
+ /* did not get the message */
+ rxRxEvents_t::iterator i = _rxRxEvents.find(arbId);
+ if(i == _rxRxEvents.end()){
+ /* we've never gotten this mesage */
+ retval = CTR_RxTimeout;
+ /* fill caller's buffer with zeros */
+ memset(dataBytes,0,8);
+ }else{
+ /* we've gotten this message before but not recently */
+ memcpy(dataBytes,i->second.bytes,8);
+ /* get the time now */
+ struct timespec temp;
+ clock_gettime(2,&temp); /* get now */
+ /* how long has it been? */
+ temp = diff(i->second.time,temp); /* temp = now - last */
+ if(temp.tv_sec > 0){
+ retval = CTR_RxTimeout;
+ }else if(temp.tv_nsec > ((int32_t)timeoutMs*1000*1000)){
+ retval = CTR_RxTimeout;
+ }else {
+ /* our last update was recent enough */
+ }
+ }
+ }
+
+ return retval;
+}
+void CtreCanNode::FlushTx(uint32_t arbId)
+{
+ int32_t status = 0;
+ txJobs_t::iterator iter = _txJobs.find(arbId);
+ if(iter != _txJobs.end())
+ FRC_NetworkCommunication_CANSessionMux_sendMessage( iter->second.arbId,
+ iter->second.toSend,
+ 8,
+ iter->second.periodMs,
+ &status);
+}
+
diff --git a/hal/lib/Athena/ctre/PCM.cpp b/hal/lib/Athena/ctre/PCM.cpp
new file mode 100644
index 0000000..58f8bc9
--- /dev/null
+++ b/hal/lib/Athena/ctre/PCM.cpp
@@ -0,0 +1,557 @@
+#pragma GCC diagnostic ignored "-Wmissing-field-initializers"
+
+#include "ctre/PCM.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h"
+#include <string.h> // memset
+#include <unistd.h> // usleep
+/* This can be a constant, as long as nobody needs to update solenoids within
+ 1/50 of a second. */
+static const INT32 kCANPeriod = 20;
+
+#define STATUS_1 0x9041400
+#define STATUS_SOL_FAULTS 0x9041440
+#define STATUS_DEBUG 0x9041480
+
+#define EXPECTED_RESPONSE_TIMEOUT_MS (50)
+#define GET_PCM_STATUS() CtreCanNode::recMsg<PcmStatus_t> rx = GetRx<PcmStatus_t> (STATUS_1|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_PCM_SOL_FAULTS() CtreCanNode::recMsg<PcmStatusFault_t> rx = GetRx<PcmStatusFault_t> (STATUS_SOL_FAULTS|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_PCM_DEBUG() CtreCanNode::recMsg<PcmDebug_t> rx = GetRx<PcmDebug_t> (STATUS_DEBUG|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)
+
+#define CONTROL_1 0x09041C00 /* PCM_Control */
+#define CONTROL_2 0x09041C40 /* PCM_SupplemControl */
+#define CONTROL_3 0x09041C80 /* PcmControlSetOneShotDur_t */
+
+/* encoder/decoders */
+typedef struct _PcmStatus_t{
+ /* Byte 0 */
+ unsigned SolenoidBits:8;
+ /* Byte 1 */
+ unsigned compressorOn:1;
+ unsigned stickyFaultFuseTripped:1;
+ unsigned stickyFaultCompCurrentTooHigh:1;
+ unsigned faultFuseTripped:1;
+ unsigned faultCompCurrentTooHigh:1;
+ unsigned faultHardwareFailure:1;
+ unsigned isCloseloopEnabled:1;
+ unsigned pressureSwitchEn:1;
+ /* Byte 2*/
+ unsigned battVoltage:8;
+ /* Byte 3 */
+ unsigned solenoidVoltageTop8:8;
+ /* Byte 4 */
+ unsigned compressorCurrentTop6:6;
+ unsigned solenoidVoltageBtm2:2;
+ /* Byte 5 */
+ unsigned StickyFault_dItooHigh :1;
+ unsigned Fault_dItooHigh :1;
+ unsigned moduleEnabled:1;
+ unsigned closedLoopOutput:1;
+ unsigned compressorCurrentBtm4:4;
+ /* Byte 6 */
+ unsigned tokenSeedTop8:8;
+ /* Byte 7 */
+ unsigned tokenSeedBtm8:8;
+}PcmStatus_t;
+
+typedef struct _PcmControl_t{
+ /* Byte 0 */
+ unsigned tokenTop8:8;
+ /* Byte 1 */
+ unsigned tokenBtm8:8;
+ /* Byte 2 */
+ unsigned solenoidBits:8;
+ /* Byte 3*/
+ unsigned reserved:4;
+ unsigned closeLoopOutput:1;
+ unsigned compressorOn:1;
+ unsigned closedLoopEnable:1;
+ unsigned clearStickyFaults:1;
+ /* Byte 4 */
+ unsigned OneShotField_h8:8;
+ /* Byte 5 */
+ unsigned OneShotField_l8:8;
+}PcmControl_t;
+
+typedef struct _PcmControlSetOneShotDur_t{
+ uint8_t sol10MsPerUnit[8];
+}PcmControlSetOneShotDur_t;
+
+typedef struct _PcmStatusFault_t{
+ /* Byte 0 */
+ unsigned SolenoidBlacklist:8;
+ /* Byte 1 */
+ unsigned reserved_bit0 :1;
+ unsigned reserved_bit1 :1;
+ unsigned reserved_bit2 :1;
+ unsigned reserved_bit3 :1;
+ unsigned StickyFault_CompNoCurrent :1;
+ unsigned Fault_CompNoCurrent :1;
+ unsigned StickyFault_SolenoidJumper :1;
+ unsigned Fault_SolenoidJumper :1;
+}PcmStatusFault_t;
+
+typedef struct _PcmDebug_t{
+ unsigned tokFailsTop8:8;
+ unsigned tokFailsBtm8:8;
+ unsigned lastFailedTokTop8:8;
+ unsigned lastFailedTokBtm8:8;
+ unsigned tokSuccessTop8:8;
+ unsigned tokSuccessBtm8:8;
+}PcmDebug_t;
+
+
+/* PCM Constructor - Clears all vars, establishes default settings, starts PCM background process
+ *
+ * @Return - void
+ *
+ * @Param - deviceNumber - Device ID of PCM to be controlled
+ */
+PCM::PCM(UINT8 deviceNumber): CtreCanNode(deviceNumber)
+{
+ RegisterRx(STATUS_1 | deviceNumber );
+ RegisterRx(STATUS_SOL_FAULTS | deviceNumber );
+ RegisterRx(STATUS_DEBUG | deviceNumber );
+ RegisterTx(CONTROL_1 | deviceNumber, kCANPeriod);
+ /* enable close loop */
+ SetClosedLoopControl(1);
+}
+/* PCM D'tor
+ */
+PCM::~PCM()
+{
+
+}
+
+/* Set PCM solenoid state
+ *
+ * @Return - CTR_Code - Error code (if any) for setting solenoid
+ *
+ * @Param - idx - ID of solenoid (0-7)
+ * @Param - en - Enable / Disable identified solenoid
+ */
+CTR_Code PCM::SetSolenoid(unsigned char idx, bool en)
+{
+ CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+ if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+ if (en)
+ toFill->solenoidBits |= (1ul << (idx));
+ else
+ toFill->solenoidBits &= ~(1ul << (idx));
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+
+/* Clears PCM sticky faults (indicators of past faults
+ *
+ * @Return - CTR_Code - Error code (if any) for setting solenoid
+ *
+ * @Param - clr - Clear / do not clear faults
+ */
+CTR_Code PCM::ClearStickyFaults()
+{
+ int32_t status = 0;
+ uint8_t pcmSupplemControl[] = { 0, 0, 0, 0x80 }; /* only bit set is ClearStickyFaults */
+ FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_2 | GetDeviceNumber(), pcmSupplemControl, sizeof(pcmSupplemControl), 0, &status);
+ if(status)
+ return CTR_TxFailed;
+ return CTR_OKAY;
+}
+
+/* Enables PCM Closed Loop Control of Compressor via pressure switch
+ *
+ * @Return - CTR_Code - Error code (if any) for setting solenoid
+ *
+ * @Param - en - Enable / Disable Closed Loop Control
+ */
+CTR_Code PCM::SetClosedLoopControl(bool en)
+{
+ CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+ if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+ toFill->closedLoopEnable = en;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+/* Get solenoid Blacklist status
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - idx - ID of solenoid [0,7] to fire one shot pulse.
+ */
+CTR_Code PCM::FireOneShotSolenoid(UINT8 idx)
+{
+ CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+ if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+ /* grab field as it is now */
+ uint16_t oneShotField;
+ oneShotField = toFill->OneShotField_h8;
+ oneShotField <<= 8;
+ oneShotField |= toFill->OneShotField_l8;
+ /* get the caller's channel */
+ uint16_t shift = 2*idx;
+ uint16_t mask = 3; /* two bits wide */
+ uint8_t chBits = (oneShotField >> shift) & mask;
+ /* flip it */
+ chBits = (chBits)%3 + 1;
+ /* clear out 2bits for this channel*/
+ oneShotField &= ~(mask << shift);
+ /* put new field in */
+ oneShotField |= chBits << shift;
+ /* apply field as it is now */
+ toFill->OneShotField_h8 = oneShotField >> 8;
+ toFill->OneShotField_l8 = oneShotField;
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+/* Configure the pulse width of a solenoid channel for one-shot pulse.
+ * Preprogrammed pulsewidth is 10ms resolute and can be between 20ms and 5.1s.
+ * @Return - CTR_Code - Error code (if any)
+ * @Param - idx - ID of solenoid [0,7] to configure.
+ * @Param - durMs - pulse width in ms.
+ */
+CTR_Code PCM::SetOneShotDurationMs(UINT8 idx,uint32_t durMs)
+{
+ /* sanity check caller's param */
+ if(idx > 7)
+ return CTR_InvalidParamValue;
+ /* get latest tx frame */
+ CtreCanNode::txTask<PcmControlSetOneShotDur_t> toFill = GetTx<PcmControlSetOneShotDur_t>(CONTROL_3 | GetDeviceNumber());
+ if(toFill.IsEmpty()){
+ /* only send this out if caller wants to do one-shots */
+ RegisterTx(CONTROL_3 | _deviceNumber, kCANPeriod);
+ /* grab it */
+ toFill = GetTx<PcmControlSetOneShotDur_t>(CONTROL_3 | GetDeviceNumber());
+ }
+ toFill->sol10MsPerUnit[idx] = std::min(durMs/10,(uint32_t)0xFF);
+ /* apply the new data bytes */
+ FlushTx(toFill);
+ return CTR_OKAY;
+}
+
+/* Get solenoid state
+ *
+ * @Return - True/False - True if solenoid enabled, false otherwise
+ *
+ * @Param - idx - ID of solenoid (0-7) to return status of
+ */
+CTR_Code PCM::GetSolenoid(UINT8 idx, bool &status)
+{
+ GET_PCM_STATUS();
+ status = (rx->SolenoidBits & (1ul<<(idx)) ) ? 1 : 0;
+ return rx.err;
+}
+
+/* Get solenoid state for all solenoids on the PCM
+ *
+ * @Return - Bitfield of solenoid states
+ */
+CTR_Code PCM::GetAllSolenoids(UINT8 &status)
+{
+ GET_PCM_STATUS();
+ status = rx->SolenoidBits;
+ return rx.err;
+}
+
+/* Get pressure switch state
+ *
+ * @Return - True/False - True if pressure adequate, false if low
+ */
+CTR_Code PCM::GetPressure(bool &status)
+{
+ GET_PCM_STATUS();
+ status = (rx->pressureSwitchEn ) ? 1 : 0;
+ return rx.err;
+}
+
+/* Get compressor state
+ *
+ * @Return - True/False - True if enabled, false if otherwise
+ */
+CTR_Code PCM::GetCompressor(bool &status)
+{
+ GET_PCM_STATUS();
+ status = (rx->compressorOn);
+ return rx.err;
+}
+
+/* Get closed loop control state
+ *
+ * @Return - True/False - True if closed loop enabled, false if otherwise
+ */
+CTR_Code PCM::GetClosedLoopControl(bool &status)
+{
+ GET_PCM_STATUS();
+ status = (rx->isCloseloopEnabled);
+ return rx.err;
+}
+
+/* Get compressor current draw
+ *
+ * @Return - Amperes - Compressor current
+ */
+CTR_Code PCM::GetCompressorCurrent(float &status)
+{
+ GET_PCM_STATUS();
+ uint32_t temp =(rx->compressorCurrentTop6);
+ temp <<= 4;
+ temp |= rx->compressorCurrentBtm4;
+ status = temp * 0.03125; /* 5.5 fixed pt value in Amps */
+ return rx.err;
+}
+
+/* Get voltage across solenoid rail
+ *
+ * @Return - Volts - Voltage across solenoid rail
+ */
+CTR_Code PCM::GetSolenoidVoltage(float &status)
+{
+ GET_PCM_STATUS();
+ uint32_t raw =(rx->solenoidVoltageTop8);
+ raw <<= 2;
+ raw |= rx->solenoidVoltageBtm2;
+ status = (double) raw * 0.03125; /* 5.5 fixed pt value in Volts */
+ return rx.err;
+}
+
+/* Get hardware fault value
+ *
+ * @Return - True/False - True if hardware failure detected, false if otherwise
+ */
+CTR_Code PCM::GetHardwareFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->faultHardwareFailure;
+ return rx.err;
+}
+
+/* Get compressor fault value
+ *
+ * @Return - True/False - True if shorted compressor detected, false if otherwise
+ */
+CTR_Code PCM::GetCompressorCurrentTooHighFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->faultCompCurrentTooHigh;
+ return rx.err;
+}
+CTR_Code PCM::GetCompressorShortedStickyFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->StickyFault_dItooHigh;
+ return rx.err;
+}
+CTR_Code PCM::GetCompressorShortedFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->Fault_dItooHigh;
+ return rx.err;
+}
+CTR_Code PCM::GetCompressorNotConnectedStickyFault(bool &status)
+{
+ GET_PCM_SOL_FAULTS();
+ status = rx->StickyFault_CompNoCurrent;
+ return rx.err;
+}
+CTR_Code PCM::GetCompressorNotConnectedFault(bool &status)
+{
+ GET_PCM_SOL_FAULTS();
+ status = rx->Fault_CompNoCurrent;
+ return rx.err;
+}
+
+/* Get solenoid fault value
+ *
+ * @Return - True/False - True if shorted solenoid detected, false if otherwise
+ */
+CTR_Code PCM::GetSolenoidFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->faultFuseTripped;
+ return rx.err;
+}
+
+/* Get compressor sticky fault value
+ *
+ * @Return - True/False - True if solenoid had previously been shorted
+ * (and sticky fault was not cleared), false if otherwise
+ */
+CTR_Code PCM::GetCompressorCurrentTooHighStickyFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->stickyFaultCompCurrentTooHigh;
+ return rx.err;
+}
+
+/* Get solenoid sticky fault value
+ *
+ * @Return - True/False - True if compressor had previously been shorted
+ * (and sticky fault was not cleared), false if otherwise
+ */
+CTR_Code PCM::GetSolenoidStickyFault(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->stickyFaultFuseTripped;
+ return rx.err;
+}
+/* Get battery voltage
+ *
+ * @Return - Volts - Voltage across PCM power ports
+ */
+CTR_Code PCM::GetBatteryVoltage(float &status)
+{
+ GET_PCM_STATUS();
+ status = (float)rx->battVoltage * 0.05 + 4.0; /* 50mV per unit plus 4V. */
+ return rx.err;
+}
+/* Return status of module enable/disable
+ *
+ * @Return - bool - Returns TRUE if PCM is enabled, FALSE if disabled
+ */
+CTR_Code PCM::isModuleEnabled(bool &status)
+{
+ GET_PCM_STATUS();
+ status = rx->moduleEnabled;
+ return rx.err;
+}
+/* Get number of total failed PCM Control Frame
+ *
+ * @Return - Failed Control Frames - Number of failed control frames (tokenization fails)
+ *
+ * @WARNING - Return only valid if [SeekDebugFrames] is enabled
+ * See function SeekDebugFrames
+ * See function EnableSeekDebugFrames
+ */
+CTR_Code PCM::GetNumberOfFailedControlFrames(UINT16 &status)
+{
+ GET_PCM_DEBUG();
+ status = rx->tokFailsTop8;
+ status <<= 8;
+ status |= rx->tokFailsBtm8;
+ return rx.err;
+}
+/* Get raw Solenoid Blacklist
+ *
+ * @Return - BINARY - Raw binary breakdown of Solenoid Blacklist
+ * BIT7 = Solenoid 1, BIT6 = Solenoid 2, etc.
+ *
+ * @WARNING - Return only valid if [SeekStatusFaultFrames] is enabled
+ * See function SeekStatusFaultFrames
+ * See function EnableSeekStatusFaultFrames
+ */
+CTR_Code PCM::GetSolenoidBlackList(UINT8 &status)
+{
+ GET_PCM_SOL_FAULTS();
+ status = rx->SolenoidBlacklist;
+ return rx.err;
+}
+/* Get solenoid Blacklist status
+ * - Blacklisted solenoids cannot be enabled until PCM is power cycled
+ *
+ * @Return - True/False - True if Solenoid is blacklisted, false if otherwise
+ *
+ * @Param - idx - ID of solenoid [0,7]
+ *
+ * @WARNING - Return only valid if [SeekStatusFaultFrames] is enabled
+ * See function SeekStatusFaultFrames
+ * See function EnableSeekStatusFaultFrames
+ */
+CTR_Code PCM::IsSolenoidBlacklisted(UINT8 idx, bool &status)
+{
+ GET_PCM_SOL_FAULTS();
+ status = (rx->SolenoidBlacklist & (1ul<<(idx)) )? 1 : 0;
+ return rx.err;
+}
+//------------------ C interface --------------------------------------------//
+extern "C" {
+ void * c_PCM_Init(void) {
+ return new PCM();
+ }
+ CTR_Code c_SetSolenoid(void * handle, unsigned char idx, INT8 param) {
+ return ((PCM*) handle)->SetSolenoid(idx, param);
+ }
+ CTR_Code c_SetClosedLoopControl(void * handle, INT8 param) {
+ return ((PCM*) handle)->SetClosedLoopControl(param);
+ }
+ CTR_Code c_ClearStickyFaults(void * handle, INT8 param) {
+ return ((PCM*) handle)->ClearStickyFaults();
+ }
+ CTR_Code c_GetSolenoid(void * handle, UINT8 idx, INT8 * status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetSolenoid(idx, bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetAllSolenoids(void * handle, UINT8 * status) {
+ return ((PCM*) handle)->GetAllSolenoids(*status);
+ }
+ CTR_Code c_GetPressure(void * handle, INT8 * status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetPressure(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetCompressor(void * handle, INT8 * status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetCompressor(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetClosedLoopControl(void * handle, INT8 * status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetClosedLoopControl(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetCompressorCurrent(void * handle, float * status) {
+ CTR_Code retval = ((PCM*) handle)->GetCompressorCurrent(*status);
+ return retval;
+ }
+ CTR_Code c_GetSolenoidVoltage(void * handle, float*status) {
+ return ((PCM*) handle)->GetSolenoidVoltage(*status);
+ }
+ CTR_Code c_GetHardwareFault(void * handle, INT8*status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetHardwareFault(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetCompressorFault(void * handle, INT8*status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetCompressorCurrentTooHighFault(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetSolenoidFault(void * handle, INT8*status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetSolenoidFault(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetCompressorStickyFault(void * handle, INT8*status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetCompressorCurrentTooHighStickyFault(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetSolenoidStickyFault(void * handle, INT8*status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->GetSolenoidStickyFault(bstatus);
+ *status = bstatus;
+ return retval;
+ }
+ CTR_Code c_GetBatteryVoltage(void * handle, float*status) {
+ CTR_Code retval = ((PCM*) handle)->GetBatteryVoltage(*status);
+ return retval;
+ }
+ void c_SetDeviceNumber_PCM(void * handle, UINT8 deviceNumber) {
+ }
+ CTR_Code c_GetNumberOfFailedControlFrames(void * handle, UINT16*status) {
+ return ((PCM*) handle)->GetNumberOfFailedControlFrames(*status);
+ }
+ CTR_Code c_GetSolenoidBlackList(void * handle, UINT8 *status) {
+ return ((PCM*) handle)->GetSolenoidBlackList(*status);
+ }
+ CTR_Code c_IsSolenoidBlacklisted(void * handle, UINT8 idx, INT8*status) {
+ bool bstatus;
+ CTR_Code retval = ((PCM*) handle)->IsSolenoidBlacklisted(idx, bstatus);
+ *status = bstatus;
+ return retval;
+ }
+}
diff --git a/hal/lib/Athena/ctre/PDP.cpp b/hal/lib/Athena/ctre/PDP.cpp
new file mode 100644
index 0000000..cae2264
--- /dev/null
+++ b/hal/lib/Athena/ctre/PDP.cpp
@@ -0,0 +1,231 @@
+#include "ctre/PDP.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h" //CAN Comm
+#include <string.h> // memset
+#include <unistd.h> // usleep
+
+#define STATUS_1 0x8041400
+#define STATUS_2 0x8041440
+#define STATUS_3 0x8041480
+#define STATUS_ENERGY 0x8041740
+
+#define CONTROL_1 0x08041C00 /* PDP_Control_ClearStats */
+
+#define EXPECTED_RESPONSE_TIMEOUT_MS (50)
+#define GET_STATUS1() CtreCanNode::recMsg<PdpStatus1_t> rx = GetRx<PdpStatus1_t>(STATUS_1,EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS2() CtreCanNode::recMsg<PdpStatus2_t> rx = GetRx<PdpStatus2_t>(STATUS_2,EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS3() CtreCanNode::recMsg<PdpStatus3_t> rx = GetRx<PdpStatus3_t>(STATUS_3,EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_STATUS_ENERGY() CtreCanNode::recMsg<PDP_Status_Energy_t> rx = GetRx<PDP_Status_Energy_t>(STATUS_ENERGY,EXPECTED_RESPONSE_TIMEOUT_MS)
+
+/* encoder/decoders */
+typedef struct _PdpStatus1_t{
+ unsigned chan1_h8:8;
+ unsigned chan2_h6:6;
+ unsigned chan1_l2:2;
+ unsigned chan3_h4:4;
+ unsigned chan2_l4:4;
+ unsigned chan4_h2:2;
+ unsigned chan3_l6:6;
+ unsigned chan4_l8:8;
+ unsigned chan5_h8:8;
+ unsigned chan6_h6:6;
+ unsigned chan5_l2:2;
+ unsigned reserved4:4;
+ unsigned chan6_l4:4;
+}PdpStatus1_t;
+typedef struct _PdpStatus2_t{
+ unsigned chan7_h8:8;
+ unsigned chan8_h6:6;
+ unsigned chan7_l2:2;
+ unsigned chan9_h4:4;
+ unsigned chan8_l4:4;
+ unsigned chan10_h2:2;
+ unsigned chan9_l6:6;
+ unsigned chan10_l8:8;
+ unsigned chan11_h8:8;
+ unsigned chan12_h6:6;
+ unsigned chan11_l2:2;
+ unsigned reserved4:4;
+ unsigned chan12_l4:4;
+}PdpStatus2_t;
+typedef struct _PdpStatus3_t{
+ unsigned chan13_h8:8;
+ unsigned chan14_h6:6;
+ unsigned chan13_l2:2;
+ unsigned chan15_h4:4;
+ unsigned chan14_l4:4;
+ unsigned chan16_h2:2;
+ unsigned chan15_l6:6;
+ unsigned chan16_l8:8;
+ unsigned internalResBattery_mOhms:8;
+ unsigned busVoltage:8;
+ unsigned temp:8;
+}PdpStatus3_t;
+typedef struct _PDP_Status_Energy_t {
+ unsigned TmeasMs_likelywillbe20ms_:8;
+ unsigned TotalCurrent_125mAperunit_h8:8;
+ unsigned Power_125mWperunit_h4:4;
+ unsigned TotalCurrent_125mAperunit_l4:4;
+ unsigned Power_125mWperunit_m8:8;
+ unsigned Energy_125mWPerUnitXTmeas_h4:4;
+ unsigned Power_125mWperunit_l4:4;
+ unsigned Energy_125mWPerUnitXTmeas_mh8:8;
+ unsigned Energy_125mWPerUnitXTmeas_ml8:8;
+ unsigned Energy_125mWPerUnitXTmeas_l8:8;
+} PDP_Status_Energy_t ;
+
+PDP::PDP(UINT8 deviceNumber): CtreCanNode(deviceNumber)
+{
+ RegisterRx(STATUS_1 | deviceNumber );
+ RegisterRx(STATUS_2 | deviceNumber );
+ RegisterRx(STATUS_3 | deviceNumber );
+}
+/* PDP D'tor
+ */
+PDP::~PDP()
+{
+}
+
+CTR_Code PDP::GetChannelCurrent(UINT8 idx, double ¤t)
+{
+ CTR_Code retval = CTR_InvalidParamValue;
+ uint32_t raw = 0;
+
+ if(idx <= 5){
+ GET_STATUS1();
+ retval = rx.err;
+ switch(idx){
+ case 0: raw = ((uint32_t)rx->chan1_h8 << 2) | rx->chan1_l2; break;
+ case 1: raw = ((uint32_t)rx->chan2_h6 << 4) | rx->chan2_l4; break;
+ case 2: raw = ((uint32_t)rx->chan3_h4 << 6) | rx->chan3_l6; break;
+ case 3: raw = ((uint32_t)rx->chan4_h2 << 8) | rx->chan4_l8; break;
+ case 4: raw = ((uint32_t)rx->chan5_h8 << 2) | rx->chan5_l2; break;
+ case 5: raw = ((uint32_t)rx->chan6_h6 << 4) | rx->chan6_l4; break;
+ default: retval = CTR_InvalidParamValue; break;
+ }
+ }else if(idx <= 11){
+ GET_STATUS2();
+ retval = rx.err;
+ switch(idx){
+ case 6: raw = ((uint32_t)rx->chan7_h8 << 2) | rx->chan7_l2; break;
+ case 7: raw = ((uint32_t)rx->chan8_h6 << 4) | rx->chan8_l4; break;
+ case 8: raw = ((uint32_t)rx->chan9_h4 << 6) | rx->chan9_l6; break;
+ case 9: raw = ((uint32_t)rx->chan10_h2 << 8) | rx->chan10_l8; break;
+ case 10: raw = ((uint32_t)rx->chan11_h8 << 2) | rx->chan11_l2; break;
+ case 11: raw = ((uint32_t)rx->chan12_h6 << 4) | rx->chan12_l4; break;
+ default: retval = CTR_InvalidParamValue; break;
+ }
+ }else if(idx <= 15){
+ GET_STATUS3();
+ retval = rx.err;
+ switch(idx){
+ case 12: raw = ((uint32_t)rx->chan13_h8 << 2) | rx->chan13_l2; break;
+ case 13: raw = ((uint32_t)rx->chan14_h6 << 4) | rx->chan14_l4; break;
+ case 14: raw = ((uint32_t)rx->chan15_h4 << 6) | rx->chan15_l6; break;
+ case 15: raw = ((uint32_t)rx->chan16_h2 << 8) | rx->chan16_l8; break;
+ default: retval = CTR_InvalidParamValue; break;
+ }
+ }
+ /* convert to amps */
+ current = (double)raw * 0.125; /* 7.3 fixed pt value in Amps */
+ /* signal caller with success */
+ return retval;
+}
+CTR_Code PDP::GetVoltage(double &voltage)
+{
+ GET_STATUS3();
+ uint32_t raw = rx->busVoltage;
+ voltage = (double)raw * 0.05 + 4.0; /* 50mV per unit plus 4V. */;
+ return rx.err;
+}
+CTR_Code PDP::GetTemperature(double &tempC)
+{
+ GET_STATUS3();
+ uint32_t raw = rx->temp;
+ tempC = (double)raw * 1.03250836957542 - 67.8564500484966;
+ return rx.err;
+}
+CTR_Code PDP::GetTotalCurrent(double ¤tAmps)
+{
+ GET_STATUS_ENERGY();
+ uint32_t raw;
+ raw = rx->TotalCurrent_125mAperunit_h8;
+ raw <<= 4;
+ raw |= rx->TotalCurrent_125mAperunit_l4;
+ currentAmps = 0.125 * raw;
+ return rx.err;
+}
+CTR_Code PDP::GetTotalPower(double &powerWatts)
+{
+ GET_STATUS_ENERGY();
+ uint32_t raw;
+ raw = rx->Power_125mWperunit_h4;
+ raw <<= 8;
+ raw |= rx->Power_125mWperunit_m8;
+ raw <<= 4;
+ raw |= rx->Power_125mWperunit_l4;
+ powerWatts = 0.125 * raw;
+ return rx.err;
+}
+CTR_Code PDP::GetTotalEnergy(double &energyJoules)
+{
+ GET_STATUS_ENERGY();
+ uint32_t raw;
+ raw = rx->Energy_125mWPerUnitXTmeas_h4;
+ raw <<= 8;
+ raw |= rx->Energy_125mWPerUnitXTmeas_mh8;
+ raw <<= 8;
+ raw |= rx->Energy_125mWPerUnitXTmeas_ml8;
+ raw <<= 8;
+ raw |= rx->Energy_125mWPerUnitXTmeas_l8;
+ energyJoules = 0.125 * raw; /* mW integrated every TmeasMs */
+ energyJoules *= 0.001; /* convert from mW to W */
+ energyJoules *= rx->TmeasMs_likelywillbe20ms_; /* multiplied by TmeasMs = joules */
+ return rx.err;
+}
+/* Clear sticky faults.
+ * @Return - CTR_Code - Error code (if any)
+ */
+CTR_Code PDP::ClearStickyFaults()
+{
+ int32_t status = 0;
+ uint8_t pdpControl[] = { 0x80 }; /* only bit set is ClearStickyFaults */
+ FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_1 | GetDeviceNumber(), pdpControl, sizeof(pdpControl), 0, &status);
+ if(status)
+ return CTR_TxFailed;
+ return CTR_OKAY;
+}
+
+/* Reset Energy Signals
+ * @Return - CTR_Code - Error code (if any)
+ */
+CTR_Code PDP::ResetEnergy()
+{
+ int32_t status = 0;
+ uint8_t pdpControl[] = { 0x40 }; /* only bit set is ResetEnergy */
+ FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_1 | GetDeviceNumber(), pdpControl, sizeof(pdpControl), 0, &status);
+ if(status)
+ return CTR_TxFailed;
+ return CTR_OKAY;
+}
+//------------------ C interface --------------------------------------------//
+extern "C" {
+ void * c_PDP_Init(void)
+ {
+ return new PDP();
+ }
+ CTR_Code c_GetChannelCurrent(void * handle,UINT8 idx, double *status)
+ {
+ return ((PDP*)handle)-> GetChannelCurrent(idx,*status);
+ }
+ CTR_Code c_GetVoltage(void * handle,double *status)
+ {
+ return ((PDP*)handle)-> GetVoltage(*status);
+ }
+ CTR_Code c_GetTemperature(void * handle,double *status)
+ {
+ return ((PDP*)handle)-> GetTemperature(*status);
+ }
+ void c_SetDeviceNumber_PDP(void * handle,UINT8 deviceNumber)
+ {
+ }
+}
diff --git a/hal/lib/Athena/frccansae/CANDeviceInterface.h b/hal/lib/Athena/frccansae/CANDeviceInterface.h
new file mode 100644
index 0000000..62a38cb
--- /dev/null
+++ b/hal/lib/Athena/frccansae/CANDeviceInterface.h
@@ -0,0 +1,156 @@
+#ifndef __CAN_DEVICE_INTERFACE_H__
+#define __CAN_DEVICE_INTERFACE_H__
+
+#define MAX_STRING_LEN 64
+
+#define SUPPORT_UNIQUE_ID (1) /* depends entirely on old vs new build */
+#define USE_NTH_ORDER (0) /* zero to user deviceId */
+#define SUPPORT_MOTOR_CONTROLLER_PROFILE (1)
+namespace CANDeviceInterface1
+{
+
+struct PIDSlot
+{
+ // Proportional gain
+ float pGain;
+ // Integral gain
+ float iGain;
+ // Differential gain
+ float dGain;
+ // Feed-forward gain
+ float fGain;
+ // Integral zone
+ float iZone;
+ // Closed-loop ramp rate
+ float clRampRate;
+};
+
+struct DeviceDescriptor
+{
+ // The full device ID, including the device number, manufacturer, and device type.
+ // The mask of a message the device supports is 0x1FFF003F.
+ unsigned int deviceID;
+#if SUPPORT_UNIQUE_ID != 0
+ // This is the ID that uniquely identifies the device node in the UI.
+ // The purpose of this is to be able to track the device across renames or deviceID changes.
+ unsigned int uniqueID;
+#endif
+ // An dynamically assigned ID that will make setting deviceIDs robust,
+ // Never again will you need to isolate a CAN node just to fix it's ID.
+ unsigned int dynamicID;
+ // User visible name. This can be customized by the user, but should have a
+ // reasonable default.
+ char name[MAX_STRING_LEN];
+ // This is a user visible model name that should match the can_devices.ini section.
+ char model[MAX_STRING_LEN];
+ // This is a version number that represents the version of firmware currently
+ // installed on the device.
+ char currentVersion[MAX_STRING_LEN];
+ // Hardware revision.
+ char hardwareRev[MAX_STRING_LEN];
+ // Bootloader version. Will not change for the life of the product, but additional
+ // field upgrade features could be added in newer hardware.
+ char bootloaderRev[MAX_STRING_LEN];
+ // Manufacture Date. Could be a calender date or just the FRC season year.
+ // Also helps troubleshooting "old ones" vs "new ones".
+ char manufactureDate[MAX_STRING_LEN];
+ // General status of the hardware. For example if the device is in bootloader
+ // due to a bad flash UI could emphasize that.
+ char softwareStatus[MAX_STRING_LEN];
+ // Is the LED currently on?
+ bool led;
+ // Reserved fields for future use by CTRE. Not touched by frccansae
+ unsigned int dynFlags;
+ unsigned int flags; /* bitfield */
+ unsigned int ptrToString;
+ //unsigned int reserved0;
+ //unsigned int reserved1;
+ //unsigned int reserved2;
+#if SUPPORT_MOTOR_CONTROLLER_PROFILE != 0
+ // Motor controller properties (ignored if SupportsMotorControllerProperties is false or unset for this model)
+ unsigned int brakeMode; // 0=Coast, 1=Brake
+ unsigned int limitSwitchFwdMode; // 0=disabled, 1=Normally Closed, 2=Normally Open
+ unsigned int limitSwitchRevMode; // 0=disabled, 1=Normally Closed, 2=Normally Open
+ // Limit-switch soft limits
+ bool bFwdSoftLimitEnable;
+ bool bRevSoftLimitEnable;
+ float softLimitFwd;
+ float softLimitRev;
+ // PID constants for slot 0
+ struct PIDSlot slot0;
+ // PID constants for slot 1
+ struct PIDSlot slot1;
+#endif
+};
+
+#define kLimitSwitchMode_Disabled (0)
+#define kLimitSwitchMode_NormallyClosed (1)
+#define kLimitSwitchMode_NormallyOpen (2)
+
+// Interface functions that must be implemented by the CAN Firmware Update Library
+
+// Returns the number of devices that will be returned in a call to
+// getListOfDevices(). The calling library will use this info to allocate enough
+// memory to accept all device info.
+int getNumberOfDevices();
+
+// Return info about discovered devices. The array of structs should be
+// populated before returning. The numDescriptors input describes how many
+// elements were allocated to prevent memory corruption. The number of devices
+// populated should be returned from this function as well.
+int getListOfDevices(DeviceDescriptor *devices, int numDescriptors);
+
+// When the user requests to update the firmware of a device a thread will be
+// spawned and this function is called from that thread. This function should
+// complete the firmware update process before returning. The image
+// contents and size are directly from the file selected by the user. The
+// error message string can be filled with a NULL-terminated message to show the
+// user if there was a problem updating firmware. The error message is only
+// displayed if a non-zero value is returned from this function.
+int updateFirmware(const DeviceDescriptor *device, const unsigned char *imageContents, unsigned int imageSize, char *errorMessage, int errorMessageMaxSize);
+
+// This function is called periodically from the UI thread while the firmware
+// update is in progress. The percentComplete parameter should the filled in
+// with the current progress of the firmware update process to update a progress
+// bar in the UI.
+void checkUpdateProgress(const DeviceDescriptor *device, int *percentComplete);
+
+// This is called when the user selects a new ID to assign on the bus and
+// chooses to save. The newDeviceID is really just the device number. The
+// manufacturer and device type will remain unchanged. If a problem is detected
+// when assigning a new ID, this function should return a non-zero value.
+int assignBroadcastDeviceID(unsigned int newDeviceID);
+// The device descriptor should be updated with the new device ID. The name may
+// also change in the descriptor and will be updated in the UI immediately.
+// Be sure to modify the descriptor first since the refresh from the UI is
+// asynchronous.
+int assignDeviceID(DeviceDescriptor *device, unsigned int newDeviceID);
+
+// This entry-point will get called when the user chooses to change the value
+// of the device's LED. This will allow the user to identify devices which
+// support dynamic addresses or are otherwise unknown. If this function returns
+// a non-zero value, the UI will report an error.
+int saveLightLed(const DeviceDescriptor *device, bool newLEDStatus);
+
+// This entry-point will get called when the user chooses to change the alias
+// of the device with the device specified. If this function returns a non-
+// zero value, the UI will report an error. The device descriptor must be
+// updated with the new name that was selected. If a different name is saved
+// to the descriptor than the user specified, this will require a manual
+// refresh by the user. This is reported as CAR #505139
+int saveDeviceName(DeviceDescriptor *device, const char *newName);
+
+// This entry-point will get called when the user changes any of the motor
+// controller specific properties. If this function returns a non-zero value,
+// the UI will report an error. The device descriptor may be updated with
+// coerced values.
+int saveMotorParameters(DeviceDescriptor *device);
+
+// Run some sort of self-test functionality on the device. This can be anything
+// and the results will be displayed to the user. A non-zero return value
+// indicates an error.
+int selfTest(const DeviceDescriptor *device, char *detailedResults, int detailedResultsMaxSize);
+
+} /* CANDeviceInterface */
+
+#endif /* __CAN_DEVICE_INTERFACE_H__ */
diff --git a/hal/lib/Athena/i2clib/i2c-lib.h b/hal/lib/Athena/i2clib/i2c-lib.h
new file mode 100644
index 0000000..b34cb33
--- /dev/null
+++ b/hal/lib/Athena/i2clib/i2c-lib.h
@@ -0,0 +1,16 @@
+#ifndef __I2C_LIB_H__
+#define __I2C_LIB_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+int i2clib_open(const char *device);
+void i2clib_close(int handle);
+int i2clib_read(int handle, uint8_t dev_addr, char *recv_buf, int32_t recv_size);
+int i2clib_write(int handle, uint8_t dev_addr, const char *send_buf, int32_t send_size);
+int i2clib_writeread(int handle, uint8_t dev_addr, const char *send_buf, int32_t send_size, char *recv_buf, int32_t recv_size);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __I2C_LIB_H__ */
\ No newline at end of file
diff --git a/hal/lib/Athena/spilib/spi-lib.h b/hal/lib/Athena/spilib/spi-lib.h
new file mode 100644
index 0000000..b5c2a7a
--- /dev/null
+++ b/hal/lib/Athena/spilib/spi-lib.h
@@ -0,0 +1,19 @@
+#ifndef __SPI_LIB_H__
+#define __SPI_LIB_H__
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+int spilib_open(const char *device);
+void spilib_close(int handle);
+int spilib_setspeed(int handle, uint32_t speed);
+int spilib_setbitsperword(int handle, uint8_t bpw);
+int spilib_setopts(int handle, int msb_first, int sample_on_trailing, int clk_idle_high);
+int spilib_read(int handle, char *recv_buf, int32_t size);
+int spilib_write(int handle, const char *send_buf, int32_t size);
+int spilib_writeread(int handle, const char *send_buf, char *recv_buf, int32_t size);
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __SPI_LIB_H__ */
\ No newline at end of file
diff --git a/hal/lib/Athena/visa/visa.h b/hal/lib/Athena/visa/visa.h
new file mode 100644
index 0000000..3c6ad30
--- /dev/null
+++ b/hal/lib/Athena/visa/visa.h
@@ -0,0 +1,1064 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc. */
+/* Contains National Instruments extensions. */
+/* Do not modify the contents of this file. */
+/*---------------------------------------------------------------------------*/
+/* */
+/* Title : VISA.H */
+/* Date : 10-09-2006 */
+/* Purpose : Include file for the VISA Library 4.0 specification */
+/* */
+/*---------------------------------------------------------------------------*/
+/* When using NI-VISA extensions, you must link with the VISA library that */
+/* comes with NI-VISA. Currently, the extensions provided by NI-VISA are: */
+/* */
+/* PXI (Compact PCI eXtensions for Instrumentation) and PCI support. To use */
+/* this, you must define the macro NIVISA_PXI before including this header. */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/* */
+/* A fast set of macros for viPeekXX/viPokeXX that guarantees binary */
+/* compatibility with other implementations of VISA. To use this, you must */
+/* define the macro NIVISA_PEEKPOKE before including this header. */
+/* */
+/* Support for USB devices that do not conform to a specific class. To use */
+/* this, you must define the macro NIVISA_USB before including this header. */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISA_HEADER__
+#define __VISA_HEADER__
+
+#include <stdarg.h>
+
+#if !defined(__VISATYPE_HEADER__)
+#include "visatype.h"
+#endif
+
+#define VI_SPEC_VERSION (0x00400000UL)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+ extern "C" {
+#endif
+
+#if defined(_CVI_)
+#pragma EnableLibraryRuntimeChecking
+#endif
+
+/*- VISA Types --------------------------------------------------------------*/
+
+typedef ViObject ViEvent;
+typedef ViEvent _VI_PTR ViPEvent;
+typedef ViObject ViFindList;
+typedef ViFindList _VI_PTR ViPFindList;
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+typedef ViUInt64 ViBusAddress;
+typedef ViUInt64 ViBusSize;
+typedef ViUInt64 ViAttrState;
+#else
+typedef ViUInt32 ViBusAddress;
+typedef ViUInt32 ViBusSize;
+typedef ViUInt32 ViAttrState;
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64 ViBusAddress64;
+typedef ViBusAddress64 _VI_PTR ViPBusAddress64;
+#endif
+
+typedef ViUInt32 ViEventType;
+typedef ViEventType _VI_PTR ViPEventType;
+typedef ViEventType _VI_PTR ViAEventType;
+typedef void _VI_PTR ViPAttrState;
+typedef ViAttr _VI_PTR ViPAttr;
+typedef ViAttr _VI_PTR ViAAttr;
+
+typedef ViString ViKeyId;
+typedef ViPString ViPKeyId;
+typedef ViUInt32 ViJobId;
+typedef ViJobId _VI_PTR ViPJobId;
+typedef ViUInt32 ViAccessMode;
+typedef ViAccessMode _VI_PTR ViPAccessMode;
+typedef ViBusAddress _VI_PTR ViPBusAddress;
+typedef ViUInt32 ViEventFilter;
+
+typedef va_list ViVAList;
+
+typedef ViStatus (_VI_FUNCH _VI_PTR ViHndlr)
+ (ViSession vi, ViEventType eventType, ViEvent event, ViAddr userHandle);
+
+/*- Resource Manager Functions and Operations -------------------------------*/
+
+ViStatus _VI_FUNC viOpenDefaultRM (ViPSession vi);
+ViStatus _VI_FUNC viFindRsrc (ViSession sesn, ViString expr, ViPFindList vi,
+ ViPUInt32 retCnt, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC viFindNext (ViFindList vi, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC viParseRsrc (ViSession rmSesn, ViRsrc rsrcName,
+ ViPUInt16 intfType, ViPUInt16 intfNum);
+ViStatus _VI_FUNC viParseRsrcEx (ViSession rmSesn, ViRsrc rsrcName, ViPUInt16 intfType,
+ ViPUInt16 intfNum, ViChar _VI_FAR rsrcClass[],
+ ViChar _VI_FAR expandedUnaliasedName[],
+ ViChar _VI_FAR aliasIfExists[]);
+ViStatus _VI_FUNC viOpen (ViSession sesn, ViRsrc name, ViAccessMode mode,
+ ViUInt32 timeout, ViPSession vi);
+
+/*- Resource Template Operations --------------------------------------------*/
+
+ViStatus _VI_FUNC viClose (ViObject vi);
+ViStatus _VI_FUNC viSetAttribute (ViObject vi, ViAttr attrName, ViAttrState attrValue);
+ViStatus _VI_FUNC viGetAttribute (ViObject vi, ViAttr attrName, void _VI_PTR attrValue);
+ViStatus _VI_FUNC viStatusDesc (ViObject vi, ViStatus status, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC viTerminate (ViObject vi, ViUInt16 degree, ViJobId jobId);
+
+ViStatus _VI_FUNC viLock (ViSession vi, ViAccessMode lockType, ViUInt32 timeout,
+ ViKeyId requestedKey, ViChar _VI_FAR accessKey[]);
+ViStatus _VI_FUNC viUnlock (ViSession vi);
+ViStatus _VI_FUNC viEnableEvent (ViSession vi, ViEventType eventType, ViUInt16 mechanism,
+ ViEventFilter context);
+ViStatus _VI_FUNC viDisableEvent (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC viDiscardEvents (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC viWaitOnEvent (ViSession vi, ViEventType inEventType, ViUInt32 timeout,
+ ViPEventType outEventType, ViPEvent outContext);
+ViStatus _VI_FUNC viInstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+ ViAddr userHandle);
+ViStatus _VI_FUNC viUninstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+ ViAddr userHandle);
+
+/*- Basic I/O Operations ----------------------------------------------------*/
+
+ViStatus _VI_FUNC viRead (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viReadAsync (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPJobId jobId);
+ViStatus _VI_FUNC viReadToFile (ViSession vi, ViConstString filename, ViUInt32 cnt,
+ ViPUInt32 retCnt);
+ViStatus _VI_FUNC viWrite (ViSession vi, ViBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viWriteAsync (ViSession vi, ViBuf buf, ViUInt32 cnt, ViPJobId jobId);
+ViStatus _VI_FUNC viWriteFromFile (ViSession vi, ViConstString filename, ViUInt32 cnt,
+ ViPUInt32 retCnt);
+ViStatus _VI_FUNC viAssertTrigger (ViSession vi, ViUInt16 protocol);
+ViStatus _VI_FUNC viReadSTB (ViSession vi, ViPUInt16 status);
+ViStatus _VI_FUNC viClear (ViSession vi);
+
+/*- Formatted and Buffered I/O Operations -----------------------------------*/
+
+ViStatus _VI_FUNC viSetBuf (ViSession vi, ViUInt16 mask, ViUInt32 size);
+ViStatus _VI_FUNC viFlush (ViSession vi, ViUInt16 mask);
+
+ViStatus _VI_FUNC viBufWrite (ViSession vi, ViBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viBufRead (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+
+ViStatus _VI_FUNCC viPrintf (ViSession vi, ViString writeFmt, ...);
+ViStatus _VI_FUNC viVPrintf (ViSession vi, ViString writeFmt, ViVAList params);
+ViStatus _VI_FUNCC viSPrintf (ViSession vi, ViPBuf buf, ViString writeFmt, ...);
+ViStatus _VI_FUNC viVSPrintf (ViSession vi, ViPBuf buf, ViString writeFmt,
+ ViVAList parms);
+
+ViStatus _VI_FUNCC viScanf (ViSession vi, ViString readFmt, ...);
+ViStatus _VI_FUNC viVScanf (ViSession vi, ViString readFmt, ViVAList params);
+ViStatus _VI_FUNCC viSScanf (ViSession vi, ViBuf buf, ViString readFmt, ...);
+ViStatus _VI_FUNC viVSScanf (ViSession vi, ViBuf buf, ViString readFmt,
+ ViVAList parms);
+
+ViStatus _VI_FUNCC viQueryf (ViSession vi, ViString writeFmt, ViString readFmt, ...);
+ViStatus _VI_FUNC viVQueryf (ViSession vi, ViString writeFmt, ViString readFmt,
+ ViVAList params);
+
+/*- Memory I/O Operations ---------------------------------------------------*/
+
+ViStatus _VI_FUNC viIn8 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt8 val8);
+ViStatus _VI_FUNC viOut8 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt8 val8);
+ViStatus _VI_FUNC viIn16 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt16 val16);
+ViStatus _VI_FUNC viOut16 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt16 val16);
+ViStatus _VI_FUNC viIn32 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt32 val32);
+ViStatus _VI_FUNC viOut32 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt32 val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viIn64 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViPUInt64 val64);
+ViStatus _VI_FUNC viOut64 (ViSession vi, ViUInt16 space,
+ ViBusAddress offset, ViUInt64 val64);
+
+ViStatus _VI_FUNC viIn8Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt8 val8);
+ViStatus _VI_FUNC viOut8Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt8 val8);
+ViStatus _VI_FUNC viIn16Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt16 val16);
+ViStatus _VI_FUNC viOut16Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt16 val16);
+ViStatus _VI_FUNC viIn32Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt32 val32);
+ViStatus _VI_FUNC viOut32Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt32 val32);
+ViStatus _VI_FUNC viIn64Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViPUInt64 val64);
+ViStatus _VI_FUNC viOut64Ex (ViSession vi, ViUInt16 space,
+ ViBusAddress64 offset, ViUInt64 val64);
+#endif
+
+ViStatus _VI_FUNC viMoveIn8 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveOut8 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveIn16 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveOut16 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveIn32 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC viMoveOut32 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt32 buf32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMoveIn64 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC viMoveOut64 (ViSession vi, ViUInt16 space, ViBusAddress offset,
+ ViBusSize length, ViAUInt64 buf64);
+
+ViStatus _VI_FUNC viMoveIn8Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveOut8Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt8 buf8);
+ViStatus _VI_FUNC viMoveIn16Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveOut16Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC viMoveIn32Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC viMoveOut32Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC viMoveIn64Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC viMoveOut64Ex (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+ ViBusSize length, ViAUInt64 buf64);
+#endif
+
+ViStatus _VI_FUNC viMove (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength);
+ViStatus _VI_FUNC viMoveAsync (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength, ViPJobId jobId);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMoveEx (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress64 destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength);
+ViStatus _VI_FUNC viMoveAsyncEx (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+ ViUInt16 srcWidth, ViUInt16 destSpace,
+ ViBusAddress64 destOffset, ViUInt16 destWidth,
+ ViBusSize srcLength, ViPJobId jobId);
+#endif
+
+ViStatus _VI_FUNC viMapAddress (ViSession vi, ViUInt16 mapSpace, ViBusAddress mapOffset,
+ ViBusSize mapSize, ViBoolean access,
+ ViAddr suggested, ViPAddr address);
+ViStatus _VI_FUNC viUnmapAddress (ViSession vi);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMapAddressEx (ViSession vi, ViUInt16 mapSpace, ViBusAddress64 mapOffset,
+ ViBusSize mapSize, ViBoolean access,
+ ViAddr suggested, ViPAddr address);
+#endif
+
+void _VI_FUNC viPeek8 (ViSession vi, ViAddr address, ViPUInt8 val8);
+void _VI_FUNC viPoke8 (ViSession vi, ViAddr address, ViUInt8 val8);
+void _VI_FUNC viPeek16 (ViSession vi, ViAddr address, ViPUInt16 val16);
+void _VI_FUNC viPoke16 (ViSession vi, ViAddr address, ViUInt16 val16);
+void _VI_FUNC viPeek32 (ViSession vi, ViAddr address, ViPUInt32 val32);
+void _VI_FUNC viPoke32 (ViSession vi, ViAddr address, ViUInt32 val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+void _VI_FUNC viPeek64 (ViSession vi, ViAddr address, ViPUInt64 val64);
+void _VI_FUNC viPoke64 (ViSession vi, ViAddr address, ViUInt64 val64);
+#endif
+
+/*- Shared Memory Operations ------------------------------------------------*/
+
+ViStatus _VI_FUNC viMemAlloc (ViSession vi, ViBusSize size, ViPBusAddress offset);
+ViStatus _VI_FUNC viMemFree (ViSession vi, ViBusAddress offset);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC viMemAllocEx (ViSession vi, ViBusSize size, ViPBusAddress64 offset);
+ViStatus _VI_FUNC viMemFreeEx (ViSession vi, ViBusAddress64 offset);
+#endif
+
+/*- Interface Specific Operations -------------------------------------------*/
+
+ViStatus _VI_FUNC viGpibControlREN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC viGpibControlATN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC viGpibSendIFC (ViSession vi);
+ViStatus _VI_FUNC viGpibCommand (ViSession vi, ViBuf cmd, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC viGpibPassControl(ViSession vi, ViUInt16 primAddr, ViUInt16 secAddr);
+
+ViStatus _VI_FUNC viVxiCommandQuery(ViSession vi, ViUInt16 mode, ViUInt32 cmd,
+ ViPUInt32 response);
+ViStatus _VI_FUNC viAssertUtilSignal(ViSession vi, ViUInt16 line);
+ViStatus _VI_FUNC viAssertIntrSignal(ViSession vi, ViInt16 mode, ViUInt32 statusID);
+ViStatus _VI_FUNC viMapTrigger (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest,
+ ViUInt16 mode);
+ViStatus _VI_FUNC viUnmapTrigger (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest);
+ViStatus _VI_FUNC viUsbControlOut (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+ ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+ ViBuf buf);
+ViStatus _VI_FUNC viUsbControlIn (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+ ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+ ViPBuf buf, ViPUInt16 retCnt);
+
+/*- Attributes (platform independent size) ----------------------------------*/
+
+#define VI_ATTR_RSRC_CLASS (0xBFFF0001UL)
+#define VI_ATTR_RSRC_NAME (0xBFFF0002UL)
+#define VI_ATTR_RSRC_IMPL_VERSION (0x3FFF0003UL)
+#define VI_ATTR_RSRC_LOCK_STATE (0x3FFF0004UL)
+#define VI_ATTR_MAX_QUEUE_LENGTH (0x3FFF0005UL)
+#define VI_ATTR_USER_DATA_32 (0x3FFF0007UL)
+#define VI_ATTR_FDC_CHNL (0x3FFF000DUL)
+#define VI_ATTR_FDC_MODE (0x3FFF000FUL)
+#define VI_ATTR_FDC_GEN_SIGNAL_EN (0x3FFF0011UL)
+#define VI_ATTR_FDC_USE_PAIR (0x3FFF0013UL)
+#define VI_ATTR_SEND_END_EN (0x3FFF0016UL)
+#define VI_ATTR_TERMCHAR (0x3FFF0018UL)
+#define VI_ATTR_TMO_VALUE (0x3FFF001AUL)
+#define VI_ATTR_GPIB_READDR_EN (0x3FFF001BUL)
+#define VI_ATTR_IO_PROT (0x3FFF001CUL)
+#define VI_ATTR_DMA_ALLOW_EN (0x3FFF001EUL)
+#define VI_ATTR_ASRL_BAUD (0x3FFF0021UL)
+#define VI_ATTR_ASRL_DATA_BITS (0x3FFF0022UL)
+#define VI_ATTR_ASRL_PARITY (0x3FFF0023UL)
+#define VI_ATTR_ASRL_STOP_BITS (0x3FFF0024UL)
+#define VI_ATTR_ASRL_FLOW_CNTRL (0x3FFF0025UL)
+#define VI_ATTR_RD_BUF_OPER_MODE (0x3FFF002AUL)
+#define VI_ATTR_RD_BUF_SIZE (0x3FFF002BUL)
+#define VI_ATTR_WR_BUF_OPER_MODE (0x3FFF002DUL)
+#define VI_ATTR_WR_BUF_SIZE (0x3FFF002EUL)
+#define VI_ATTR_SUPPRESS_END_EN (0x3FFF0036UL)
+#define VI_ATTR_TERMCHAR_EN (0x3FFF0038UL)
+#define VI_ATTR_DEST_ACCESS_PRIV (0x3FFF0039UL)
+#define VI_ATTR_DEST_BYTE_ORDER (0x3FFF003AUL)
+#define VI_ATTR_SRC_ACCESS_PRIV (0x3FFF003CUL)
+#define VI_ATTR_SRC_BYTE_ORDER (0x3FFF003DUL)
+#define VI_ATTR_SRC_INCREMENT (0x3FFF0040UL)
+#define VI_ATTR_DEST_INCREMENT (0x3FFF0041UL)
+#define VI_ATTR_WIN_ACCESS_PRIV (0x3FFF0045UL)
+#define VI_ATTR_WIN_BYTE_ORDER (0x3FFF0047UL)
+#define VI_ATTR_GPIB_ATN_STATE (0x3FFF0057UL)
+#define VI_ATTR_GPIB_ADDR_STATE (0x3FFF005CUL)
+#define VI_ATTR_GPIB_CIC_STATE (0x3FFF005EUL)
+#define VI_ATTR_GPIB_NDAC_STATE (0x3FFF0062UL)
+#define VI_ATTR_GPIB_SRQ_STATE (0x3FFF0067UL)
+#define VI_ATTR_GPIB_SYS_CNTRL_STATE (0x3FFF0068UL)
+#define VI_ATTR_GPIB_HS488_CBL_LEN (0x3FFF0069UL)
+#define VI_ATTR_CMDR_LA (0x3FFF006BUL)
+#define VI_ATTR_VXI_DEV_CLASS (0x3FFF006CUL)
+#define VI_ATTR_MAINFRAME_LA (0x3FFF0070UL)
+#define VI_ATTR_MANF_NAME (0xBFFF0072UL)
+#define VI_ATTR_MODEL_NAME (0xBFFF0077UL)
+#define VI_ATTR_VXI_VME_INTR_STATUS (0x3FFF008BUL)
+#define VI_ATTR_VXI_TRIG_STATUS (0x3FFF008DUL)
+#define VI_ATTR_VXI_VME_SYSFAIL_STATE (0x3FFF0094UL)
+#define VI_ATTR_WIN_BASE_ADDR_32 (0x3FFF0098UL)
+#define VI_ATTR_WIN_SIZE_32 (0x3FFF009AUL)
+#define VI_ATTR_ASRL_AVAIL_NUM (0x3FFF00ACUL)
+#define VI_ATTR_MEM_BASE_32 (0x3FFF00ADUL)
+#define VI_ATTR_ASRL_CTS_STATE (0x3FFF00AEUL)
+#define VI_ATTR_ASRL_DCD_STATE (0x3FFF00AFUL)
+#define VI_ATTR_ASRL_DSR_STATE (0x3FFF00B1UL)
+#define VI_ATTR_ASRL_DTR_STATE (0x3FFF00B2UL)
+#define VI_ATTR_ASRL_END_IN (0x3FFF00B3UL)
+#define VI_ATTR_ASRL_END_OUT (0x3FFF00B4UL)
+#define VI_ATTR_ASRL_REPLACE_CHAR (0x3FFF00BEUL)
+#define VI_ATTR_ASRL_RI_STATE (0x3FFF00BFUL)
+#define VI_ATTR_ASRL_RTS_STATE (0x3FFF00C0UL)
+#define VI_ATTR_ASRL_XON_CHAR (0x3FFF00C1UL)
+#define VI_ATTR_ASRL_XOFF_CHAR (0x3FFF00C2UL)
+#define VI_ATTR_WIN_ACCESS (0x3FFF00C3UL)
+#define VI_ATTR_RM_SESSION (0x3FFF00C4UL)
+#define VI_ATTR_VXI_LA (0x3FFF00D5UL)
+#define VI_ATTR_MANF_ID (0x3FFF00D9UL)
+#define VI_ATTR_MEM_SIZE_32 (0x3FFF00DDUL)
+#define VI_ATTR_MEM_SPACE (0x3FFF00DEUL)
+#define VI_ATTR_MODEL_CODE (0x3FFF00DFUL)
+#define VI_ATTR_SLOT (0x3FFF00E8UL)
+#define VI_ATTR_INTF_INST_NAME (0xBFFF00E9UL)
+#define VI_ATTR_IMMEDIATE_SERV (0x3FFF0100UL)
+#define VI_ATTR_INTF_PARENT_NUM (0x3FFF0101UL)
+#define VI_ATTR_RSRC_SPEC_VERSION (0x3FFF0170UL)
+#define VI_ATTR_INTF_TYPE (0x3FFF0171UL)
+#define VI_ATTR_GPIB_PRIMARY_ADDR (0x3FFF0172UL)
+#define VI_ATTR_GPIB_SECONDARY_ADDR (0x3FFF0173UL)
+#define VI_ATTR_RSRC_MANF_NAME (0xBFFF0174UL)
+#define VI_ATTR_RSRC_MANF_ID (0x3FFF0175UL)
+#define VI_ATTR_INTF_NUM (0x3FFF0176UL)
+#define VI_ATTR_TRIG_ID (0x3FFF0177UL)
+#define VI_ATTR_GPIB_REN_STATE (0x3FFF0181UL)
+#define VI_ATTR_GPIB_UNADDR_EN (0x3FFF0184UL)
+#define VI_ATTR_DEV_STATUS_BYTE (0x3FFF0189UL)
+#define VI_ATTR_FILE_APPEND_EN (0x3FFF0192UL)
+#define VI_ATTR_VXI_TRIG_SUPPORT (0x3FFF0194UL)
+#define VI_ATTR_TCPIP_ADDR (0xBFFF0195UL)
+#define VI_ATTR_TCPIP_HOSTNAME (0xBFFF0196UL)
+#define VI_ATTR_TCPIP_PORT (0x3FFF0197UL)
+#define VI_ATTR_TCPIP_DEVICE_NAME (0xBFFF0199UL)
+#define VI_ATTR_TCPIP_NODELAY (0x3FFF019AUL)
+#define VI_ATTR_TCPIP_KEEPALIVE (0x3FFF019BUL)
+#define VI_ATTR_4882_COMPLIANT (0x3FFF019FUL)
+#define VI_ATTR_USB_SERIAL_NUM (0xBFFF01A0UL)
+#define VI_ATTR_USB_INTFC_NUM (0x3FFF01A1UL)
+#define VI_ATTR_USB_PROTOCOL (0x3FFF01A7UL)
+#define VI_ATTR_USB_MAX_INTR_SIZE (0x3FFF01AFUL)
+#define VI_ATTR_PXI_DEV_NUM (0x3FFF0201UL)
+#define VI_ATTR_PXI_FUNC_NUM (0x3FFF0202UL)
+#define VI_ATTR_PXI_BUS_NUM (0x3FFF0205UL)
+#define VI_ATTR_PXI_CHASSIS (0x3FFF0206UL)
+#define VI_ATTR_PXI_SLOTPATH (0xBFFF0207UL)
+#define VI_ATTR_PXI_SLOT_LBUS_LEFT (0x3FFF0208UL)
+#define VI_ATTR_PXI_SLOT_LBUS_RIGHT (0x3FFF0209UL)
+#define VI_ATTR_PXI_TRIG_BUS (0x3FFF020AUL)
+#define VI_ATTR_PXI_STAR_TRIG_BUS (0x3FFF020BUL)
+#define VI_ATTR_PXI_STAR_TRIG_LINE (0x3FFF020CUL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR0 (0x3FFF0211UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR1 (0x3FFF0212UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR2 (0x3FFF0213UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR3 (0x3FFF0214UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR4 (0x3FFF0215UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR5 (0x3FFF0216UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR0 (0x3FFF0221UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR1 (0x3FFF0222UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR2 (0x3FFF0223UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR3 (0x3FFF0224UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR4 (0x3FFF0225UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR5 (0x3FFF0226UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR0 (0x3FFF0231UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR1 (0x3FFF0232UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR2 (0x3FFF0233UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR3 (0x3FFF0234UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR4 (0x3FFF0235UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR5 (0x3FFF0236UL)
+#define VI_ATTR_PXI_IS_EXPRESS (0x3FFF0240UL)
+#define VI_ATTR_PXI_SLOT_LWIDTH (0x3FFF0241UL)
+#define VI_ATTR_PXI_MAX_LWIDTH (0x3FFF0242UL)
+#define VI_ATTR_PXI_ACTUAL_LWIDTH (0x3FFF0243UL)
+#define VI_ATTR_PXI_DSTAR_BUS (0x3FFF0244UL)
+#define VI_ATTR_PXI_DSTAR_SET (0x3FFF0245UL)
+
+#define VI_ATTR_JOB_ID (0x3FFF4006UL)
+#define VI_ATTR_EVENT_TYPE (0x3FFF4010UL)
+#define VI_ATTR_SIGP_STATUS_ID (0x3FFF4011UL)
+#define VI_ATTR_RECV_TRIG_ID (0x3FFF4012UL)
+#define VI_ATTR_INTR_STATUS_ID (0x3FFF4023UL)
+#define VI_ATTR_STATUS (0x3FFF4025UL)
+#define VI_ATTR_RET_COUNT_32 (0x3FFF4026UL)
+#define VI_ATTR_BUFFER (0x3FFF4027UL)
+#define VI_ATTR_RECV_INTR_LEVEL (0x3FFF4041UL)
+#define VI_ATTR_OPER_NAME (0xBFFF4042UL)
+#define VI_ATTR_GPIB_RECV_CIC_STATE (0x3FFF4193UL)
+#define VI_ATTR_RECV_TCPIP_ADDR (0xBFFF4198UL)
+#define VI_ATTR_USB_RECV_INTR_SIZE (0x3FFF41B0UL)
+#define VI_ATTR_USB_RECV_INTR_DATA (0xBFFF41B1UL)
+
+/*- Attributes (platform dependent size) ------------------------------------*/
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_USER_DATA_64 (0x3FFF000AUL)
+#define VI_ATTR_RET_COUNT_64 (0x3FFF4028UL)
+#define VI_ATTR_USER_DATA (VI_ATTR_USER_DATA_64)
+#define VI_ATTR_RET_COUNT (VI_ATTR_RET_COUNT_64)
+#else
+#define VI_ATTR_USER_DATA (VI_ATTR_USER_DATA_32)
+#define VI_ATTR_RET_COUNT (VI_ATTR_RET_COUNT_32)
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+#define VI_ATTR_WIN_BASE_ADDR_64 (0x3FFF009BUL)
+#define VI_ATTR_WIN_SIZE_64 (0x3FFF009CUL)
+#define VI_ATTR_MEM_BASE_64 (0x3FFF00D0UL)
+#define VI_ATTR_MEM_SIZE_64 (0x3FFF00D1UL)
+#endif
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_WIN_BASE_ADDR (VI_ATTR_WIN_BASE_ADDR_64)
+#define VI_ATTR_WIN_SIZE (VI_ATTR_WIN_SIZE_64)
+#define VI_ATTR_MEM_BASE (VI_ATTR_MEM_BASE_64)
+#define VI_ATTR_MEM_SIZE (VI_ATTR_MEM_SIZE_64)
+#else
+#define VI_ATTR_WIN_BASE_ADDR (VI_ATTR_WIN_BASE_ADDR_32)
+#define VI_ATTR_WIN_SIZE (VI_ATTR_WIN_SIZE_32)
+#define VI_ATTR_MEM_BASE (VI_ATTR_MEM_BASE_32)
+#define VI_ATTR_MEM_SIZE (VI_ATTR_MEM_SIZE_32)
+#endif
+
+/*- Event Types -------------------------------------------------------------*/
+
+#define VI_EVENT_IO_COMPLETION (0x3FFF2009UL)
+#define VI_EVENT_TRIG (0xBFFF200AUL)
+#define VI_EVENT_SERVICE_REQ (0x3FFF200BUL)
+#define VI_EVENT_CLEAR (0x3FFF200DUL)
+#define VI_EVENT_EXCEPTION (0xBFFF200EUL)
+#define VI_EVENT_GPIB_CIC (0x3FFF2012UL)
+#define VI_EVENT_GPIB_TALK (0x3FFF2013UL)
+#define VI_EVENT_GPIB_LISTEN (0x3FFF2014UL)
+#define VI_EVENT_VXI_VME_SYSFAIL (0x3FFF201DUL)
+#define VI_EVENT_VXI_VME_SYSRESET (0x3FFF201EUL)
+#define VI_EVENT_VXI_SIGP (0x3FFF2020UL)
+#define VI_EVENT_VXI_VME_INTR (0xBFFF2021UL)
+#define VI_EVENT_PXI_INTR (0x3FFF2022UL)
+#define VI_EVENT_TCPIP_CONNECT (0x3FFF2036UL)
+#define VI_EVENT_USB_INTR (0x3FFF2037UL)
+
+#define VI_ALL_ENABLED_EVENTS (0x3FFF7FFFUL)
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS_EVENT_EN (0x3FFF0002L) /* 3FFF0002, 1073676290 */
+#define VI_SUCCESS_EVENT_DIS (0x3FFF0003L) /* 3FFF0003, 1073676291 */
+#define VI_SUCCESS_QUEUE_EMPTY (0x3FFF0004L) /* 3FFF0004, 1073676292 */
+#define VI_SUCCESS_TERM_CHAR (0x3FFF0005L) /* 3FFF0005, 1073676293 */
+#define VI_SUCCESS_MAX_CNT (0x3FFF0006L) /* 3FFF0006, 1073676294 */
+#define VI_SUCCESS_DEV_NPRESENT (0x3FFF007DL) /* 3FFF007D, 1073676413 */
+#define VI_SUCCESS_TRIG_MAPPED (0x3FFF007EL) /* 3FFF007E, 1073676414 */
+#define VI_SUCCESS_QUEUE_NEMPTY (0x3FFF0080L) /* 3FFF0080, 1073676416 */
+#define VI_SUCCESS_NCHAIN (0x3FFF0098L) /* 3FFF0098, 1073676440 */
+#define VI_SUCCESS_NESTED_SHARED (0x3FFF0099L) /* 3FFF0099, 1073676441 */
+#define VI_SUCCESS_NESTED_EXCLUSIVE (0x3FFF009AL) /* 3FFF009A, 1073676442 */
+#define VI_SUCCESS_SYNC (0x3FFF009BL) /* 3FFF009B, 1073676443 */
+
+#define VI_WARN_QUEUE_OVERFLOW (0x3FFF000CL) /* 3FFF000C, 1073676300 */
+#define VI_WARN_CONFIG_NLOADED (0x3FFF0077L) /* 3FFF0077, 1073676407 */
+#define VI_WARN_NULL_OBJECT (0x3FFF0082L) /* 3FFF0082, 1073676418 */
+#define VI_WARN_NSUP_ATTR_STATE (0x3FFF0084L) /* 3FFF0084, 1073676420 */
+#define VI_WARN_UNKNOWN_STATUS (0x3FFF0085L) /* 3FFF0085, 1073676421 */
+#define VI_WARN_NSUP_BUF (0x3FFF0088L) /* 3FFF0088, 1073676424 */
+#define VI_WARN_EXT_FUNC_NIMPL (0x3FFF00A9L) /* 3FFF00A9, 1073676457 */
+
+#define VI_ERROR_SYSTEM_ERROR (_VI_ERROR+0x3FFF0000L) /* BFFF0000, -1073807360 */
+#define VI_ERROR_INV_OBJECT (_VI_ERROR+0x3FFF000EL) /* BFFF000E, -1073807346 */
+#define VI_ERROR_RSRC_LOCKED (_VI_ERROR+0x3FFF000FL) /* BFFF000F, -1073807345 */
+#define VI_ERROR_INV_EXPR (_VI_ERROR+0x3FFF0010L) /* BFFF0010, -1073807344 */
+#define VI_ERROR_RSRC_NFOUND (_VI_ERROR+0x3FFF0011L) /* BFFF0011, -1073807343 */
+#define VI_ERROR_INV_RSRC_NAME (_VI_ERROR+0x3FFF0012L) /* BFFF0012, -1073807342 */
+#define VI_ERROR_INV_ACC_MODE (_VI_ERROR+0x3FFF0013L) /* BFFF0013, -1073807341 */
+#define VI_ERROR_TMO (_VI_ERROR+0x3FFF0015L) /* BFFF0015, -1073807339 */
+#define VI_ERROR_CLOSING_FAILED (_VI_ERROR+0x3FFF0016L) /* BFFF0016, -1073807338 */
+#define VI_ERROR_INV_DEGREE (_VI_ERROR+0x3FFF001BL) /* BFFF001B, -1073807333 */
+#define VI_ERROR_INV_JOB_ID (_VI_ERROR+0x3FFF001CL) /* BFFF001C, -1073807332 */
+#define VI_ERROR_NSUP_ATTR (_VI_ERROR+0x3FFF001DL) /* BFFF001D, -1073807331 */
+#define VI_ERROR_NSUP_ATTR_STATE (_VI_ERROR+0x3FFF001EL) /* BFFF001E, -1073807330 */
+#define VI_ERROR_ATTR_READONLY (_VI_ERROR+0x3FFF001FL) /* BFFF001F, -1073807329 */
+#define VI_ERROR_INV_LOCK_TYPE (_VI_ERROR+0x3FFF0020L) /* BFFF0020, -1073807328 */
+#define VI_ERROR_INV_ACCESS_KEY (_VI_ERROR+0x3FFF0021L) /* BFFF0021, -1073807327 */
+#define VI_ERROR_INV_EVENT (_VI_ERROR+0x3FFF0026L) /* BFFF0026, -1073807322 */
+#define VI_ERROR_INV_MECH (_VI_ERROR+0x3FFF0027L) /* BFFF0027, -1073807321 */
+#define VI_ERROR_HNDLR_NINSTALLED (_VI_ERROR+0x3FFF0028L) /* BFFF0028, -1073807320 */
+#define VI_ERROR_INV_HNDLR_REF (_VI_ERROR+0x3FFF0029L) /* BFFF0029, -1073807319 */
+#define VI_ERROR_INV_CONTEXT (_VI_ERROR+0x3FFF002AL) /* BFFF002A, -1073807318 */
+#define VI_ERROR_QUEUE_OVERFLOW (_VI_ERROR+0x3FFF002DL) /* BFFF002D, -1073807315 */
+#define VI_ERROR_NENABLED (_VI_ERROR+0x3FFF002FL) /* BFFF002F, -1073807313 */
+#define VI_ERROR_ABORT (_VI_ERROR+0x3FFF0030L) /* BFFF0030, -1073807312 */
+#define VI_ERROR_RAW_WR_PROT_VIOL (_VI_ERROR+0x3FFF0034L) /* BFFF0034, -1073807308 */
+#define VI_ERROR_RAW_RD_PROT_VIOL (_VI_ERROR+0x3FFF0035L) /* BFFF0035, -1073807307 */
+#define VI_ERROR_OUTP_PROT_VIOL (_VI_ERROR+0x3FFF0036L) /* BFFF0036, -1073807306 */
+#define VI_ERROR_INP_PROT_VIOL (_VI_ERROR+0x3FFF0037L) /* BFFF0037, -1073807305 */
+#define VI_ERROR_BERR (_VI_ERROR+0x3FFF0038L) /* BFFF0038, -1073807304 */
+#define VI_ERROR_IN_PROGRESS (_VI_ERROR+0x3FFF0039L) /* BFFF0039, -1073807303 */
+#define VI_ERROR_INV_SETUP (_VI_ERROR+0x3FFF003AL) /* BFFF003A, -1073807302 */
+#define VI_ERROR_QUEUE_ERROR (_VI_ERROR+0x3FFF003BL) /* BFFF003B, -1073807301 */
+#define VI_ERROR_ALLOC (_VI_ERROR+0x3FFF003CL) /* BFFF003C, -1073807300 */
+#define VI_ERROR_INV_MASK (_VI_ERROR+0x3FFF003DL) /* BFFF003D, -1073807299 */
+#define VI_ERROR_IO (_VI_ERROR+0x3FFF003EL) /* BFFF003E, -1073807298 */
+#define VI_ERROR_INV_FMT (_VI_ERROR+0x3FFF003FL) /* BFFF003F, -1073807297 */
+#define VI_ERROR_NSUP_FMT (_VI_ERROR+0x3FFF0041L) /* BFFF0041, -1073807295 */
+#define VI_ERROR_LINE_IN_USE (_VI_ERROR+0x3FFF0042L) /* BFFF0042, -1073807294 */
+#define VI_ERROR_NSUP_MODE (_VI_ERROR+0x3FFF0046L) /* BFFF0046, -1073807290 */
+#define VI_ERROR_SRQ_NOCCURRED (_VI_ERROR+0x3FFF004AL) /* BFFF004A, -1073807286 */
+#define VI_ERROR_INV_SPACE (_VI_ERROR+0x3FFF004EL) /* BFFF004E, -1073807282 */
+#define VI_ERROR_INV_OFFSET (_VI_ERROR+0x3FFF0051L) /* BFFF0051, -1073807279 */
+#define VI_ERROR_INV_WIDTH (_VI_ERROR+0x3FFF0052L) /* BFFF0052, -1073807278 */
+#define VI_ERROR_NSUP_OFFSET (_VI_ERROR+0x3FFF0054L) /* BFFF0054, -1073807276 */
+#define VI_ERROR_NSUP_VAR_WIDTH (_VI_ERROR+0x3FFF0055L) /* BFFF0055, -1073807275 */
+#define VI_ERROR_WINDOW_NMAPPED (_VI_ERROR+0x3FFF0057L) /* BFFF0057, -1073807273 */
+#define VI_ERROR_RESP_PENDING (_VI_ERROR+0x3FFF0059L) /* BFFF0059, -1073807271 */
+#define VI_ERROR_NLISTENERS (_VI_ERROR+0x3FFF005FL) /* BFFF005F, -1073807265 */
+#define VI_ERROR_NCIC (_VI_ERROR+0x3FFF0060L) /* BFFF0060, -1073807264 */
+#define VI_ERROR_NSYS_CNTLR (_VI_ERROR+0x3FFF0061L) /* BFFF0061, -1073807263 */
+#define VI_ERROR_NSUP_OPER (_VI_ERROR+0x3FFF0067L) /* BFFF0067, -1073807257 */
+#define VI_ERROR_INTR_PENDING (_VI_ERROR+0x3FFF0068L) /* BFFF0068, -1073807256 */
+#define VI_ERROR_ASRL_PARITY (_VI_ERROR+0x3FFF006AL) /* BFFF006A, -1073807254 */
+#define VI_ERROR_ASRL_FRAMING (_VI_ERROR+0x3FFF006BL) /* BFFF006B, -1073807253 */
+#define VI_ERROR_ASRL_OVERRUN (_VI_ERROR+0x3FFF006CL) /* BFFF006C, -1073807252 */
+#define VI_ERROR_TRIG_NMAPPED (_VI_ERROR+0x3FFF006EL) /* BFFF006E, -1073807250 */
+#define VI_ERROR_NSUP_ALIGN_OFFSET (_VI_ERROR+0x3FFF0070L) /* BFFF0070, -1073807248 */
+#define VI_ERROR_USER_BUF (_VI_ERROR+0x3FFF0071L) /* BFFF0071, -1073807247 */
+#define VI_ERROR_RSRC_BUSY (_VI_ERROR+0x3FFF0072L) /* BFFF0072, -1073807246 */
+#define VI_ERROR_NSUP_WIDTH (_VI_ERROR+0x3FFF0076L) /* BFFF0076, -1073807242 */
+#define VI_ERROR_INV_PARAMETER (_VI_ERROR+0x3FFF0078L) /* BFFF0078, -1073807240 */
+#define VI_ERROR_INV_PROT (_VI_ERROR+0x3FFF0079L) /* BFFF0079, -1073807239 */
+#define VI_ERROR_INV_SIZE (_VI_ERROR+0x3FFF007BL) /* BFFF007B, -1073807237 */
+#define VI_ERROR_WINDOW_MAPPED (_VI_ERROR+0x3FFF0080L) /* BFFF0080, -1073807232 */
+#define VI_ERROR_NIMPL_OPER (_VI_ERROR+0x3FFF0081L) /* BFFF0081, -1073807231 */
+#define VI_ERROR_INV_LENGTH (_VI_ERROR+0x3FFF0083L) /* BFFF0083, -1073807229 */
+#define VI_ERROR_INV_MODE (_VI_ERROR+0x3FFF0091L) /* BFFF0091, -1073807215 */
+#define VI_ERROR_SESN_NLOCKED (_VI_ERROR+0x3FFF009CL) /* BFFF009C, -1073807204 */
+#define VI_ERROR_MEM_NSHARED (_VI_ERROR+0x3FFF009DL) /* BFFF009D, -1073807203 */
+#define VI_ERROR_LIBRARY_NFOUND (_VI_ERROR+0x3FFF009EL) /* BFFF009E, -1073807202 */
+#define VI_ERROR_NSUP_INTR (_VI_ERROR+0x3FFF009FL) /* BFFF009F, -1073807201 */
+#define VI_ERROR_INV_LINE (_VI_ERROR+0x3FFF00A0L) /* BFFF00A0, -1073807200 */
+#define VI_ERROR_FILE_ACCESS (_VI_ERROR+0x3FFF00A1L) /* BFFF00A1, -1073807199 */
+#define VI_ERROR_FILE_IO (_VI_ERROR+0x3FFF00A2L) /* BFFF00A2, -1073807198 */
+#define VI_ERROR_NSUP_LINE (_VI_ERROR+0x3FFF00A3L) /* BFFF00A3, -1073807197 */
+#define VI_ERROR_NSUP_MECH (_VI_ERROR+0x3FFF00A4L) /* BFFF00A4, -1073807196 */
+#define VI_ERROR_INTF_NUM_NCONFIG (_VI_ERROR+0x3FFF00A5L) /* BFFF00A5, -1073807195 */
+#define VI_ERROR_CONN_LOST (_VI_ERROR+0x3FFF00A6L) /* BFFF00A6, -1073807194 */
+#define VI_ERROR_MACHINE_NAVAIL (_VI_ERROR+0x3FFF00A7L) /* BFFF00A7, -1073807193 */
+#define VI_ERROR_NPERMISSION (_VI_ERROR+0x3FFF00A8L) /* BFFF00A8, -1073807192 */
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_VERSION_MAJOR(ver) ((((ViVersion)ver) & 0xFFF00000UL) >> 20)
+#define VI_VERSION_MINOR(ver) ((((ViVersion)ver) & 0x000FFF00UL) >> 8)
+#define VI_VERSION_SUBMINOR(ver) ((((ViVersion)ver) & 0x000000FFUL) )
+
+#define VI_FIND_BUFLEN (256)
+
+#define VI_INTF_GPIB (1)
+#define VI_INTF_VXI (2)
+#define VI_INTF_GPIB_VXI (3)
+#define VI_INTF_ASRL (4)
+#define VI_INTF_PXI (5)
+#define VI_INTF_TCPIP (6)
+#define VI_INTF_USB (7)
+
+#define VI_PROT_NORMAL (1)
+#define VI_PROT_FDC (2)
+#define VI_PROT_HS488 (3)
+#define VI_PROT_4882_STRS (4)
+#define VI_PROT_USBTMC_VENDOR (5)
+
+#define VI_FDC_NORMAL (1)
+#define VI_FDC_STREAM (2)
+
+#define VI_LOCAL_SPACE (0)
+#define VI_A16_SPACE (1)
+#define VI_A24_SPACE (2)
+#define VI_A32_SPACE (3)
+#define VI_A64_SPACE (4)
+#define VI_PXI_ALLOC_SPACE (9)
+#define VI_PXI_CFG_SPACE (10)
+#define VI_PXI_BAR0_SPACE (11)
+#define VI_PXI_BAR1_SPACE (12)
+#define VI_PXI_BAR2_SPACE (13)
+#define VI_PXI_BAR3_SPACE (14)
+#define VI_PXI_BAR4_SPACE (15)
+#define VI_PXI_BAR5_SPACE (16)
+#define VI_OPAQUE_SPACE (0xFFFF)
+
+#define VI_UNKNOWN_LA (-1)
+#define VI_UNKNOWN_SLOT (-1)
+#define VI_UNKNOWN_LEVEL (-1)
+#define VI_UNKNOWN_CHASSIS (-1)
+
+#define VI_QUEUE (1)
+#define VI_HNDLR (2)
+#define VI_SUSPEND_HNDLR (4)
+#define VI_ALL_MECH (0xFFFF)
+
+#define VI_ANY_HNDLR (0)
+
+#define VI_TRIG_ALL (-2)
+#define VI_TRIG_SW (-1)
+#define VI_TRIG_TTL0 (0)
+#define VI_TRIG_TTL1 (1)
+#define VI_TRIG_TTL2 (2)
+#define VI_TRIG_TTL3 (3)
+#define VI_TRIG_TTL4 (4)
+#define VI_TRIG_TTL5 (5)
+#define VI_TRIG_TTL6 (6)
+#define VI_TRIG_TTL7 (7)
+#define VI_TRIG_ECL0 (8)
+#define VI_TRIG_ECL1 (9)
+#define VI_TRIG_PANEL_IN (27)
+#define VI_TRIG_PANEL_OUT (28)
+
+#define VI_TRIG_PROT_DEFAULT (0)
+#define VI_TRIG_PROT_ON (1)
+#define VI_TRIG_PROT_OFF (2)
+#define VI_TRIG_PROT_SYNC (5)
+#define VI_TRIG_PROT_RESERVE (6)
+#define VI_TRIG_PROT_UNRESERVE (7)
+
+#define VI_READ_BUF (1)
+#define VI_WRITE_BUF (2)
+#define VI_READ_BUF_DISCARD (4)
+#define VI_WRITE_BUF_DISCARD (8)
+#define VI_IO_IN_BUF (16)
+#define VI_IO_OUT_BUF (32)
+#define VI_IO_IN_BUF_DISCARD (64)
+#define VI_IO_OUT_BUF_DISCARD (128)
+
+#define VI_FLUSH_ON_ACCESS (1)
+#define VI_FLUSH_WHEN_FULL (2)
+#define VI_FLUSH_DISABLE (3)
+
+#define VI_NMAPPED (1)
+#define VI_USE_OPERS (2)
+#define VI_DEREF_ADDR (3)
+#define VI_DEREF_ADDR_BYTE_SWAP (4)
+
+#define VI_TMO_IMMEDIATE (0L)
+#define VI_TMO_INFINITE (0xFFFFFFFFUL)
+
+#define VI_NO_LOCK (0)
+#define VI_EXCLUSIVE_LOCK (1)
+#define VI_SHARED_LOCK (2)
+#define VI_LOAD_CONFIG (4)
+
+#define VI_NO_SEC_ADDR (0xFFFF)
+
+#define VI_ASRL_PAR_NONE (0)
+#define VI_ASRL_PAR_ODD (1)
+#define VI_ASRL_PAR_EVEN (2)
+#define VI_ASRL_PAR_MARK (3)
+#define VI_ASRL_PAR_SPACE (4)
+
+#define VI_ASRL_STOP_ONE (10)
+#define VI_ASRL_STOP_ONE5 (15)
+#define VI_ASRL_STOP_TWO (20)
+
+#define VI_ASRL_FLOW_NONE (0)
+#define VI_ASRL_FLOW_XON_XOFF (1)
+#define VI_ASRL_FLOW_RTS_CTS (2)
+#define VI_ASRL_FLOW_DTR_DSR (4)
+
+#define VI_ASRL_END_NONE (0)
+#define VI_ASRL_END_LAST_BIT (1)
+#define VI_ASRL_END_TERMCHAR (2)
+#define VI_ASRL_END_BREAK (3)
+
+#define VI_STATE_ASSERTED (1)
+#define VI_STATE_UNASSERTED (0)
+#define VI_STATE_UNKNOWN (-1)
+
+#define VI_BIG_ENDIAN (0)
+#define VI_LITTLE_ENDIAN (1)
+
+#define VI_DATA_PRIV (0)
+#define VI_DATA_NPRIV (1)
+#define VI_PROG_PRIV (2)
+#define VI_PROG_NPRIV (3)
+#define VI_BLCK_PRIV (4)
+#define VI_BLCK_NPRIV (5)
+#define VI_D64_PRIV (6)
+#define VI_D64_NPRIV (7)
+
+#define VI_WIDTH_8 (1)
+#define VI_WIDTH_16 (2)
+#define VI_WIDTH_32 (4)
+#define VI_WIDTH_64 (8)
+
+#define VI_GPIB_REN_DEASSERT (0)
+#define VI_GPIB_REN_ASSERT (1)
+#define VI_GPIB_REN_DEASSERT_GTL (2)
+#define VI_GPIB_REN_ASSERT_ADDRESS (3)
+#define VI_GPIB_REN_ASSERT_LLO (4)
+#define VI_GPIB_REN_ASSERT_ADDRESS_LLO (5)
+#define VI_GPIB_REN_ADDRESS_GTL (6)
+
+#define VI_GPIB_ATN_DEASSERT (0)
+#define VI_GPIB_ATN_ASSERT (1)
+#define VI_GPIB_ATN_DEASSERT_HANDSHAKE (2)
+#define VI_GPIB_ATN_ASSERT_IMMEDIATE (3)
+
+#define VI_GPIB_HS488_DISABLED (0)
+#define VI_GPIB_HS488_NIMPL (-1)
+
+#define VI_GPIB_UNADDRESSED (0)
+#define VI_GPIB_TALKER (1)
+#define VI_GPIB_LISTENER (2)
+
+#define VI_VXI_CMD16 (0x0200)
+#define VI_VXI_CMD16_RESP16 (0x0202)
+#define VI_VXI_RESP16 (0x0002)
+#define VI_VXI_CMD32 (0x0400)
+#define VI_VXI_CMD32_RESP16 (0x0402)
+#define VI_VXI_CMD32_RESP32 (0x0404)
+#define VI_VXI_RESP32 (0x0004)
+
+#define VI_ASSERT_SIGNAL (-1)
+#define VI_ASSERT_USE_ASSIGNED (0)
+#define VI_ASSERT_IRQ1 (1)
+#define VI_ASSERT_IRQ2 (2)
+#define VI_ASSERT_IRQ3 (3)
+#define VI_ASSERT_IRQ4 (4)
+#define VI_ASSERT_IRQ5 (5)
+#define VI_ASSERT_IRQ6 (6)
+#define VI_ASSERT_IRQ7 (7)
+
+#define VI_UTIL_ASSERT_SYSRESET (1)
+#define VI_UTIL_ASSERT_SYSFAIL (2)
+#define VI_UTIL_DEASSERT_SYSFAIL (3)
+
+#define VI_VXI_CLASS_MEMORY (0)
+#define VI_VXI_CLASS_EXTENDED (1)
+#define VI_VXI_CLASS_MESSAGE (2)
+#define VI_VXI_CLASS_REGISTER (3)
+#define VI_VXI_CLASS_OTHER (4)
+
+#define VI_PXI_ADDR_NONE (0)
+#define VI_PXI_ADDR_MEM (1)
+#define VI_PXI_ADDR_IO (2)
+#define VI_PXI_ADDR_CFG (3)
+
+#define VI_TRIG_UNKNOWN (-1)
+
+#define VI_PXI_LBUS_UNKNOWN (-1)
+#define VI_PXI_LBUS_NONE (0)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_0 (1000)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_1 (1001)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_2 (1002)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_3 (1003)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_4 (1004)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_5 (1005)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_6 (1006)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_7 (1007)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_8 (1008)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_9 (1009)
+#define VI_PXI_STAR_TRIG_CONTROLLER (1413)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define viGetDefaultRM(vi) viOpenDefaultRM(vi)
+#define VI_ERROR_INV_SESSION (VI_ERROR_INV_OBJECT)
+#define VI_INFINITE (VI_TMO_INFINITE)
+#define VI_NORMAL (VI_PROT_NORMAL)
+#define VI_FDC (VI_PROT_FDC)
+#define VI_HS488 (VI_PROT_HS488)
+#define VI_ASRL488 (VI_PROT_4882_STRS)
+#define VI_ASRL_IN_BUF (VI_IO_IN_BUF)
+#define VI_ASRL_OUT_BUF (VI_IO_OUT_BUF)
+#define VI_ASRL_IN_BUF_DISCARD (VI_IO_IN_BUF_DISCARD)
+#define VI_ASRL_OUT_BUF_DISCARD (VI_IO_OUT_BUF_DISCARD)
+
+/*- National Instruments ----------------------------------------------------*/
+
+#define VI_INTF_RIO (8)
+#define VI_INTF_FIREWIRE (9)
+
+#define VI_ATTR_SYNC_MXI_ALLOW_EN (0x3FFF0161UL) /* ViBoolean, read/write */
+
+/* This is for VXI SERVANT resources */
+
+#define VI_EVENT_VXI_DEV_CMD (0xBFFF200FUL)
+#define VI_ATTR_VXI_DEV_CMD_TYPE (0x3FFF4037UL) /* ViInt16, read-only */
+#define VI_ATTR_VXI_DEV_CMD_VALUE (0x3FFF4038UL) /* ViUInt32, read-only */
+
+#define VI_VXI_DEV_CMD_TYPE_16 (16)
+#define VI_VXI_DEV_CMD_TYPE_32 (32)
+
+ViStatus _VI_FUNC viVxiServantResponse(ViSession vi, ViInt16 mode, ViUInt32 resp);
+/* mode values include VI_VXI_RESP16, VI_VXI_RESP32, and the next 2 values */
+#define VI_VXI_RESP_NONE (0)
+#define VI_VXI_RESP_PROT_ERROR (-1)
+
+/* This allows extended Serial support on Win32 and on NI ENET Serial products */
+
+#define VI_ATTR_ASRL_DISCARD_NULL (0x3FFF00B0UL)
+#define VI_ATTR_ASRL_CONNECTED (0x3FFF01BBUL)
+#define VI_ATTR_ASRL_BREAK_STATE (0x3FFF01BCUL)
+#define VI_ATTR_ASRL_BREAK_LEN (0x3FFF01BDUL)
+#define VI_ATTR_ASRL_ALLOW_TRANSMIT (0x3FFF01BEUL)
+#define VI_ATTR_ASRL_WIRE_MODE (0x3FFF01BFUL)
+
+#define VI_ASRL_WIRE_485_4 (0)
+#define VI_ASRL_WIRE_485_2_DTR_ECHO (1)
+#define VI_ASRL_WIRE_485_2_DTR_CTRL (2)
+#define VI_ASRL_WIRE_485_2_AUTO (3)
+#define VI_ASRL_WIRE_232_DTE (128)
+#define VI_ASRL_WIRE_232_DCE (129)
+#define VI_ASRL_WIRE_232_AUTO (130)
+
+#define VI_EVENT_ASRL_BREAK (0x3FFF2023UL)
+#define VI_EVENT_ASRL_CTS (0x3FFF2029UL)
+#define VI_EVENT_ASRL_DSR (0x3FFF202AUL)
+#define VI_EVENT_ASRL_DCD (0x3FFF202CUL)
+#define VI_EVENT_ASRL_RI (0x3FFF202EUL)
+#define VI_EVENT_ASRL_CHAR (0x3FFF2035UL)
+#define VI_EVENT_ASRL_TERMCHAR (0x3FFF2024UL)
+
+/* This is for fast viPeek/viPoke macros */
+
+#if defined(NIVISA_PEEKPOKE)
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+#undef NIVISA_PEEKPOKE_SUPP
+#endif
+
+#if (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+/* This macro is supported for all Win32 compilers, including CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_CVI_) && !defined(_NI_mswin16_)
+/* This macro is supported for Borland and Microsoft compilers on Win16, but not CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif defined(_CVI_) && defined(_NI_sparc_)
+/* This macro is supported for Solaris 1 and 2, from CVI only. */
+#define NIVISA_PEEKPOKE_SUPP
+#else
+/* This macro is not supported on other platforms. */
+#endif
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+
+extern ViBoolean NI_viImplVISA1;
+ViStatus _VI_FUNC NI_viOpenDefaultRM (ViPSession vi);
+#define viOpenDefaultRM(vi) NI_viOpenDefaultRM(vi)
+
+#define viPeek8(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((ViPUInt8)(val)) = *((volatile ViUInt8 _VI_PTR)(addr))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPeek8)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPoke8(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((volatile ViUInt8 _VI_PTR)(addr)) = ((ViUInt8)(val))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPoke8)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPeek16(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((ViPUInt16)(val)) = *((volatile ViUInt16 _VI_PTR)(addr))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPeek16)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPoke16(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((volatile ViUInt16 _VI_PTR)(addr)) = ((ViUInt16)(val))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPoke16)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPeek32(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((ViPUInt32)(val)) = *((volatile ViUInt32 _VI_PTR)(addr))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPeek32)((vi),(addr),(val)); \
+ } \
+ }
+
+#define viPoke32(vi,addr,val) \
+ { \
+ if ((NI_viImplVISA1) && (*((ViPUInt32)(vi)))) \
+ { \
+ do (*((volatile ViUInt32 _VI_PTR)(addr)) = ((ViUInt32)(val))); \
+ while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10); \
+ } \
+ else \
+ { \
+ (viPoke32)((vi),(addr),(val)); \
+ } \
+ }
+
+#endif
+
+#endif
+
+#if defined(NIVISA_PXI) || defined(PXISAVISA_PXI)
+
+#if 0
+/* The following 2 attributes were incorrectly implemented in earlier
+ versions of NI-VISA. You should now query VI_ATTR_MANF_ID or
+ VI_ATTR_MODEL_CODE. Those attributes contain sub-vendor information
+ when it exists. To get both the actual primary and subvendor codes
+ from the device, you should call viIn16 using VI_PXI_CFG_SPACE. */
+#define VI_ATTR_PXI_SUB_MANF_ID (0x3FFF0203UL)
+#define VI_ATTR_PXI_SUB_MODEL_CODE (0x3FFF0204UL)
+#endif
+
+#define VI_ATTR_PXI_SRC_TRIG_BUS (0x3FFF020DUL)
+#define VI_ATTR_PXI_DEST_TRIG_BUS (0x3FFF020EUL)
+
+#define VI_ATTR_PXI_RECV_INTR_SEQ (0x3FFF4240UL)
+#define VI_ATTR_PXI_RECV_INTR_DATA (0x3FFF4241UL)
+
+#endif
+
+#if defined(NIVISA_USB)
+
+#define VI_ATTR_USB_BULK_OUT_PIPE (0x3FFF01A2UL)
+#define VI_ATTR_USB_BULK_IN_PIPE (0x3FFF01A3UL)
+#define VI_ATTR_USB_INTR_IN_PIPE (0x3FFF01A4UL)
+#define VI_ATTR_USB_CLASS (0x3FFF01A5UL)
+#define VI_ATTR_USB_SUBCLASS (0x3FFF01A6UL)
+#define VI_ATTR_USB_ALT_SETTING (0x3FFF01A8UL)
+#define VI_ATTR_USB_END_IN (0x3FFF01A9UL)
+#define VI_ATTR_USB_NUM_INTFCS (0x3FFF01AAUL)
+#define VI_ATTR_USB_NUM_PIPES (0x3FFF01ABUL)
+#define VI_ATTR_USB_BULK_OUT_STATUS (0x3FFF01ACUL)
+#define VI_ATTR_USB_BULK_IN_STATUS (0x3FFF01ADUL)
+#define VI_ATTR_USB_INTR_IN_STATUS (0x3FFF01AEUL)
+#define VI_ATTR_USB_CTRL_PIPE (0x3FFF01B0UL)
+
+#define VI_USB_PIPE_STATE_UNKNOWN (-1)
+#define VI_USB_PIPE_READY (0)
+#define VI_USB_PIPE_STALLED (1)
+
+#define VI_USB_END_NONE (0)
+#define VI_USB_END_SHORT (4)
+#define VI_USB_END_SHORT_OR_COUNT (5)
+
+#endif
+
+#define VI_ATTR_FIREWIRE_DEST_UPPER_OFFSET (0x3FFF01F0UL)
+#define VI_ATTR_FIREWIRE_SRC_UPPER_OFFSET (0x3FFF01F1UL)
+#define VI_ATTR_FIREWIRE_WIN_UPPER_OFFSET (0x3FFF01F2UL)
+#define VI_ATTR_FIREWIRE_VENDOR_ID (0x3FFF01F3UL)
+#define VI_ATTR_FIREWIRE_LOWER_CHIP_ID (0x3FFF01F4UL)
+#define VI_ATTR_FIREWIRE_UPPER_CHIP_ID (0x3FFF01F5UL)
+
+#define VI_FIREWIRE_DFLT_SPACE (5)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+ }
+#endif
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
diff --git a/hal/lib/Athena/visa/visatype.h b/hal/lib/Athena/visa/visatype.h
new file mode 100644
index 0000000..ef089dd
--- /dev/null
+++ b/hal/lib/Athena/visa/visatype.h
@@ -0,0 +1,201 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc. */
+/* */
+/* Do not modify the contents of this file. */
+/*---------------------------------------------------------------------------*/
+/* */
+/* Title : VISATYPE.H */
+/* Date : 04-14-2006 */
+/* Purpose : Fundamental VISA data types and macro definitions */
+/* */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISATYPE_HEADER__
+#define __VISATYPE_HEADER__
+
+#if defined(_WIN64)
+#define _VI_FAR
+#define _VI_FUNC __fastcall
+#define _VI_FUNCC __fastcall
+#define _VI_FUNCH __fastcall
+#define _VI_SIGNED signed
+#elif (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+#define _VI_FAR
+#define _VI_FUNC __stdcall
+#define _VI_FUNCC __cdecl
+#define _VI_FUNCH __stdcall
+#define _VI_SIGNED signed
+#elif defined(_CVI_) && defined(_NI_i386_)
+#define _VI_FAR
+#define _VI_FUNC _pascal
+#define _VI_FUNCC
+#define _VI_FUNCH _pascal
+#define _VI_SIGNED signed
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_NI_mswin16_)
+#define _VI_FAR _far
+#define _VI_FUNC _far _pascal _export
+#define _VI_FUNCC _far _cdecl _export
+#define _VI_FUNCH _far _pascal
+#define _VI_SIGNED signed
+#elif (defined(hpux) || defined(__hpux)) && (defined(__cplusplus) || defined(__cplusplus__))
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED
+#else
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED signed
+#endif
+
+#define _VI_ERROR (-2147483647L-1) /* 0x80000000 */
+#define _VI_PTR _VI_FAR *
+
+/*- VISA Types --------------------------------------------------------------*/
+
+#ifndef _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64) || ((defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_))
+#if (defined(_MSC_VER) && (_MSC_VER >= 1200)) || (defined(_CVI_) && (_CVI_ >= 700)) || (defined(__BORLANDC__) && (__BORLANDC__ >= 0x0520))
+typedef unsigned __int64 ViUInt64;
+typedef _VI_SIGNED __int64 ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#endif
+#elif defined(__GNUC__) && (__GNUC__ >= 3)
+#include <limits.h>
+#include <sys/types.h>
+typedef u_int64_t ViUInt64;
+typedef int64_t ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#else
+/* This platform does not support 64-bit types */
+#endif
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64 _VI_PTR ViPUInt64;
+typedef ViUInt64 _VI_PTR ViAUInt64;
+typedef ViInt64 _VI_PTR ViPInt64;
+typedef ViInt64 _VI_PTR ViAInt64;
+#endif
+
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+typedef unsigned int ViUInt32;
+typedef _VI_SIGNED int ViInt32;
+#else
+typedef unsigned long ViUInt32;
+typedef _VI_SIGNED long ViInt32;
+#endif
+
+typedef ViUInt32 _VI_PTR ViPUInt32;
+typedef ViUInt32 _VI_PTR ViAUInt32;
+typedef ViInt32 _VI_PTR ViPInt32;
+typedef ViInt32 _VI_PTR ViAInt32;
+
+typedef unsigned short ViUInt16;
+typedef ViUInt16 _VI_PTR ViPUInt16;
+typedef ViUInt16 _VI_PTR ViAUInt16;
+
+typedef _VI_SIGNED short ViInt16;
+typedef ViInt16 _VI_PTR ViPInt16;
+typedef ViInt16 _VI_PTR ViAInt16;
+
+typedef unsigned char ViUInt8;
+typedef ViUInt8 _VI_PTR ViPUInt8;
+typedef ViUInt8 _VI_PTR ViAUInt8;
+
+typedef _VI_SIGNED char ViInt8;
+typedef ViInt8 _VI_PTR ViPInt8;
+typedef ViInt8 _VI_PTR ViAInt8;
+
+typedef char ViChar;
+typedef ViChar _VI_PTR ViPChar;
+typedef ViChar _VI_PTR ViAChar;
+
+typedef unsigned char ViByte;
+typedef ViByte _VI_PTR ViPByte;
+typedef ViByte _VI_PTR ViAByte;
+
+typedef void _VI_PTR ViAddr;
+typedef ViAddr _VI_PTR ViPAddr;
+typedef ViAddr _VI_PTR ViAAddr;
+
+typedef float ViReal32;
+typedef ViReal32 _VI_PTR ViPReal32;
+typedef ViReal32 _VI_PTR ViAReal32;
+
+typedef double ViReal64;
+typedef ViReal64 _VI_PTR ViPReal64;
+typedef ViReal64 _VI_PTR ViAReal64;
+
+typedef ViPByte ViBuf;
+typedef ViPByte ViPBuf;
+typedef ViPByte _VI_PTR ViABuf;
+
+typedef ViPChar ViString;
+typedef ViPChar ViPString;
+typedef ViPChar _VI_PTR ViAString;
+
+typedef ViString ViRsrc;
+typedef ViString ViPRsrc;
+typedef ViString _VI_PTR ViARsrc;
+
+typedef ViUInt16 ViBoolean;
+typedef ViBoolean _VI_PTR ViPBoolean;
+typedef ViBoolean _VI_PTR ViABoolean;
+
+typedef ViInt32 ViStatus;
+typedef ViStatus _VI_PTR ViPStatus;
+typedef ViStatus _VI_PTR ViAStatus;
+
+typedef ViUInt32 ViVersion;
+typedef ViVersion _VI_PTR ViPVersion;
+typedef ViVersion _VI_PTR ViAVersion;
+
+typedef ViUInt32 ViObject;
+typedef ViObject _VI_PTR ViPObject;
+typedef ViObject _VI_PTR ViAObject;
+
+typedef ViObject ViSession;
+typedef ViSession _VI_PTR ViPSession;
+typedef ViSession _VI_PTR ViASession;
+
+typedef ViUInt32 ViAttr;
+
+#ifndef _VI_CONST_STRING_DEFINED
+typedef const ViChar * ViConstString;
+#define _VI_CONST_STRING_DEFINED
+#endif
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS (0L)
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_NULL (0)
+
+#define VI_TRUE (1)
+#define VI_FALSE (0)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define VISAFN _VI_FUNC
+#define ViPtr _VI_PTR
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
+
diff --git a/hal/lib/Desktop/HALDesktop.cpp b/hal/lib/Desktop/HALDesktop.cpp
new file mode 100644
index 0000000..7860708
--- /dev/null
+++ b/hal/lib/Desktop/HALDesktop.cpp
@@ -0,0 +1 @@
+//nothing here yet!
\ No newline at end of file
diff --git a/hal/lib/Shared/FRC_NetworkCommunication/FRCComm.h b/hal/lib/Shared/FRC_NetworkCommunication/FRCComm.h
new file mode 100644
index 0000000..54c9463
--- /dev/null
+++ b/hal/lib/Shared/FRC_NetworkCommunication/FRCComm.h
@@ -0,0 +1,111 @@
+/*************************************************************
+ * NOTICE
+ *
+ * These are the only externally exposed functions to the
+ * NetworkCommunication library
+ *
+ * This is an implementation of FRC Spec for Comm Protocol
+ * Revision 4.5, June 30, 2008
+ *
+ * Copyright (c) National Instruments 2008. All Rights Reserved.
+ *
+ *************************************************************/
+
+//This file must compile on ALL PLATFORMS. Be very careful what you put in here.
+
+#ifndef __FRC_COMM_H__
+#define __FRC_COMM_H__
+
+#ifdef _WIN32
+ #ifdef USE_THRIFT
+ #define EXPORT_FUNC
+ #else
+ #define EXPORT_FUNC __declspec(dllexport) __cdecl
+ #endif
+#else
+ #include <stdint.h>
+ #include <pthread.h>
+ #define EXPORT_FUNC
+#endif
+
+#define ERR_FRCSystem_NetCommNotResponding -44049
+#define ERR_FRCSystem_NoDSConnection -44018
+
+enum AllianceStationID_t {
+ kAllianceStationID_red1,
+ kAllianceStationID_red2,
+ kAllianceStationID_red3,
+ kAllianceStationID_blue1,
+ kAllianceStationID_blue2,
+ kAllianceStationID_blue3,
+};
+
+enum MatchType_t {
+ kMatchType_none,
+ kMatchType_practice,
+ kMatchType_qualification,
+ kMatchType_elimination,
+};
+
+struct ControlWord_t {
+ uint32_t enabled : 1;
+ uint32_t autonomous : 1;
+ uint32_t test :1;
+ uint32_t eStop : 1;
+ uint32_t fmsAttached:1;
+ uint32_t dsAttached:1;
+ uint32_t control_reserved : 26;
+};
+
+struct JoystickAxes_t {
+ uint16_t count;
+ int16_t axes[1];
+};
+
+struct JoystickPOV_t {
+ uint16_t count;
+ int16_t povs[1];
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+ int EXPORT_FUNC FRC_NetworkCommunication_Reserve(void *instance);
+#ifndef SIMULATION
+ void EXPORT_FUNC getFPGAHardwareVersion(uint16_t *fpgaVersion, uint32_t *fpgaRevision);
+#endif
+ int EXPORT_FUNC setStatusData(float battery, uint8_t dsDigitalOut, uint8_t updateNumber,
+ const char *userDataHigh, int userDataHighLength,
+ const char *userDataLow, int userDataLowLength, int wait_ms);
+ int EXPORT_FUNC setErrorData(const char *errors, int errorsLength, int wait_ms);
+
+#ifdef SIMULATION
+ void EXPORT_FUNC setNewDataSem(HANDLE);
+#else
+ void EXPORT_FUNC setNewDataSem(pthread_cond_t *);
+#endif
+
+ // this uint32_t is really a LVRefNum
+ int EXPORT_FUNC setNewDataOccurRef(uint32_t refnum);
+
+ int EXPORT_FUNC FRC_NetworkCommunication_getControlWord(struct ControlWord_t *controlWord);
+ int EXPORT_FUNC FRC_NetworkCommunication_getAllianceStation(enum AllianceStationID_t *allianceStation);
+ int EXPORT_FUNC FRC_NetworkCommunication_getMatchTime(float *matchTime);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickAxes(uint8_t joystickNum, struct JoystickAxes_t *axes, uint8_t maxAxes);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickButtons(uint8_t joystickNum, uint32_t *buttons, uint8_t *count);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickPOVs(uint8_t joystickNum, struct JoystickPOV_t *povs, uint8_t maxPOVs);
+ int EXPORT_FUNC FRC_NetworkCommunication_setJoystickOutputs(uint8_t joystickNum, uint32_t hidOutputs, uint16_t leftRumble, uint16_t rightRumble);
+ int EXPORT_FUNC FRC_NetworkCommunication_getJoystickDesc(uint8_t joystickNum, uint8_t *isXBox, uint8_t *type, char *name,
+ uint8_t *axisCount, uint8_t *axisTypes, uint8_t *buttonCount, uint8_t *povCount);
+
+ void EXPORT_FUNC FRC_NetworkCommunication_getVersionString(char *version);
+ int EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramStarting(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramDisabled(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramAutonomous(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramTeleop(void);
+ void EXPORT_FUNC FRC_NetworkCommunication_observeUserProgramTest(void);
+#ifdef __cplusplus
+}
+#endif
+
+#endif
diff --git a/hal/lib/Shared/HAL.cpp b/hal/lib/Shared/HAL.cpp
new file mode 100644
index 0000000..9781278
--- /dev/null
+++ b/hal/lib/Shared/HAL.cpp
@@ -0,0 +1,128 @@
+//This file must compile on ALL PLATFORMS. Be very careful what you put in here.
+#include "HAL/HAL.hpp"
+#include "FRC_NetworkCommunication/FRCComm.h"
+#include <cstring>
+
+int HALGetControlWord(HALControlWord *data)
+{
+ return FRC_NetworkCommunication_getControlWord((ControlWord_t*) data);
+}
+
+void HALSetNewDataSem(MULTIWAIT_ID sem)
+{
+ setNewDataSem(sem->native_handle());
+}
+
+int HALGetAllianceStation(enum HALAllianceStationID *allianceStation)
+{
+ return FRC_NetworkCommunication_getAllianceStation((AllianceStationID_t*) allianceStation);
+}
+
+int HALGetJoystickAxes(uint8_t joystickNum, HALJoystickAxes *axes)
+{
+ return FRC_NetworkCommunication_getJoystickAxes(joystickNum, (JoystickAxes_t*) axes, kMaxJoystickAxes);
+}
+
+int HALGetJoystickPOVs(uint8_t joystickNum, HALJoystickPOVs *povs)
+{
+ return FRC_NetworkCommunication_getJoystickPOVs(joystickNum, (JoystickPOV_t*) povs, kMaxJoystickPOVs);
+}
+
+int HALGetJoystickButtons(uint8_t joystickNum, HALJoystickButtons *buttons)
+{
+ return FRC_NetworkCommunication_getJoystickButtons(joystickNum, &buttons->buttons, &buttons->count);
+}
+
+int HALGetJoystickDescriptor(uint8_t joystickNum, HALJoystickDescriptor *desc)
+{
+ return FRC_NetworkCommunication_getJoystickDesc(joystickNum, &desc->isXbox, &desc->type, (char *)(&desc->name),
+ &desc->axisCount, (uint8_t *)&desc->axisTypes, &desc->buttonCount, &desc->povCount);
+}
+
+int HALGetJoystickIsXbox(uint8_t joystickNum)
+{
+ HALJoystickDescriptor joystickDesc;
+ if(HALGetJoystickDescriptor(joystickNum, &joystickDesc)<0)
+ {
+ return 0;
+ }else
+ {
+ return joystickDesc.isXbox;
+ }
+}
+
+int HALGetJoystickType(uint8_t joystickNum)
+{
+ HALJoystickDescriptor joystickDesc;
+ if(HALGetJoystickDescriptor(joystickNum, &joystickDesc)<0)
+ {
+ return -1;
+ } else
+ {
+ return joystickDesc.type;
+ }
+}
+
+char* HALGetJoystickName(uint8_t joystickNum)
+{
+ HALJoystickDescriptor joystickDesc;
+ if(HALGetJoystickDescriptor(joystickNum, &joystickDesc)<0)
+ {
+ char* name = (char*)std::malloc(1);
+ name[0] = '\0';
+ return name;
+ } else
+ {
+ size_t len = std::strlen(joystickDesc.name);
+ char* name = (char*)std::malloc(len+1);
+ std::strcpy(name, joystickDesc.name);
+ return name;
+ }
+}
+
+int HALGetJoystickAxisType(uint8_t joystickNum, uint8_t axis)
+{
+ HALJoystickDescriptor joystickDesc;
+ if(HALGetJoystickDescriptor(joystickNum, &joystickDesc)<0)
+ {
+ return -1;
+ } else
+ {
+ return joystickDesc.axisTypes[axis];
+ }
+}
+
+int HALSetJoystickOutputs(uint8_t joystickNum, uint32_t outputs, uint16_t leftRumble, uint16_t rightRumble)
+{
+ return FRC_NetworkCommunication_setJoystickOutputs(joystickNum, outputs, leftRumble, rightRumble);
+}
+
+int HALGetMatchTime(float *matchTime)
+{
+ return FRC_NetworkCommunication_getMatchTime(matchTime);
+}
+
+void HALNetworkCommunicationObserveUserProgramStarting(void)
+{
+ FRC_NetworkCommunication_observeUserProgramStarting();
+}
+
+void HALNetworkCommunicationObserveUserProgramDisabled(void)
+{
+ FRC_NetworkCommunication_observeUserProgramDisabled();
+}
+
+void HALNetworkCommunicationObserveUserProgramAutonomous(void)
+{
+ FRC_NetworkCommunication_observeUserProgramAutonomous();
+}
+
+void HALNetworkCommunicationObserveUserProgramTeleop(void)
+{
+ FRC_NetworkCommunication_observeUserProgramTeleop();
+}
+
+void HALNetworkCommunicationObserveUserProgramTest(void)
+{
+ FRC_NetworkCommunication_observeUserProgramTest();
+}