Squashed 'third_party/allwpilib_2017/' content from commit 35ac87d
Change-Id: I7bb6f5556c30d3f5a092e68de0be9c710c60c9f4
git-subtree-dir: third_party/allwpilib_2017
git-subtree-split: 35ac87d6ff8b7f061c4f18c9ea316e5dccd4888a
diff --git a/hal/include/ctre/CtreCanNode.h b/hal/include/ctre/CtreCanNode.h
new file mode 100644
index 0000000..2707598
--- /dev/null
+++ b/hal/include/ctre/CtreCanNode.h
@@ -0,0 +1,131 @@
+#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);
+ /**
+ * Schedule a CAN Frame for periodic transmit. Assume eight byte DLC and zero value for initial transmission.
+ * @param arbId CAN Frame Arbitration ID. Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+ * @param periodMs Period to transmit CAN frame. Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+ */
+ void RegisterTx(uint32_t arbId, uint32_t periodMs);
+ /**
+ * Schedule a CAN Frame for periodic transmit.
+ * @param arbId CAN Frame Arbitration ID. Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+ * @param periodMs Period to transmit CAN frame. Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+ * @param dlc Number of bytes to transmit (0 to 8).
+ * @param initialFrame Ptr to the frame data to schedule for transmitting. Passing null will result
+ * in defaulting to zero data value.
+ */
+ void RegisterTx(uint32_t arbId, uint32_t periodMs, uint32_t dlc, const uint8_t * initialFrame);
+ void UnregisterTx(uint32_t arbId);
+
+ CTR_Code GetRx(uint32_t arbId,uint8_t * dataBytes,uint32_t timeoutMs);
+ void FlushTx(uint32_t arbId);
+ bool ChangeTxPeriod(uint32_t arbId, uint32_t periodMs);
+
+ 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;
+ uint8_t dlc;
+ };
+
+ 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..03d9b2d
--- /dev/null
+++ b/hal/include/ctre/PCM.h
@@ -0,0 +1,226 @@
+#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);
+
+ /* Set all PCM solenoid states
+ *
+ * @Return - CTR_Code - Error code (if any) for setting solenoids
+ * @Param - state Bitfield to set all solenoids to
+ */
+ CTR_Code SetAllSolenoids(UINT8 state);
+
+ /* 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_SetAllSolenoids(void * handle,UINT8 state);
+ 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..a0f99b3
--- /dev/null
+++ b/hal/include/ctre/ctre.h
@@ -0,0 +1,57 @@
+/**
+ * @file ctre.h
+ * Common header for all CTRE HAL modules.
+ */
+#ifndef CTRE_H
+#define CTRE_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_BufferFull, //!< Caller attempted to insert data into a buffer that is full.
+}CTR_Code;
+
+#include "ctre_frames.h"
+
+#endif /* CTRE_H */
diff --git a/hal/include/ctre/ctre_frames.h b/hal/include/ctre/ctre_frames.h
new file mode 100644
index 0000000..f131538
--- /dev/null
+++ b/hal/include/ctre/ctre_frames.h
@@ -0,0 +1,243 @@
+/**
+ * @file ctre_frames.h
+ * CAN Encoder/Decoder Structures for CTRE devices.
+ */
+#ifndef CTRE_FRAMES_H
+#define CTRE_FRAMES_H
+
+/** 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 ;
+
+/* TALON_Control_2_Rates_OneShot_t removed since it has been deprecated */
+
+typedef struct _TALON_Control_3_ClearFlags_OneShot_t {
+ unsigned ZeroFeedbackSensor:1;
+ unsigned ClearStickyFaults:1;
+} TALON_Control_3_ClearFlags_OneShot_t ;
+
+typedef struct _TALON_Control_5_General_10ms_t {
+ unsigned ThrottleBump_h3:3;
+ unsigned ReservedZero:5;
+ unsigned ThrottleBump_l8: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_5_General_10ms_t ;
+
+typedef struct _TALON_Control_6_MotProfAddTrajPoint_t {
+ unsigned huffCode:2; //!< Compression coding
+ unsigned NextPt_VelOnly:1;
+ unsigned NextPt_IsLast:1;
+ unsigned reserved0:2;
+ unsigned NextPt_ZeroPosition:1;
+ unsigned NextPt_ProfileSlotSelect:1;
+ unsigned Idx:4;
+ unsigned reserved1:4;
+ unsigned restOfFrame0:8;
+ unsigned restOfFrame1:8;
+ unsigned restOfFrame2:8;
+ unsigned restOfFrame3:8;
+ unsigned restOfFrame4:8;
+ unsigned restOfFrame5:8;
+} TALON_Control_6_MotProfAddTrajPoint_t;
+
+typedef struct _TALON_Control_6_MotProfAddTrajPoint_huff0_t {
+ unsigned huffCode_expect_0:2; //!< Compression coding
+ unsigned NextPt_VelOnly:1;
+ unsigned NextPt_IsLast:1;
+ unsigned reserved0:2;
+ unsigned NextPt_ZeroPosition:1;
+ unsigned NextPt_ProfileSlotSelect:1;
+ unsigned Idx:4;
+ unsigned reserved1:4;
+ unsigned NextPt_DurationMs:8;
+ unsigned NextPt_VelocityH:8;
+ unsigned NextPt_VelocityL:8;
+ unsigned NextPt_PositionH:8;
+ unsigned NextPt_PositionM:8;
+ unsigned NextPt_PositionL:8;
+} TALON_Control_6_MotProfAddTrajPoint_huff0_t;
+
+typedef struct _TALON_Control_6_MotProfAddTrajPoint_huff1_t {
+ unsigned huffCode_expect_1:2; //!< Compression coding
+ unsigned NextPt_VelOnly:1;
+ unsigned NextPt_IsLast:1;
+ unsigned reserved0:2;
+ unsigned NextPt_ZeroPosition:1;
+ unsigned NextPt_ProfileSlotSelect:1;
+ unsigned Idx:4;
+ unsigned reserved1:4;
+ unsigned NextPt_DurationMs:8;
+ unsigned NextPt_SameVelocityH:8;
+ unsigned NextPt_SameVelocityL:8;
+ unsigned NextPt_DeltaPositionH:8;
+ unsigned NextPt_DeltaPositionL:8;
+ unsigned NextPt_Count:8;
+} TALON_Control_6_MotProfAddTrajPoint_huff1_t;
+
+/** status */
+typedef struct _TALON_Status_1_General_10ms_t {
+ unsigned CloseLoopErrH:8;
+ unsigned CloseLoopErrM:8;
+ unsigned CloseLoopErrL:8;
+ unsigned AppliedThrottle_h3:3;
+ unsigned Fault_RevSoftLim:1;
+ unsigned Fault_ForSoftLim:1;
+ unsigned TokLocked:1;
+ unsigned LimitSwitchClosedRev:1;
+ unsigned LimitSwitchClosedFor:1;
+ unsigned AppliedThrottle_l8:8;
+ unsigned ModeSelect_h1:1;
+ unsigned FeedbackDeviceSelect:4;
+ unsigned LimitSwitchEn:3;
+ unsigned Fault_HardwareFailure:1;
+ unsigned Fault_RevLim:1;
+ unsigned Fault_ForLim:1;
+ unsigned Fault_UnderVoltage:1;
+ unsigned Fault_OverTemp:1;
+ unsigned ModeSelect_b3:3;
+ unsigned TokenSeed:8;
+} TALON_Status_1_General_10ms_t ;
+typedef struct _TALON_Status_2_Feedback_20ms_t {
+ unsigned SensorPositionH:8;
+ unsigned SensorPositionM:8;
+ unsigned SensorPositionL:8;
+ unsigned SensorVelocityH:8;
+ unsigned SensorVelocityL:8;
+ unsigned Current_h8:8;
+ unsigned StckyFault_RevSoftLim:1;
+ unsigned StckyFault_ForSoftLim:1;
+ unsigned StckyFault_RevLim:1;
+ unsigned StckyFault_ForLim:1;
+ unsigned StckyFault_UnderVoltage:1;
+ unsigned StckyFault_OverTemp:1;
+ unsigned Current_l2:2;
+ unsigned reserved:3;
+ unsigned Cmd5Allowed:1;
+ 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_Status_9_MotProfBuffer_100ms_t {
+ unsigned ActTraj_IsValid:1; //!< '1' if other ActTraj_* signals are valid. '0' if there is no active trajectory pt.
+ unsigned ActTraj_ProfileSlotSelect:1;
+ unsigned ActTraj_VelOnly:1;
+ unsigned ActTraj_IsLast:1;
+ unsigned OutputType:2;
+ unsigned HasUnderrun:1;
+ unsigned IsUnderrun:1;
+ unsigned NextID:4;
+ unsigned reserved1:3;
+ unsigned BufferIsFull:1;
+ unsigned Count:8;
+ unsigned ActTraj_VelocityH:8;
+ unsigned ActTraj_VelocityL:8;
+ unsigned ActTraj_PositionH:8;
+ unsigned ActTraj_PositionM:8;
+ unsigned ActTraj_PositionL:8;
+} TALON_Status_9_MotProfBuffer_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 ;
+
+#endif /* CTRE_FRAMES_H */