Class BaseTalon

java.lang.Object
com.ctre.phoenix.motorcontrol.can.BaseMotorController
com.ctre.phoenix.motorcontrol.can.BaseTalon
All Implemented Interfaces:
IFollower, IMotorController, IMotorControllerEnhanced, IInvertable, IOutputSignal
Direct Known Subclasses:
TalonFX, TalonSRX

public class BaseTalon
extends BaseMotorController
implements IMotorControllerEnhanced
CTRE Talon SRX Motor Controller when used on CAN Bus.
  • Constructor Details

    • BaseTalon

      public BaseTalon​(int deviceNumber, String model, String canbus)
      Constructor for BaseTalon object
      Parameters:
      deviceNumber - CAN Device ID of Device
    • BaseTalon

      public BaseTalon​(int deviceNumber, String model)
      Constructor for BaseTalon object
      Parameters:
      deviceNumber - CAN Device ID of Device
  • Method Details

    • getTalonSRXSensorCollection

    • getTalonFXSensorCollection

    • getTalonSRXSimCollection

    • getTalonFXSimCollection

    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(StatusFrameEnhanced frame, int periodMs, int timeoutMs)
      Sets the period of the given status frame. User ensure CAN Bus utilization is not high. This setting is not persistent and is lost when device is reset. If this is a concern, calling application can use hasResetOccurred() to determine if the status frame needs to be reconfigured.
      Specified by:
      setStatusFramePeriod in interface IMotorControllerEnhanced
      Parameters:
      frame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • setStatusFramePeriod

      public ErrorCode setStatusFramePeriod​(StatusFrameEnhanced frame, int periodMs)
      Sets the period of the given status frame. User ensure CAN Bus utilization is not high. This setting is not persistent and is lost when device is reset. If this is a concern, calling application can use hasResetOccurred() to determine if the status frame needs to be reconfigured.
      Parameters:
      frame - Frame whose period is to be changed.
      periodMs - Period in ms for the given frame.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getStatusFramePeriod

      public int getStatusFramePeriod​(StatusFrameEnhanced frame, int timeoutMs)
      Gets the period of the given status frame.
      Specified by:
      getStatusFramePeriod in interface IMotorControllerEnhanced
      Overrides:
      getStatusFramePeriod in class BaseMotorController
      Parameters:
      frame - Frame to get the period of.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Period of the given status frame.
    • getStatusFramePeriod

      Gets the period of the given status frame.
      Overrides:
      getStatusFramePeriod in class BaseMotorController
      Parameters:
      frame - Frame to get the period of.
      Returns:
      Period of the given status frame.
    • getOutputCurrent

      @Deprecated public double getOutputCurrent()
      Deprecated.
      Use getStatorCurrent/getSupplyCurrent instead.
      Gets the output current of the motor controller. In the case of TalonSRX class, this routine returns supply current for legacy reasons. In order to get the "true" output current, call GetStatorCurrent(). In the case of TalonFX class, this routine returns the true output stator current.
      Specified by:
      getOutputCurrent in interface IMotorControllerEnhanced
      Overrides:
      getOutputCurrent in class BaseMotorController
      Returns:
      The output current (in amps).
    • getStatorCurrent

      public double getStatorCurrent()
      Gets the stator/output current of the motor controller.
      Returns:
      The stator/output current (in amps).
    • getSupplyCurrent

      public double getSupplyCurrent()
      Gets the supply/input current of the motor controller.
      Returns:
      The supply/input current (in amps).
    • configVelocityMeasurementPeriod

      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Specified by:
      configVelocityMeasurementPeriod in interface IMotorControllerEnhanced
      Overrides:
      configVelocityMeasurementPeriod in class BaseMotorController
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementPeriod

      Deprecated.
      Use the overload with SensorVelocityMeasPeriod instead.
      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Specified by:
      configVelocityMeasurementPeriod in interface IMotorControllerEnhanced
      Overrides:
      configVelocityMeasurementPeriod in class BaseMotorController
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementPeriod

      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Overrides:
      configVelocityMeasurementPeriod in class BaseMotorController
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementPeriod

      Deprecated.
      Use the overload with SensorVelocityMeasPeriod instead.
      Configures the period of each velocity sample. Every 1ms a position value is sampled, and the delta between that sample and the position sampled kPeriod ms ago is inserted into a filter. kPeriod is configured with this function.
      Overrides:
      configVelocityMeasurementPeriod in class BaseMotorController
      Parameters:
      period - Desired period for the velocity measurement. @see com.ctre.phoenix.motorcontrol.VelocityMeasPeriod
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementWindow

      public ErrorCode configVelocityMeasurementWindow​(int windowSize, int timeoutMs)
      Sets the number of velocity samples used in the rolling average velocity measurement.
      Specified by:
      configVelocityMeasurementWindow in interface IMotorControllerEnhanced
      Overrides:
      configVelocityMeasurementWindow in class BaseMotorController
      Parameters:
      windowSize - Number of samples in the rolling average of velocity measurement. Valid values are 1,2,4,8,16,32. If another value is specified, it will truncate to nearest support value.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configVelocityMeasurementWindow

      public ErrorCode configVelocityMeasurementWindow​(int windowSize)
      Sets the number of velocity samples used in the rolling average velocity measurement.
      Overrides:
      configVelocityMeasurementWindow in class BaseMotorController
      Parameters:
      windowSize - Number of samples in the rolling average of velocity measurement. Valid values are 1,2,4,8,16,32. If another value is specified, it will truncate to nearest support value.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configForwardLimitSwitchSource

      public ErrorCode configForwardLimitSwitchSource​(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)
      Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.
      Specified by:
      configForwardLimitSwitchSource in interface IMotorControllerEnhanced
      Overrides:
      configForwardLimitSwitchSource in class BaseMotorController
      Parameters:
      type - Limit switch source. User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
      normalOpenOrClose - Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configForwardLimitSwitchSource

      Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.
      Overrides:
      configForwardLimitSwitchSource in class BaseMotorController
      Parameters:
      type - Limit switch source. User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
      normalOpenOrClose - Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configReverseLimitSwitchSource

      public ErrorCode configReverseLimitSwitchSource​(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)
      Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.
      Specified by:
      configReverseLimitSwitchSource in interface IMotorControllerEnhanced
      Parameters:
      type - Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
      normalOpenOrClose - Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configReverseLimitSwitchSource

      Configures a limit switch for a local/remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon, CANifier, or local Gadgeteer feedback connector. If the sensor is remote, a device ID of zero is assumed. If that's not desired, use the four parameter version of this function.
      Parameters:
      type - Limit switch source. @see com.ctre.phoenix.motorcontrol.LimitSwitchSource User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
      normalOpenOrClose - Setting for normally open, normally closed, or disabled. This setting matches the Phoenix Tuner drop down.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configSupplyCurrentLimit

      public ErrorCode configSupplyCurrentLimit​(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs)
      Configures the supply (input) current limit.
      Specified by:
      configSupplyCurrentLimit in interface IMotorControllerEnhanced
      Parameters:
      currLimitCfg - Current limit configuration
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • isFwdLimitSwitchClosed

      public int isFwdLimitSwitchClosed()
      Is forward limit switch closed.
      Returns:
      '1' iff forward limit switch input is closed, 0 iff switch is open. This function works regardless if limit switch feature is enabled. Remote limit features do not impact this routine.
    • isRevLimitSwitchClosed

      public int isRevLimitSwitchClosed()
      Is reverse limit switch closed.
      Returns:
      '1' iff reverse limit switch is closed, 0 iff switch is open. This function works regardless if limit switch feature is enabled. Remote limit features do not impact this routine.
    • configurePID

      protected ErrorCode configurePID​(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs, boolean enableOptimizations)
      Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).
      Parameters:
      pid - Object with all of the PID set persistant settings
      pidIdx - 0 for Primary closed-loop. 1 for auxiliary closed-loop.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      enableOptimizations - Enable the optimization technique
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configurePID

      Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).
      Parameters:
      pid - Object with all of the PID set persistant settings
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getPIDConfigs

      protected void getPIDConfigs​(BaseTalonPIDSetConfiguration pid, int pidIdx, int timeoutMs)
      Gets all PID set persistant settings.
      Parameters:
      pid - Object with all of the PID set persistant settings
      pidIdx - 0 for Primary closed-loop. 1 for auxiliary closed-loop.
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
    • getPIDConfigs

      Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).
      Parameters:
      pid - Object with all of the PID set persistant settings
    • configAllSettings

      protected ErrorCode configAllSettings​(BaseTalonConfiguration allConfigs, int timeoutMs)
      Configures all persistent settings.
      Parameters:
      allConfigs - Object with all of the persistant settings
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
      Returns:
      Error Code generated by function. 0 indicates no error.
    • configAllSettings

      Configures all persistent settings (overloaded so timeoutMs is 50 ms).
      Parameters:
      allConfigs - Object with all of the persistant settings
      Returns:
      Error Code generated by function. 0 indicates no error.
    • getAllConfigs

      protected void getAllConfigs​(BaseTalonConfiguration allConfigs, int timeoutMs)
      Gets all persistant settings.
      Parameters:
      allConfigs - Object with all of the persistant settings
      timeoutMs - Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.
    • getAllConfigs

      protected void getAllConfigs​(BaseTalonConfiguration allConfigs)
      Gets all persistant settings (overloaded so timeoutMs is 50 ms).
      Parameters:
      allConfigs - Object with all of the persistant settings