IMotorController

class phoenix5.IMotorController

Bases: IFollower

Interface for motor controllers

changeMotionControlFramePeriod(periodMs: int) phoenix5._ctre.ErrorCode

Calling application can opt to speed up the handshaking between the robot API and the controller to increase the download rate of the controller’s Motion Profile. Ideally the period should be no more than half the period of a trajectory point.

Parameters:

periodMs – The transmit period in ms.

Returns:

Error Code generated by function. 0 indicates no error.

clearMotionProfileHasUnderrun(timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Clear the “Has Underrun” flag. Typically this is called after application has confirmed an underrun had occured.

Parameters:

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.

clearMotionProfileTrajectories() phoenix5._ctre.ErrorCode

Clear the buffered motion profile in both controller’s RAM (bottom), and in the API (top).

Returns:

Error Code generated by function. 0 indicates no error

clearStickyFaults(timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Clears all sticky faults.

Parameters:

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:

Last Error Code generated by a function.

configAllowableClosedloopError(slotIdx: int, allowableCloseLoopError: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the allowable closed-loop error in the given parameter slot.

Parameters:
  • slotIdx – Parameter slot for the constant.

  • allowableCloseLoopError – Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).

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

configAuxPIDPolarity(invert: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the Polarity of the Auxiliary PID (PID1).

Standard Polarity: Primary Output = PID0 + PID1, Auxiliary Output = PID0 - PID1,

Inverted Polarity: Primary Output = PID0 - PID1, Auxiliary Output = PID0 + PID1,

Parameters:
  • invert – If true, use inverted PID1 output polarity.

  • 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

configClearPositionOnLimitF(clearPositionOnLimitF: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Enables clearing the position of the feedback sensor when the forward limit switch is triggered

Parameters:
  • clearPositionOnLimitF – Whether clearing is enabled, defaults false

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

configClearPositionOnLimitR(clearPositionOnLimitR: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Enables clearing the position of the feedback sensor when the reverse limit switch is triggered

Parameters:
  • clearPositionOnLimitR – Whether clearing is enabled, defaults false

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

configClearPositionOnQuadIdx(clearPositionOnQuadIdx: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Enables clearing the position of the feedback sensor when the quadrature index signal is detected

Parameters:
  • clearPositionOnQuadIdx – Whether clearing is enabled, defaults false

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

configClosedLoopPeakOutput(slotIdx: int, percentOut: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the peak closed-loop output. This peak output is slot-specific and is applied to the output of the associated PID loop. This setting is seperate from the generic Peak Output setting.

Parameters:
  • slotIdx – Parameter slot for the constant.

  • percentOut – Peak Percent Output from 0 to 1. This value is absolute and * the magnitude will apply in both forward and reverse directions.

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

configClosedLoopPeriod(slotIdx: int, loopTimeMs: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the loop time (in milliseconds) of the PID closed-loop calculations. Default value is 1 ms.

Parameters:
  • slotIdx – Parameter slot for the constant.

  • loopTimeMs – Loop timing of the closed-loop calculations. Minimum value of * 1 ms, maximum of 64 ms.

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

configClosedloopRamp(secondsFromNeutralToFull: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the closed-loop ramp rate of throttle output.

Parameters:
  • secondsFromNeutralToFull – Minimum desired time to go from neutral to full throttle. A value of ‘0’ will disable the ramp.

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

configFactoryDefault(timeout: int) phoenix5._ctre.ErrorCode

Revert all configurations to factory default values. Use this before your individual config* calls to avoid having to config every single param.

Alternatively you can use the configAllSettings routine.

Parameters:

timeout – Timeout value in ms. Function will generate error if config is not successful within timeout.

Returns:

Error Code generated by function. 0 indicates no error.

configFeedbackNotContinuous(feedbackNotContinuous: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Disables continuous tracking of the position for analog and pulse-width. If the signal goes from 4095 to 0 (pulse-width) a motor controller will continue to read 4096 by default. If overflow tracking is disabled, it will wrap to 0 (not continuous)

If using pulse-width on CTRE Mag Encoder (within one rotation) or absolute analog sensor (within one rotation), setting feedbackNotContinuous to true is recommended, to prevent intermittent connections from causing sensor “jumps” of 4096 (or 1024 for analog) units.

Parameters:
  • feedbackNotContinuous – True to disable the overflow tracking.

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

configForwardSoftLimitEnable(enable: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the forward soft limit enable.

Parameters:
  • enable – Forward Sensor Position Limit Enable.

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

configForwardSoftLimitThreshold(forwardSensorLimit: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the forward soft limit threhold.

Parameters:
  • forwardSensorLimit – Forward Sensor Position Limit (in raw sensor units).

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

configGetCustomParam(paramIndex: int, timeoutMs: int = 0) int

Gets the value of a custom parameter.

Parameters:
  • paramIndex – Index of custom parameter [0,1].

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

Value of the custom param.

configGetParameter(paramEnum: phoenix5._ctre.ParamEnum, ordinal: int, timeoutMs: int = 0) float

Gets a parameter.

Parameters:
  • paramEnum – Parameter enumeration.

  • ordinal – Ordinal of parameter.

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

Value of parameter.

configLimitSwitchDisableNeutralOnLOS(limitSwitchDisableNeutralOnLOS: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Disables limit switches triggering (if enabled) when the sensor is no longer detected.

Parameters:
  • limitSwitchDisableNeutralOnLOS – disable triggering

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

configMaxIntegralAccumulator(slotIdx: int, iaccum: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the maximum integral accumulator in the given parameter slot.

Parameters:
  • slotIdx – Parameter slot for the constant.

  • iaccum – Value of the maximum integral accumulator (closed loop error units X 1ms).

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

configMotionAcceleration(sensorUnitsPer100msPerSec: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the Motion Magic Acceleration. This is the target acceleration that the motion magic curve generator can use.

Parameters:
  • sensorUnitsPer100msPerSec – Motion Magic Acceleration (in raw sensor units per 100 ms per second).

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

configMotionCruiseVelocity(sensorUnitsPer100ms: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the Motion Magic Cruise Velocity. This is the peak target velocity that the motion magic curve generator can use.

Parameters:
  • sensorUnitsPer100ms – Motion Magic Cruise Velocity (in raw sensor units per 100 ms).

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

configMotionProfileTrajectoryPeriod(baseTrajDurationMs: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

When trajectory points are processed in the motion profile executer, the MPE determines how long to apply the active trajectory point by summing baseTrajDurationMs with the timeDur of the trajectory point (see TrajectoryPoint).

This allows general selection of the execution rate of the points with 1ms resolution, while allowing some degree of change from point to point.

Parameters:
  • baseTrajDurationMs – The base duration time of every trajectory point. This is summed with the trajectory points unique timeDur.

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

configMotionSCurveStrength(curveStrength: int, timeoutMs: int) phoenix5._ctre.ErrorCode

Sets the Motion Magic S Curve Strength. Call this before using Motion Magic. Modifying this during a Motion Magic action should be avoided.

Parameters:
  • curveStrength – 0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing).

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

configNeutralDeadband(percentDeadband: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the output deadband percentage.

Parameters:
  • percentDeadband – Desired deadband percentage. Minimum is 0.1%, Maximum is 25%. Pass 0.04 for 4% (factory default).

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

configNominalOutputForward(percentOut: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the forward nominal output percentage.

Parameters:
  • percentOut – Nominal (minimum) percent output. [0,+1]

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

configNominalOutputReverse(percentOut: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the reverse nominal output percentage.

Parameters:
  • percentOut – Nominal (minimum) percent output. [-1,0]

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

configOpenloopRamp(secondsFromNeutralToFull: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the open-loop ramp rate of throttle output.

Parameters:
  • secondsFromNeutralToFull – Minimum desired time to go from neutral to full throttle. A value of ‘0’ will disable the ramp.

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

configPeakOutputForward(percentOut: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the forward peak output percentage.

Parameters:
  • percentOut – Desired peak output percentage. [0,1]

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

configPeakOutputReverse(percentOut: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the reverse peak output percentage.

Parameters:
  • percentOut – Desired peak output percentage.

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

configPulseWidthPeriod_EdgesPerRot(pulseWidthPeriod_EdgesPerRot: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the edges per rotation of a pulse width sensor. (This should be set for tachometer use).

Parameters:
  • pulseWidthPeriod_EdgesPerRot – edges per rotation

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

configPulseWidthPeriod_FilterWindowSz(pulseWidthPeriod_FilterWindowSz: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the number of samples to use in smoothing a pulse width sensor with a rolling average. Default is 1 (no smoothing).

Parameters:
  • pulseWidthPeriod_FilterWindowSz – samples for rolling avg

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

configRemoteFeedbackFilter(*args, **kwargs)

Overloaded function.

  1. configRemoteFeedbackFilter(self: phoenix5._ctre.IMotorController, deviceID: int, remoteSensorSource: phoenix5._ctre.RemoteSensorSource, remoteOrdinal: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X as a PID source for closed-loop features.

Parameters:
  • deviceID – The device ID of the remote sensor device.

  • remoteSensorSource – The remote sensor device and signal type to bind.

  • remoteOrdinal – 0 for configuring Remote Sensor 0, 1 for configuring Remote Sensor 1

  • 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. configRemoteFeedbackFilter(self: phoenix5._ctre.IMotorController, canCoderRef: phoenix5._ctre.sensors.CANCoder, remoteOrdinal: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X as a PID source for closed-loop features.

Parameters:
  • canCoderRef – CANCoder device reference to use.

  • remoteOrdinal – 0 for configuring Remote Sensor 0, 1 for configuring Remote Sensor 1

  • 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. configRemoteFeedbackFilter(self: phoenix5._ctre.IMotorController, talonRef: phoenix5._ctre.BaseTalon, remoteOrdinal: int, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1. After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X as a PID source for closed-loop features.

Parameters:
  • talonRef – Talon device reference to use.

  • remoteOrdinal – 0 for configuring Remote Sensor 0, 1 for configuring Remote Sensor 1

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

configRemoteSensorClosedLoopDisableNeutralOnLOS(remoteSensorClosedLoopDisableNeutralOnLOS: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Disables going to neutral (brake/coast) when a remote sensor is no longer detected.

Parameters:
  • remoteSensorClosedLoopDisableNeutralOnLOS – disable going to neutral

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

configReverseSoftLimitEnable(enable: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the reverse soft limit enable.

Parameters:
  • enable – Reverse Sensor Position Limit Enable.

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

configReverseSoftLimitThreshold(reverseSensorLimit: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the reverse soft limit threshold.

Parameters:
  • reverseSensorLimit – Reverse Sensor Position Limit (in raw sensor units).

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

configSelectedFeedbackCoefficient(coefficient: float, pidIdx: int = 0, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

The Feedback Coefficient is a scalar applied to the value of the feedback sensor. Useful when you need to scale your sensor values within the closed-loop calculations. Default value is 1.

Selected Feedback Sensor register in firmware is the decoded sensor value multiplied by the Feedback Coefficient.

Parameters:
  • coefficient – Feedback Coefficient value. Maximum value of 1. * Resolution is 1/(2^16). Cannot be 0.

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

configSelectedFeedbackSensor(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.

configSensorTerm(sensorTerm: phoenix5._ctre.SensorTerm, feedbackDevice: phoenix5._ctre.FeedbackDevice, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Select what sensor term should be bound to switch feedback device. Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1 Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1 The four terms are specified with this routine. Then Sensor Sum/Difference can be selected for closed-looping.

Parameters:
  • sensorTerm – Which sensor term to bind to a feedback source.

  • feedbackDevice – The sensor signal to attach to sensorTerm.

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

configSetCustomParam(newValue: int, paramIndex: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the value of a custom parameter. This is for arbitrary use.

Sometimes it is necessary to save calibration/limit/target information in the device. Particularly if the device is part of a subsystem that can be replaced.

Parameters:
  • newValue – Value for custom parameter.

  • paramIndex – Index of custom parameter [0,1]

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

configSetParameter(param: phoenix5._ctre.ParamEnum, value: float, subValue: int, ordinal: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.

Parameters:
  • param – Parameter enumeration.

  • value – Value of parameter.

  • subValue – Subvalue for parameter. Maximum value of 255.

  • ordinal – Ordinal of parameter.

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

configSoftLimitDisableNeutralOnLOS(softLimitDisableNeutralOnLOS: bool, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Disables soft limits triggering (if enabled) when the sensor is no longer detected.

Parameters:
  • softLimitDisableNeutralOnLOS – disable triggering

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

configVoltageCompSaturation(voltage: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the Voltage Compensation saturation voltage.

Parameters:
  • voltage – This is the max voltage to apply to the hbridge when voltage compensation is enabled. For example, if 10 (volts) is specified and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc) then the TalonSRX will attempt to apply a duty-cycle to produce 5V.

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

configVoltageMeasurementFilter(filterWindowSamples: int, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configures the voltage measurement filter.

Parameters:
  • filterWindowSamples – Number of samples in the rolling average of voltage measurement.

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

config_IntegralZone(slotIdx: int, izone: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the Integral Zone constant in the given parameter slot. If the (absolute) closed-loop error is outside of this zone, integral accumulator is automatically cleared. This ensures than integral wind up events will stop after the sensor gets far enough from its target.

Parameters:
  • slotIdx – Parameter slot for the constant.

  • izone – Value of the Integral Zone constant (closed loop error units X 1ms).

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

config_kD(slotIdx: int, value: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the ‘D’ constant in the given parameter slot.

This is multiplied by derivative error (sensor units per PID loop, typically 1ms). Note the closed loop output interprets a final value of 1023 as full output. So use a gain of ‘250’ to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)

Parameters:
  • slotIdx – Parameter slot for the constant.

  • value – Value of the D constant.

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

config_kF(slotIdx: int, value: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the ‘F’ constant in the given parameter slot.

See documentation for calculation details. If using velocity, motion magic, or motion profile, use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).

Parameters:
  • slotIdx – Parameter slot for the constant.

  • value – Value of the F constant.

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

config_kI(slotIdx: int, value: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the ‘I’ constant in the given parameter slot. This is multiplied by accumulated closed loop error in sensor units every PID Loop. Note the closed loop output interprets a final value of 1023 as full output. So use a gain of ‘0.00025’ to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000), [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].

Parameters:
  • slotIdx – Parameter slot for the constant.

  • value – Value of the I constant.

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

config_kP(slotIdx: int, value: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the ‘P’ constant in the given parameter slot. This is multiplied by closed loop error in sensor units. Note the closed loop output interprets a final value of 1023 as full output. So use a gain of ‘0.25’ to get full output if err is 4096u (Mag Encoder 1 rotation)

Parameters:
  • slotIdx – Parameter slot for the constant.

  • value – Value of the P constant.

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

enableVoltageCompensation(enable: bool) None

Enables voltage compensation. If enabled, voltage compensation works in all control modes.

Be sure to configure the saturation voltage before enabling this.

Parameters:

enable – Enable state of voltage compensation.

getActiveTrajectoryArbFeedFwd(pidIdx: int = 0) float

Gets the active trajectory arbitrary feedforward using MotionMagic/MotionProfile control modes.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

The Active Trajectory ArbFeedFwd in units of percent output (where 0.01 is 1%).

getActiveTrajectoryPosition(pidIdx: int = 0) float

Gets the active trajectory target position for using MotionMagic/MotionProfile control modes.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

The Active Trajectory Position in sensor units.

getActiveTrajectoryVelocity(pidIdx: int = 0) float

Gets the active trajectory target velocity for using MotionMagic/MotionProfile control modes.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

The Active Trajectory Velocity in sensor units per 100ms.

getBaseID() int
Returns:

BaseID of device

getBusVoltage() float

Gets the bus voltage seen by the device.

Returns:

The bus voltage value (in volts).

getClosedLoopError(pidIdx: int = 0) float

Gets the closed-loop error. The units depend on which control mode is in use.

If closed-loop is seeking a target sensor position, closed-loop error is the difference between target and current sensor value (in sensor units. Example 4096 units per rotation for CTRE Mag Encoder).

If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target and current sensor value (in sensor units per 100ms).

If using motion profiling or Motion Magic, closed loop error is calculated against the current target, and not the “final” target at the end of the profile/movement.

See Phoenix-Documentation information on units.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

Closed-loop error value.

getClosedLoopTarget(pidIdx: int = 0) float

Gets the current target of a given closed loop.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

The closed loop target.

getControlMode() phoenix5._ctre.ControlMode
Returns:

control mode motor controller is in

getDeviceID() int

Returns the Device ID

Returns:

Device number.

getErrorDerivative(pidIdx: int = 0) float

Gets the derivative of the closed-loop error.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

The error derivative value.

getFaults(toFill: phoenix5._ctre.Faults) phoenix5._ctre.ErrorCode

Polls the various fault flags.

Parameters:

toFill – Caller’s object to fill with latest fault flags.

Returns:

Last Error Code generated by a function.

getFirmwareVersion() int

Gets the firmware version of the device.

Returns:

Firmware version of device. For example: version 1-dot-2 is 0x0102.

getIntegralAccumulator(pidIdx: int = 0) float

Gets the iaccum value.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

Integral accumulator value (Closed-loop error X 1ms).

getInverted() bool
Returns:

invert setting of motor output.

getLastError() phoenix5._ctre.ErrorCode

Gets the last error generated by this object. Not all functions return an error code but can potentially report errors. This function can be used to retrieve those error codes.

Returns:

Last Error Code generated by a function.

getMotionProfileStatus(statusToFill: phoenix5._ctre.MotionProfileStatus) phoenix5._ctre.ErrorCode

Retrieve all status information. For best performance, Caller can snapshot all status information regarding the motion profile executer.

The members are filled, as follows…

  • topBufferRem: The available empty slots in the trajectory buffer.

The robot API holds a “top buffer” of trajectory points, so your applicaion can dump several points at once. The API will then stream them into the low-level buffer, allowing the motor controller to act on them.

  • topBufferRem: The number of points in the top trajectory buffer.

  • btmBufferCnt: The number of points in the low level controller buffer.

  • hasUnderrun: Set if isUnderrun ever gets set.

Can be manually cleared by clearMotionProfileHasUnderrun() or automatically cleared by startMotionProfile().

  • isUnderrun: This is set if controller needs to shift a point from its buffer into

  • the active trajectory point however

  • the buffer is empty.

  • This gets cleared automatically when is resolved.

  • activePointValid: True if the active trajectory point is not empty, false otherwise. The members in activePoint are only valid if this signal is set.

  • isLast: is set/cleared based on the MP executer’s current

trajectory point’s IsLast value. This assumes IsLast was set when PushMotionProfileTrajectory was used to insert the currently processed trajectory point.

  • profileSlotSelect: The currently processed trajectory point’s

selected slot. This can differ in the currently selected slot used for Position and Velocity servo modes

  • outputEnable: The current output mode of the motion profile

  • executer (disabled, enabled, or hold). When changing the set()

  • value in MP mode, it’s important to check this signal to

  • confirm the change takes effect before interacting with the top buffer.

Parameters:

statusToFill – Caller supplied object to fill.

Returns:

Error Code generated by function. 0 indicates no error.

getMotionProfileTopLevelBufferCount() int

Retrieve just the buffer count for the api-level (top) buffer. This routine performs no CAN or data structure lookups, so its fast and ideal if caller needs to quickly poll the progress of trajectory points being emptied into controller’s RAM. Otherwise just use GetMotionProfileStatus.

Returns:

number of trajectory points in the top buffer.

getMotorOutputPercent() float

Gets the output percentage of the motor controller.

Returns:

Output of the motor controller (in percent).

getMotorOutputVoltage() float
Returns:

applied voltage to motor in volts.

getSelectedSensorPosition(pidIdx: int = 0) float

Get the selected sensor position (in raw sensor units).

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop. See Phoenix-Documentation for how to interpret.

Returns:

Position of selected sensor (in raw sensor units).

getSelectedSensorVelocity(pidIdx: int = 0) float

Get the selected sensor velocity.

Parameters:

pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

Returns:

selected sensor (in raw sensor units) per 100ms. See Phoenix-Documentation for how to interpret.

getStatusFramePeriod(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.

getStickyFaults(toFill: phoenix5._ctre.StickyFaults) phoenix5._ctre.ErrorCode

Polls the various sticky fault flags.

Parameters:

toFill – Caller’s object to fill with latest sticky fault flags.

Returns:

Last Error Code generated by a function.

getTemperature() float

Gets the temperature of the motor controller.

Returns:

Temperature of the motor controller (in ‘C)

hasResetOccurred() bool

Returns true if the device has reset since last call.

Returns:

Has a Device Reset Occurred?

isMotionProfileTopLevelBufferFull() bool

Retrieve just the buffer full for the api-level (top) buffer. This routine performs no CAN or data structure lookups, so its fast and ideal if caller needs to quickly poll. Otherwise just use GetMotionProfileStatus.

Returns:

number of trajectory points in the top buffer.

isVoltageCompensationEnabled() bool

Returns the enable state of Voltage Compensation that the caller has set.

Returns:

TRUE if voltage compensation is enabled.

neutralOutput() None

Neutral the motor output by setting control mode to disabled.

overrideLimitSwitchesEnable(enable: bool) None

Sets the enable state for limit switches.

Parameters:

enable – Enable state for limit switches.

overrideSoftLimitsEnable(enable: bool) None

Can be used to override-disable the soft limits. This function can be used to quickly disable soft limits without having to modify the persistent configuration.

Parameters:

enable – Enable state for soft limit switches.

processMotionProfileBuffer() None

This must be called periodically to funnel the trajectory points from the API’s top level buffer to the controller’s bottom level buffer. Recommendation is to call this twice as fast as the execution rate of the motion profile. So if MP is running with 20ms trajectory points, try calling this routine every 10ms. All motion profile functions are thread-safe through the use of a mutex, so there is no harm in having the caller utilize threading.

pushMotionProfileTrajectory(trajPt: phoenix5._ctre.TrajectoryPoint) phoenix5._ctre.ErrorCode

Push another trajectory point into the top level buffer (which is emptied into the motor controller’s bottom buffer as room allows).

targPos: servo position in sensor units. * targVel: velocity to feed-forward in sensor units per 100ms. profileSlotSelect0 Which slot to get PIDF gains. PID is used for position servo. F is used * as the Kv constant for velocity feed-forward. Typically this is hardcoded * to the a particular slot, but you are free gain schedule if need be. * Choose from [0,3] * profileSlotSelect1 Which slot to get PIDF gains for auxiliary PId. * This only has impact during MotionProfileArc Control mode. * Choose from [0,1]. isLastPoint set to nonzero to signal motor controller to keep processing this trajectory point, instead of jumping to the next one when timeDurMs expires. Otherwise MP executer will eventually see an empty buffer after the last point expires, causing it to assert the IsUnderRun flag. However this may be desired if calling application never wants to terminate the MP. * zeroPos set to nonzero to signal motor controller to “zero” the selected position sensor before executing this trajectory point. Typically the first point should have this set only thus allowing the remainder of the MP positions to be relative to zero. * timeDur Duration to apply this trajectory pt. This time unit is ADDED to the exising base time set by configMotionProfileTrajectoryPeriod().

Parameters:

trajPt – to push into buffer. The members should be filled in with these values…

Returns:

CTR_OKAY if trajectory point push ok. ErrorCode if buffer is full due to kMotionProfileTopBufferCapacity.

selectProfileSlot(slotIdx: int, pidIdx: int) phoenix5._ctre.ErrorCode

Selects which profile slot to use for closed-loop control.

Parameters:
  • slotIdx – Profile slot to select.

  • pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

set(*args, **kwargs)

Overloaded function.

  1. set(self: phoenix5._ctre.IMotorController, Mode: phoenix5._ctre.ControlMode, demand: float) -> None

Sets the appropriate output on the talon, depending on the mode.

  • Standard Driving Example:

  • _talonLeft.set(ControlMode.PercentOutput, leftJoy);

  • _talonRght.set(ControlMode.PercentOutput, rghtJoy);

Parameters:
  • Mode – The output mode to apply. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. In Follower mode, the output value is the integer device ID of the talon to duplicate.

  • demand – The setpoint value, as described above.

  1. set(self: phoenix5._ctre.IMotorController, mode: phoenix5._ctre.ControlMode, demand0: float, demand1Type: phoenix5._ctre.DemandType, demand1: float) -> None

Arcade Drive Example: * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn); * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);

  • Drive Straight Example:

  • Note: Selected Sensor Configuration is necessary for both PID0 and PID1.

  • _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);

  • _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);

  • Drive Straight to a Distance Example:

  • Note: Other configurations (sensor selection, PID gains, etc.) need to be set.

  • _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);

  • _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);

Parameters:
  • mode – Sets the appropriate output on the talon, depending on the mode.

  • demand0 – The output value to apply. such as advanced feed forward and/or auxiliary close-looping in firmware. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. See In Follower mode, the output value is the integer device ID of the talon to duplicate.

  • demand1Type – The demand type for demand1. Neutral: Ignore demand1 and apply no change to the demand0 output. AuxPID: Use demand1 to set the target for the auxiliary PID 1. ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the * demand0 output. In PercentOutput the demand0 output is the motor output, and in closed-loop modes the demand0 output is the output of PID0.

  • demand1 – Supplmental output value. Units match the set mode.

setControlFramePeriod(frame: phoenix5._ctre.ControlFrame, periodMs: int) phoenix5._ctre.ErrorCode

Sets the period of the given control frame.

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.

setIntegralAccumulator(iaccum: float, pidIdx: int = 0, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the integral accumulator. Typically this is used to clear/zero the integral accumulator, however some use cases may require seeding the accumulator for a faster response.

Parameters:
  • iaccum – Value to set for the integral accumulator (closed loop error units X 1ms).

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

setInverted(*args, **kwargs)

Overloaded function.

  1. setInverted(self: phoenix5._ctre.IMotorController, invert: bool) -> None

Inverts the hbridge output of the motor controller.

This does not impact sensor phase and should not be used to correct sensor polarity.

This will invert the hbridge output but NOT the LEDs. This ensures…. - Green LEDs always represents positive request from robot-controller/closed-looping mode. - Green LEDs correlates to forward limit switch. - Green LEDs correlates to forward soft limit.

Parameters:

invert – Invert state to set.

  1. setInverted(self: phoenix5._ctre.IMotorController, invertType: phoenix5._ctre.InvertType) -> None

Inverts the hbridge output of the motor controller in relation to the master if present

This does not impact sensor phase and should not be used to correct sensor polarity.

This will allow you to either: - Not invert the motor - Invert the motor - Always follow the master regardless of master’s inversion - Always oppose the master regardless of master’s inversion

Parameters:

invertType – Invert state to set.

setNeutralMode(neutralMode: phoenix5._ctre.NeutralMode) None

Sets the mode of operation during neutral throttle output.

Parameters:

neutralMode – The desired mode of operation when the Controller output throttle is neutral (ie brake/coast)

setSelectedSensorPosition(sensorPos: float, pidIdx: int = 0, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Sets the sensor position to the given value.

Parameters:
  • sensorPos – Position to set for the selected sensor (in raw sensor units).

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

setSensorPhase(PhaseSensor: bool) None

Sets the phase of the sensor. Use when controller forward/reverse output doesn’t correlate to appropriate forward/reverse reading of sensor. Pick a value so that positive PercentOutput yields a positive change in sensor. After setting this, user can freely call SetInverted() with any value.

Parameters:

PhaseSensor – Indicates whether to invert the phase of the sensor.

setStatusFramePeriod(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.