IMotorControllerEnhanced

class phoenix5.IMotorControllerEnhanced

Bases: IMotorController

Interface for enhanced motor controllers

configForwardLimitSwitchSource(*args, **kwargs)

Overloaded function.

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

Configures the forward limit switch for a remote source. For example, a CAN motor controller may need to monitor the Limit-F pin of another Talon or CANifier.

Parameters:
  • type – Remote limit switch source. User can choose between a 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.

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

Configures the forward limit switch for a remote source. For example, a CAN motor controller may need to monitor the Limit-F pin of another Talon or CANifier.

Parameters:
  • type – Remote limit switch source. User can choose between a 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(*args, **kwargs)

Overloaded function.

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

Configures the reverse limit switch for a remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon or CANifier.

Parameters:
  • type – Remote limit switch source. User can choose between a 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.

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

Configures the reverse limit switch for a remote source. For example, a CAN motor controller may need to monitor the Limit-R pin of another Talon or CANifier.

Parameters:
  • type – Remote limit switch source. User can choose between a 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.

configSelectedFeedbackSensor(*args, **kwargs)

Overloaded function.

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

Select the feedback device for the motor controller.

Parameters:
  • feedbackDevice – 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.IMotorControllerEnhanced, feedbackDevice: phoenix5._ctre.RemoteFeedbackDevice, pidIdx: int = 0, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select the feedback device for the motor controller.

Parameters:
  • feedbackDevice – 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

Configures the supply-side current limit.

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.

configVelocityMeasurementPeriod(period: phoenix5._ctre.VelocityMeasPeriod, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the period over which velocity measurements are taken.

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.

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

getStatusFramePeriod(*args, **kwargs)

Overloaded function.

  1. getStatusFramePeriod(self: phoenix5._ctre.IMotorControllerEnhanced, 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.

  1. getStatusFramePeriod(self: phoenix5._ctre.IMotorControllerEnhanced, 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.

setStatusFramePeriod(*args, **kwargs)

Overloaded function.

  1. setStatusFramePeriod(self: phoenix5._ctre.IMotorControllerEnhanced, 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.

  1. setStatusFramePeriod(self: phoenix5._ctre.IMotorControllerEnhanced, 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.