BaseTalon

class phoenix5.BaseTalon(deviceNumber: int, model: str, canbus: str = '')

Bases: BaseMotorController, IMotorControllerEnhanced

CTRE Talon SRX Motor Controller when used on CAN Bus.

Constructor for a Talon

Parameters:
  • deviceNumber – CAN Device ID of BaseTalon

  • canbus – Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number

configForwardLimitSwitchSource(*args, **kwargs)

Overloaded function.

  1. configForwardLimitSwitchSource(self: phoenix5._ctre.BaseTalon, limitSwitchSource: phoenix5._ctre.LimitSwitchSource, normalOpenOrClose: phoenix5._ctre.LimitSwitchNormal, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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:
  • limitSwitchSource – 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.

  1. configForwardLimitSwitchSource(self: phoenix5._ctre.BaseTalon, limitSwitchSource: phoenix5._ctre.RemoteLimitSwitchSource, normalOpenOrClose: phoenix5._ctre.LimitSwitchNormal, deviceID: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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:
  • limitSwitchSource – 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.

  • deviceID – Device ID of remote source (Talon SRX or CANifier device ID).

  • 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(*args, **kwargs)

Overloaded function.

  1. configReverseLimitSwitchSource(self: phoenix5._ctre.BaseTalon, limitSwitchSource: phoenix5._ctre.LimitSwitchSource, normalOpenOrClose: phoenix5._ctre.LimitSwitchNormal, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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:
  • limitSwitchSource – Limit switch source. @see #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.

  1. configReverseLimitSwitchSource(self: phoenix5._ctre.BaseTalon, limitSwitchSource: phoenix5._ctre.RemoteLimitSwitchSource, normalOpenOrClose: phoenix5._ctre.LimitSwitchNormal, deviceID: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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:
  • limitSwitchSource – Limit switch source. @see #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.

  • deviceID – Device ID of remote source (Talon SRX or CANifier device ID).

  • 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.

configSelectedFeedbackSensor(*args, **kwargs)

Overloaded function.

  1. configSelectedFeedbackSensor(self: phoenix5._ctre.BaseTalon, feedbackDevice: phoenix5._ctre.FeedbackDevice, pidIdx: int = 0, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select the remote feedback device for the motor controller. Most CTRE CAN motor controllers will support remote sensors over CAN.

Parameters:
  • feedbackDevice – Remote Feedback Device to select.

  • 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.

Returns:

Error Code generated by function. 0 indicates no error.

  1. configSelectedFeedbackSensor(self: phoenix5._ctre.BaseTalon, feedbackDevice: phoenix5._ctre.RemoteFeedbackDevice, pidIdx: int = 0, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select the remote feedback device for the motor controller. Most CTRE CAN motor controllers will support remote sensors over CAN.

Parameters:
  • feedbackDevice – Remote Feedback Device to select.

  • 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.

Returns:

Error Code generated by function. 0 indicates no error.

configSupplyCurrentLimit(currLimitConfigs: phoenix5._ctre.SupplyCurrentLimitConfiguration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode
configVelocityMeasurementPeriod(period: phoenix5._ctre.sensors.SensorVelocityMeasPeriod, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

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.

Parameters:
  • period – Desired period for the velocity measurement. @see #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.

configVelocityMeasurementWindow(windowSize: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the number of velocity samples used in the rolling average velocity measurement.

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.

getOutputCurrent() float

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.

[[deprecated(“Use GetStatorCurrent/GetSupplyCurrent instead.”)]]

Returns:

The output current (in amps).

getStatorCurrent() float

Gets the stator/output current of the motor controller.

Returns:

The stator/output current (in amps).

getStatusFramePeriod(*args, **kwargs)

Overloaded function.

  1. getStatusFramePeriod(self: phoenix5._ctre.BaseTalon, frame: phoenix5._ctre.StatusFrameEnhanced, timeoutMs: int = 0) -> int

Gets the period of the given status frame.

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.

  1. getStatusFramePeriod(self: phoenix5._ctre.BaseTalon, frame: phoenix5._ctre.StatusFrame, timeoutMs: int = 0) -> int

Gets the period of the given status frame.

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.

getSupplyCurrent() float

Gets the supply/input current of the motor controller.

Returns:

The supply/input current (in amps).

isFwdLimitSwitchClosed() int
isRevLimitSwitchClosed() int
setStatusFramePeriod(*args, **kwargs)

Overloaded function.

  1. setStatusFramePeriod(self: phoenix5._ctre.BaseTalon, frame: phoenix5._ctre.StatusFrameEnhanced, periodMs: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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.

  • 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.

  1. setStatusFramePeriod(self: phoenix5._ctre.BaseTalon, frame: phoenix5._ctre.StatusFrame, periodMs: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

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.

  • 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.