WPILibC++  unspecified
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Pages
CanTalonSRX.h
1 
107 #ifndef CanTalonSRX_H_
108 #define CanTalonSRX_H_
109 #include "ctre/ctre.h" //BIT Defines + Typedefs, TALON_Control_6_MotProfAddTrajPoint_t
110 #include "ctre/CtreCanNode.h"
111 #include <FRC_NetworkCommunication/CANSessionMux.h> //CAN Comm
112 #include <map>
113 #include <atomic>
114 #include <deque>
115 #include <mutex>
116 class CanTalonSRX : public CtreCanNode {
117  private:
118  // Use this for determining whether the default move constructor has been
119  // called; this prevents us from calling the destructor twice.
120  struct HasBeenMoved {
121  HasBeenMoved(HasBeenMoved &&other) {
122  other.moved = true;
123  moved = false;
124  }
125  HasBeenMoved() = default;
126  std::atomic<bool> moved{false};
127  operator bool() const { return moved; }
128  } m_hasBeenMoved;
129 
130  // Vars for opening a CAN stream if caller needs signals that require
131  // soliciting
132  uint32_t _can_h;
133  int32_t _can_stat;
134  struct tCANStreamMessage _msgBuff[20];
135  static int const kMsgCapacity = 20;
136  typedef std::map<uint32_t, uint32_t> sigs_t;
137  // Catches signal updates that are solicited. Expect this to be very few.
138  sigs_t _sigs;
139  void OpenSessionIfNeedBe();
140  void ProcessStreamMessages();
150  void UpdateControlId();
156  bool IsControl5Supported();
161  void GetControlFrameCopy(uint8_t *toFill);
174  void ReactToMotionProfileCall();
184  void CopyTrajPtIntoControl(
187  //---------------------- General Control framing ---------------------------//
191  int _controlPeriodMs = kDefaultControlPeriodMs;
195  int _control6PeriodMs = kDefaultControl6PeriodMs;
201  int _enablePeriodMs = kDefaultEnablePeriodMs;
205  uint32_t _controlFrameArbId;
211  bool _useControl5ifSupported = true;
212  //--------------------- Buffering Motion Profile ---------------------------//
222  class TrajectoryBuffer {
223  public:
224  void Clear() { _motProfTopBuffer.clear(); }
229  _motProfTopBuffer.push_back(pt);
230  }
237  /* TODO : peek ahead and use compression strategies */
238  _lastFront = _motProfTopBuffer.front();
239  return (TALON_Control_6_MotProfAddTrajPoint_t *)&_lastFront;
240  }
241  void Pop() {
242  /* TODO : pop multiple points if last front'd point was compressed. */
243  _motProfTopBuffer.pop_front();
244  }
245  unsigned int GetNumTrajectories() { return _motProfTopBuffer.size(); }
246  bool IsEmpty() { return _motProfTopBuffer.empty(); }
247 
248  private:
249  std::deque<TALON_Control_6_MotProfAddTrajPoint_huff0_t> _motProfTopBuffer;
251  };
252  TrajectoryBuffer _motProfTopBuffer;
259  static const int kMotionProfileTopBufferCapacity = 2048;
263  int32_t _motProfFlowControl = -1;
268  std::mutex _mutMotProf;
281  CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits);
285  CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t &rawBits);
286 
287  public:
288  // default control update rate is 10ms.
289  static const int kDefaultControlPeriodMs = 10;
290  // default enable update rate is 50ms (when using the new control5 frame).
291  static const int kDefaultEnablePeriodMs = 50;
292  // Default update rate for motion profile control 6. This only takes effect
293  // when calling uses MP functions.
294  static const int kDefaultControl6PeriodMs = 10;
295  explicit CanTalonSRX(int deviceNumber = 0,
296  int controlPeriodMs = kDefaultControlPeriodMs,
297  int enablePeriodMs = kDefaultEnablePeriodMs);
298  ~CanTalonSRX();
299  void Set(double value);
300  /* mode select enumerations */
301  // Demand is 11bit signed duty cycle [-1023,1023].
302  static const int kMode_DutyCycle = 0;
303  // Position PIDF.
304  static const int kMode_PositionCloseLoop = 1;
305  // Velocity PIDF.
306  static const int kMode_VelocityCloseLoop = 2;
307  // Current close loop - not done.
308  static const int kMode_CurrentCloseLoop = 3;
309  // Voltage Compensation Mode - not done. Demand is fixed pt target 8.8 volts.
310  static const int kMode_VoltCompen = 4;
311  // Demand is the 6 bit Device ID of the 'master' TALON SRX.
312  static const int kMode_SlaveFollower = 5;
313  // Demand is '0' (Disabled), '1' (Enabled), or '2' (Hold).
314  static const int kMode_MotionProfile = 6;
315  // Zero the output (honors brake/coast) regardless of demand.
316  // Might be useful if we need to change modes but can't atomically
317  // change all the signals we want in between.
318  static const int kMode_NoDrive = 15;
319  /* limit switch enumerations */
320  static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1;
321  static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4;
322  static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5;
323  static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6;
324  static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7;
325  /* brake override enumerations */
326  static const int kBrakeOverride_UseDefaultsFromFlash = 0;
327  static const int kBrakeOverride_OverrideCoast = 1;
328  static const int kBrakeOverride_OverrideBrake = 2;
329  /* feedback device enumerations */
330  static const int kFeedbackDev_DigitalQuadEnc = 0;
331  static const int kFeedbackDev_AnalogPot = 2;
332  static const int kFeedbackDev_AnalogEncoder = 3;
333  static const int kFeedbackDev_CountEveryRisingEdge = 4;
334  static const int kFeedbackDev_CountEveryFallingEdge = 5;
335  static const int kFeedbackDev_PosIsPulseWidth = 8;
336  /* ProfileSlotSelect enumerations*/
337  static const int kProfileSlotSelect_Slot0 = 0;
338  static const int kProfileSlotSelect_Slot1 = 1;
339  /* status frame rate types */
340  static const int kStatusFrame_General = 0;
341  static const int kStatusFrame_Feedback = 1;
342  static const int kStatusFrame_Encoder = 2;
343  static const int kStatusFrame_AnalogTempVbat = 3;
344  static const int kStatusFrame_PulseWidthMeas = 4;
345  static const int kStatusFrame_MotionProfile = 5;
346  /* Motion Profile status bits */
347  static const int kMotionProfileFlag_ActTraj_IsValid = 0x1;
348  static const int kMotionProfileFlag_HasUnderrun = 0x2;
349  static const int kMotionProfileFlag_IsUnderrun = 0x4;
350  static const int kMotionProfileFlag_ActTraj_IsLast = 0x8;
351  static const int kMotionProfileFlag_ActTraj_VelOnly = 0x10;
352  /* Motion Profile Set Output */
353  // Motor output is neutral, Motion Profile Executer is not running.
354  static const int kMotionProf_Disabled = 0;
355  // Motor output is updated from Motion Profile Executer, MPE will
356  // process the buffered points.
357  static const int kMotionProf_Enable = 1;
358  // Motor output is updated from Motion Profile Executer, MPE will
359  // stay processing current trajectory point.
360  static const int kMotionProf_Hold = 2;
368  enum param_t {
369  eProfileParamSlot0_P = 1,
370  eProfileParamSlot0_I = 2,
371  eProfileParamSlot0_D = 3,
372  eProfileParamSlot0_F = 4,
373  eProfileParamSlot0_IZone = 5,
374  eProfileParamSlot0_CloseLoopRampRate = 6,
375  eProfileParamSlot1_P = 11,
376  eProfileParamSlot1_I = 12,
377  eProfileParamSlot1_D = 13,
378  eProfileParamSlot1_F = 14,
379  eProfileParamSlot1_IZone = 15,
380  eProfileParamSlot1_CloseLoopRampRate = 16,
381  eProfileParamSoftLimitForThreshold = 21,
382  eProfileParamSoftLimitRevThreshold = 22,
383  eProfileParamSoftLimitForEnable = 23,
384  eProfileParamSoftLimitRevEnable = 24,
385  eOnBoot_BrakeMode = 31,
386  eOnBoot_LimitSwitch_Forward_NormallyClosed = 32,
387  eOnBoot_LimitSwitch_Reverse_NormallyClosed = 33,
388  eOnBoot_LimitSwitch_Forward_Disable = 34,
389  eOnBoot_LimitSwitch_Reverse_Disable = 35,
390  eFault_OverTemp = 41,
391  eFault_UnderVoltage = 42,
392  eFault_ForLim = 43,
393  eFault_RevLim = 44,
394  eFault_HardwareFailure = 45,
395  eFault_ForSoftLim = 46,
396  eFault_RevSoftLim = 47,
397  eStckyFault_OverTemp = 48,
398  eStckyFault_UnderVoltage = 49,
399  eStckyFault_ForLim = 50,
400  eStckyFault_RevLim = 51,
401  eStckyFault_ForSoftLim = 52,
402  eStckyFault_RevSoftLim = 53,
403  eAppliedThrottle = 61,
404  eCloseLoopErr = 62,
405  eFeedbackDeviceSelect = 63,
406  eRevMotDuringCloseLoopEn = 64,
407  eModeSelect = 65,
408  eProfileSlotSelect = 66,
409  eRampThrottle = 67,
410  eRevFeedbackSensor = 68,
411  eLimitSwitchEn = 69,
412  eLimitSwitchClosedFor = 70,
413  eLimitSwitchClosedRev = 71,
414  eSensorPosition = 73,
415  eSensorVelocity = 74,
416  eCurrent = 75,
417  eBrakeIsEnabled = 76,
418  eEncPosition = 77,
419  eEncVel = 78,
420  eEncIndexRiseEvents = 79,
421  eQuadApin = 80,
422  eQuadBpin = 81,
423  eQuadIdxpin = 82,
424  eAnalogInWithOv = 83,
425  eAnalogInVel = 84,
426  eTemp = 85,
427  eBatteryV = 86,
428  eResetCount = 87,
429  eResetFlags = 88,
430  eFirmVers = 89,
431  eSettingsChanged = 90,
432  eQuadFilterEn = 91,
433  ePidIaccum = 93,
434  eStatus1FrameRate = 94, // TALON_Status_1_General_10ms_t
435  eStatus2FrameRate = 95, // TALON_Status_2_Feedback_20ms_t
436  eStatus3FrameRate = 96, // TALON_Status_3_Enc_100ms_t
437  eStatus4FrameRate = 97, // TALON_Status_4_AinTempVbat_100ms_t
438  eStatus6FrameRate = 98, // TALON_Status_6_Eol_t
439  eStatus7FrameRate = 99, // TALON_Status_7_Debug_200ms_t
440  eClearPositionOnIdx = 100,
441  // reserved,
442  // reserved,
443  // reserved,
444  ePeakPosOutput = 104,
445  eNominalPosOutput = 105,
446  ePeakNegOutput = 106,
447  eNominalNegOutput = 107,
448  eQuadIdxPolarity = 108,
449  eStatus8FrameRate = 109, // TALON_Status_8_PulseWid_100ms_t
450  eAllowPosOverflow = 110,
451  eProfileParamSlot0_AllowableClosedLoopErr = 111,
452  eNumberPotTurns = 112,
453  eNumberEncoderCPR = 113,
454  ePwdPosition = 114,
455  eAinPosition = 115,
456  eProfileParamVcompRate = 116,
457  eProfileParamSlot1_AllowableClosedLoopErr = 117,
458  eStatus9FrameRate = 118, // TALON_Status_9_MotProfBuffer_100ms_t
459  eMotionProfileHasUnderrunErr = 119,
460  eReserved120 = 120,
461  eLegacyControlMode = 121,
462  };
463  //---- setters and getters that use the solicated param request/response ---//
476  CTR_Code SetParam(param_t paramEnum, double value);
484  CTR_Code RequestParam(param_t paramEnum);
485  CTR_Code GetParamResponse(param_t paramEnum, double &value);
486  CTR_Code GetParamResponseInt32(param_t paramEnum, int &value);
487  //----------- getters and setters that use param request/response ----------//
497  CTR_Code SetPgain(unsigned slotIdx, double gain);
498  CTR_Code SetIgain(unsigned slotIdx, double gain);
499  CTR_Code SetDgain(unsigned slotIdx, double gain);
500  CTR_Code SetFgain(unsigned slotIdx, double gain);
501  CTR_Code SetIzone(unsigned slotIdx, int zone);
502  CTR_Code SetCloseLoopRampRate(unsigned slotIdx, int closeLoopRampRate);
503  CTR_Code SetVoltageCompensationRate(double voltagePerMs);
504  CTR_Code SetSensorPosition(int pos);
505  CTR_Code SetForwardSoftLimit(int forwardLimit);
506  CTR_Code SetReverseSoftLimit(int reverseLimit);
507  CTR_Code SetForwardSoftEnable(int enable);
508  CTR_Code SetReverseSoftEnable(int enable);
509  CTR_Code GetPgain(unsigned slotIdx, double &gain);
510  CTR_Code GetIgain(unsigned slotIdx, double &gain);
511  CTR_Code GetDgain(unsigned slotIdx, double &gain);
512  CTR_Code GetFgain(unsigned slotIdx, double &gain);
513  CTR_Code GetIzone(unsigned slotIdx, int &zone);
514  CTR_Code GetCloseLoopRampRate(unsigned slotIdx, int &closeLoopRampRate);
515  CTR_Code GetVoltageCompensationRate(double &voltagePerMs);
516  CTR_Code GetForwardSoftLimit(int &forwardLimit);
517  CTR_Code GetReverseSoftLimit(int &reverseLimit);
518  CTR_Code GetForwardSoftEnable(int &enable);
519  CTR_Code GetReverseSoftEnable(int &enable);
520  CTR_Code GetPulseWidthRiseToFallUs(int &param);
521  CTR_Code IsPulseWidthSensorPresent(int &param);
522  CTR_Code SetModeSelect(int modeSelect, int demand);
527  CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs);
539  void ChangeMotionControlFramePeriod(uint32_t periodMs);
589  CTR_Code PushMotionProfileTrajectory(int targPos, int targVel,
590  int profileSlotSelect, int timeDurMs,
591  int velOnly, int isLastPoint,
592  int zeroPos);
650  CTR_Code GetMotionProfileStatus(uint32_t &flags, uint32_t &profileSlotSelect,
651  int32_t &targPos, int32_t &targVel,
652  uint32_t &topBufferRemaining,
653  uint32_t &topBufferCnt,
654  uint32_t &btmBufferCnt,
655  uint32_t &outputEnable);
656 //------------------------ auto generated ------------------------------------//
657 /* This API is optimal since it uses the fire-and-forget CAN interface.
658  * These signals should cover the majority of all use cases.
659  */
660  CTR_Code GetFault_OverTemp(int &param);
661  CTR_Code GetFault_UnderVoltage(int &param);
662  CTR_Code GetFault_ForLim(int &param);
663  CTR_Code GetFault_RevLim(int &param);
664  CTR_Code GetFault_HardwareFailure(int &param);
665  CTR_Code GetFault_ForSoftLim(int &param);
666  CTR_Code GetFault_RevSoftLim(int &param);
667  CTR_Code GetStckyFault_OverTemp(int &param);
668  CTR_Code GetStckyFault_UnderVoltage(int &param);
669  CTR_Code GetStckyFault_ForLim(int &param);
670  CTR_Code GetStckyFault_RevLim(int &param);
671  CTR_Code GetStckyFault_ForSoftLim(int &param);
672  CTR_Code GetStckyFault_RevSoftLim(int &param);
673  CTR_Code GetAppliedThrottle(int &param);
674  CTR_Code GetCloseLoopErr(int &param);
675  CTR_Code GetFeedbackDeviceSelect(int &param);
676  CTR_Code GetModeSelect(int &param);
677  CTR_Code GetLimitSwitchEn(int &param);
678  CTR_Code GetLimitSwitchClosedFor(int &param);
679  CTR_Code GetLimitSwitchClosedRev(int &param);
680  CTR_Code GetSensorPosition(int &param);
681  CTR_Code GetSensorVelocity(int &param);
682  CTR_Code GetCurrent(double &param);
683  CTR_Code GetBrakeIsEnabled(int &param);
684  CTR_Code GetEncPosition(int &param);
685  CTR_Code GetEncVel(int &param);
686  CTR_Code GetEncIndexRiseEvents(int &param);
687  CTR_Code GetQuadApin(int &param);
688  CTR_Code GetQuadBpin(int &param);
689  CTR_Code GetQuadIdxpin(int &param);
690  CTR_Code GetAnalogInWithOv(int &param);
691  CTR_Code GetAnalogInVel(int &param);
692  CTR_Code GetTemp(double &param);
693  CTR_Code GetBatteryV(double &param);
694  CTR_Code GetResetCount(int &param);
695  CTR_Code GetResetFlags(int &param);
696  CTR_Code GetFirmVers(int &param);
697  CTR_Code GetPulseWidthPosition(int &param);
698  CTR_Code GetPulseWidthVelocity(int &param);
699  CTR_Code GetPulseWidthRiseToRiseUs(int &param);
700  CTR_Code GetActTraj_IsValid(int &param);
701  CTR_Code GetActTraj_ProfileSlotSelect(int &param);
702  CTR_Code GetActTraj_VelOnly(int &param);
703  CTR_Code GetActTraj_IsLast(int &param);
704  CTR_Code GetOutputType(int &param);
705  CTR_Code GetHasUnderrun(int &param);
706  CTR_Code GetIsUnderrun(int &param);
707  CTR_Code GetNextID(int &param);
708  CTR_Code GetBufferIsFull(int &param);
709  CTR_Code GetCount(int &param);
710  CTR_Code GetActTraj_Velocity(int &param);
711  CTR_Code GetActTraj_Position(int &param);
712  CTR_Code SetDemand(int param);
713  CTR_Code SetOverrideLimitSwitchEn(int param);
714  CTR_Code SetFeedbackDeviceSelect(int param);
715  CTR_Code SetRevMotDuringCloseLoopEn(int param);
716  CTR_Code SetOverrideBrakeType(int param);
717  CTR_Code SetModeSelect(int param);
718  CTR_Code SetProfileSlotSelect(int param);
719  CTR_Code SetRampThrottle(int param);
720  CTR_Code SetRevFeedbackSensor(int param);
721 };
722 extern "C" {
723  void *c_TalonSRX_Create3(int deviceNumber, int controlPeriodMs, int enablePeriodMs);
724  void *c_TalonSRX_Create2(int deviceNumber, int controlPeriodMs);
725  void *c_TalonSRX_Create1(int deviceNumber);
726  void c_TalonSRX_Destroy(void *handle);
727  void c_TalonSRX_Set(void *handle, double value);
728  CTR_Code c_TalonSRX_SetParam(void *handle, int paramEnum, double value);
729  CTR_Code c_TalonSRX_RequestParam(void *handle, int paramEnum);
730  CTR_Code c_TalonSRX_GetParamResponse(void *handle, int paramEnum, double *value);
731  CTR_Code c_TalonSRX_GetParamResponseInt32(void *handle, int paramEnum, int *value);
732  CTR_Code c_TalonSRX_SetPgain(void *handle, int slotIdx, double gain);
733  CTR_Code c_TalonSRX_SetIgain(void *handle, int slotIdx, double gain);
734  CTR_Code c_TalonSRX_SetDgain(void *handle, int slotIdx, double gain);
735  CTR_Code c_TalonSRX_SetFgain(void *handle, int slotIdx, double gain);
736  CTR_Code c_TalonSRX_SetIzone(void *handle, int slotIdx, int zone);
737  CTR_Code c_TalonSRX_SetCloseLoopRampRate(void *handle, int slotIdx, int closeLoopRampRate);
738  CTR_Code c_TalonSRX_SetVoltageCompensationRate(void *handle, double voltagePerMs);
739  CTR_Code c_TalonSRX_SetSensorPosition(void *handle, int pos);
740  CTR_Code c_TalonSRX_SetForwardSoftLimit(void *handle, int forwardLimit);
741  CTR_Code c_TalonSRX_SetReverseSoftLimit(void *handle, int reverseLimit);
742  CTR_Code c_TalonSRX_SetForwardSoftEnable(void *handle, int enable);
743  CTR_Code c_TalonSRX_SetReverseSoftEnable(void *handle, int enable);
744  CTR_Code c_TalonSRX_GetPgain(void *handle, int slotIdx, double *gain);
745  CTR_Code c_TalonSRX_GetIgain(void *handle, int slotIdx, double *gain);
746  CTR_Code c_TalonSRX_GetDgain(void *handle, int slotIdx, double *gain);
747  CTR_Code c_TalonSRX_GetFgain(void *handle, int slotIdx, double *gain);
748  CTR_Code c_TalonSRX_GetIzone(void *handle, int slotIdx, int *zone);
749  CTR_Code c_TalonSRX_GetCloseLoopRampRate(void *handle, int slotIdx, int *closeLoopRampRate);
750  CTR_Code c_TalonSRX_GetVoltageCompensationRate(void *handle, double *voltagePerMs);
751  CTR_Code c_TalonSRX_GetForwardSoftLimit(void *handle, int *forwardLimit);
752  CTR_Code c_TalonSRX_GetReverseSoftLimit(void *handle, int *reverseLimit);
753  CTR_Code c_TalonSRX_GetForwardSoftEnable(void *handle, int *enable);
754  CTR_Code c_TalonSRX_GetReverseSoftEnable(void *handle, int *enable);
755  CTR_Code c_TalonSRX_GetPulseWidthRiseToFallUs(void *handle, int *param);
756  CTR_Code c_TalonSRX_IsPulseWidthSensorPresent(void *handle, int *param);
757  CTR_Code c_TalonSRX_SetModeSelect2(void *handle, int modeSelect, int demand);
758  CTR_Code c_TalonSRX_SetStatusFrameRate(void *handle, int frameEnum, int periodMs);
759  CTR_Code c_TalonSRX_ClearStickyFaults(void *handle);
760  void c_TalonSRX_ChangeMotionControlFramePeriod(void *handle, int periodMs);
761  void c_TalonSRX_ClearMotionProfileTrajectories(void *handle);
762  int c_TalonSRX_GetMotionProfileTopLevelBufferCount(void *handle);
763  int c_TalonSRX_IsMotionProfileTopLevelBufferFull(void *handle);
764  CTR_Code c_TalonSRX_PushMotionProfileTrajectory(void *handle, int targPos, int targVel, int profileSlotSelect, int timeDurMs, int velOnly, int isLastPoint, int zeroPos);
765  void c_TalonSRX_ProcessMotionProfileBuffer(void *handle);
766  CTR_Code c_TalonSRX_GetMotionProfileStatus(void *handle, int *flags, int *profileSlotSelect, int *targPos, int *targVel, int *topBufferRemaining, int *topBufferCnt, int *btmBufferCnt, int *outputEnable);
767  CTR_Code c_TalonSRX_GetFault_OverTemp(void *handle, int *param);
768  CTR_Code c_TalonSRX_GetFault_UnderVoltage(void *handle, int *param);
769  CTR_Code c_TalonSRX_GetFault_ForLim(void *handle, int *param);
770  CTR_Code c_TalonSRX_GetFault_RevLim(void *handle, int *param);
771  CTR_Code c_TalonSRX_GetFault_HardwareFailure(void *handle, int *param);
772  CTR_Code c_TalonSRX_GetFault_ForSoftLim(void *handle, int *param);
773  CTR_Code c_TalonSRX_GetFault_RevSoftLim(void *handle, int *param);
774  CTR_Code c_TalonSRX_GetStckyFault_OverTemp(void *handle, int *param);
775  CTR_Code c_TalonSRX_GetStckyFault_UnderVoltage(void *handle, int *param);
776  CTR_Code c_TalonSRX_GetStckyFault_ForLim(void *handle, int *param);
777  CTR_Code c_TalonSRX_GetStckyFault_RevLim(void *handle, int *param);
778  CTR_Code c_TalonSRX_GetStckyFault_ForSoftLim(void *handle, int *param);
779  CTR_Code c_TalonSRX_GetStckyFault_RevSoftLim(void *handle, int *param);
780  CTR_Code c_TalonSRX_GetAppliedThrottle(void *handle, int *param);
781  CTR_Code c_TalonSRX_GetCloseLoopErr(void *handle, int *param);
782  CTR_Code c_TalonSRX_GetFeedbackDeviceSelect(void *handle, int *param);
783  CTR_Code c_TalonSRX_GetModeSelect(void *handle, int *param);
784  CTR_Code c_TalonSRX_GetLimitSwitchEn(void *handle, int *param);
785  CTR_Code c_TalonSRX_GetLimitSwitchClosedFor(void *handle, int *param);
786  CTR_Code c_TalonSRX_GetLimitSwitchClosedRev(void *handle, int *param);
787  CTR_Code c_TalonSRX_GetSensorPosition(void *handle, int *param);
788  CTR_Code c_TalonSRX_GetSensorVelocity(void *handle, int *param);
789  CTR_Code c_TalonSRX_GetCurrent(void *handle, double *param);
790  CTR_Code c_TalonSRX_GetBrakeIsEnabled(void *handle, int *param);
791  CTR_Code c_TalonSRX_GetEncPosition(void *handle, int *param);
792  CTR_Code c_TalonSRX_GetEncVel(void *handle, int *param);
793  CTR_Code c_TalonSRX_GetEncIndexRiseEvents(void *handle, int *param);
794  CTR_Code c_TalonSRX_GetQuadApin(void *handle, int *param);
795  CTR_Code c_TalonSRX_GetQuadBpin(void *handle, int *param);
796  CTR_Code c_TalonSRX_GetQuadIdxpin(void *handle, int *param);
797  CTR_Code c_TalonSRX_GetAnalogInWithOv(void *handle, int *param);
798  CTR_Code c_TalonSRX_GetAnalogInVel(void *handle, int *param);
799  CTR_Code c_TalonSRX_GetTemp(void *handle, double *param);
800  CTR_Code c_TalonSRX_GetBatteryV(void *handle, double *param);
801  CTR_Code c_TalonSRX_GetResetCount(void *handle, int *param);
802  CTR_Code c_TalonSRX_GetResetFlags(void *handle, int *param);
803  CTR_Code c_TalonSRX_GetFirmVers(void *handle, int *param);
804  CTR_Code c_TalonSRX_GetPulseWidthPosition(void *handle, int *param);
805  CTR_Code c_TalonSRX_GetPulseWidthVelocity(void *handle, int *param);
806  CTR_Code c_TalonSRX_GetPulseWidthRiseToRiseUs(void *handle, int *param);
807  CTR_Code c_TalonSRX_GetActTraj_IsValid(void *handle, int *param);
808  CTR_Code c_TalonSRX_GetActTraj_ProfileSlotSelect(void *handle, int *param);
809  CTR_Code c_TalonSRX_GetActTraj_VelOnly(void *handle, int *param);
810  CTR_Code c_TalonSRX_GetActTraj_IsLast(void *handle, int *param);
811  CTR_Code c_TalonSRX_GetOutputType(void *handle, int *param);
812  CTR_Code c_TalonSRX_GetHasUnderrun(void *handle, int *param);
813  CTR_Code c_TalonSRX_GetIsUnderrun(void *handle, int *param);
814  CTR_Code c_TalonSRX_GetNextID(void *handle, int *param);
815  CTR_Code c_TalonSRX_GetBufferIsFull(void *handle, int *param);
816  CTR_Code c_TalonSRX_GetCount(void *handle, int *param);
817  CTR_Code c_TalonSRX_GetActTraj_Velocity(void *handle, int *param);
818  CTR_Code c_TalonSRX_GetActTraj_Position(void *handle, int *param);
819  CTR_Code c_TalonSRX_SetDemand(void *handle, int param);
820  CTR_Code c_TalonSRX_SetOverrideLimitSwitchEn(void *handle, int param);
821  CTR_Code c_TalonSRX_SetFeedbackDeviceSelect(void *handle, int param);
822  CTR_Code c_TalonSRX_SetRevMotDuringCloseLoopEn(void *handle, int param);
823  CTR_Code c_TalonSRX_SetOverrideBrakeType(void *handle, int param);
824  CTR_Code c_TalonSRX_SetModeSelect(void *handle, int param);
825  CTR_Code c_TalonSRX_SetProfileSlotSelect(void *handle, int param);
826  CTR_Code c_TalonSRX_SetRampThrottle(void *handle, int param);
827  CTR_Code c_TalonSRX_SetRevFeedbackSensor(void *handle, int param);
828 }
829 #endif
CTR_Code ClearStickyFaults()
Clear all sticky faults in TALON.
Definition: CtreCanNode.h:20
void ProcessMotionProfileBuffer()
This must be called periodically to funnel the trajectory points from the API's top level buffer to t...
Common header for all CTRE HAL modules.
Definition: ctre_frames.h:49
CTR_Code SetParam(param_t paramEnum, double value)
Send a one shot frame to set an arbitrary signal.
CAN TALON SRX driver.
Definition: CanTalonSRX.h:116
CTR_Code SetStatusFrameRate(unsigned frameEnum, unsigned periodMs)
Change the periodMs of a TALON's status frame.
Definition: CtreCanNode.h:7
uint32_t GetMotionProfileTopLevelBufferCount()
Retrieve just the buffer count for the api-level (top) buffer.
CTR_Code
Definition: ctre.h:44
Definition: CANSessionMux.h:27
CTR_Code GetMotionProfileStatus(uint32_t &flags, uint32_t &profileSlotSelect, int32_t &targPos, int32_t &targVel, uint32_t &topBufferRemaining, uint32_t &topBufferCnt, uint32_t &btmBufferCnt, uint32_t &outputEnable)
Retrieve all status information.
param_t
Signal enumeration for generic signal access.
Definition: CanTalonSRX.h:368
CTR_Code PushMotionProfileTrajectory(int targPos, int targVel, int profileSlotSelect, int timeDurMs, int velOnly, int isLastPoint, int zeroPos)
Push another trajectory point into the top level buffer (which is emptied into the Talon's bottom buf...
void ChangeMotionControlFramePeriod(uint32_t periodMs)
Calling application can opt to speed up the handshaking between the robot API and the Talon to increa...
void ClearMotionProfileTrajectories()
Clear the buffered motion profile in both Talon RAM (bottom), and in the API (top).
CTR_Code RequestParam(param_t paramEnum)
Asks TALON to immedietely respond with signal value.
bool IsMotionProfileTopLevelBufferFull()
Retrieve just the buffer full for the api-level (top) buffer.
CTR_Code SetPgain(unsigned slotIdx, double gain)
These signals are backed up in flash and will survive a power cycle.