TalonSRX

class wpilib.TalonSRX(channel)[source]

Bases: wpilib.SafePWM

Cross the Road Electronics (CTRE) Talon SRX Speed Controller via PWM

See also

See CANTalon for CAN control of Talon SRX.

Constructor for a TalonSRX connected via PWM.

Parameters:channel (int) – The PWM channel that the TalonSRX is attached to. 0-9 are on-board, 10-19 are on the MXP port.

Note

The TalonSRX uses the following bounds for PWM values. These values should work reasonably well for most controllers, but if users experience issues such as asymmetric behavior around the deadband or inability to saturate the controller in either direction, calibration is recommended. The calibration procedure can be found in the TalonSRX User Manual available from CTRE.

  • 2.004ms = full “forward”
  • 1.520ms = the “high end” of the deadband range
  • 1.500ms = center of the deadband range (off)
  • 1.480ms = the “low end” of the deadband range
  • 0.997ms = full “reverse”
get()[source]

Get the recently set value of the PWM.

Returns:The most recently set value for the PWM between -1.0 and 1.0.
Return type:float
pidWrite(output)[source]

Write out the PID value as seen in the PIDOutput base object.

Parameters:output (float) – Write out the PWM value as was found in the PIDController.
set(speed, syncGroup=0)[source]

Set the PWM value.

The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the FPGA.

Parameters:
  • speed (float) – The speed to set. Value should be between -1.0 and 1.0.
  • syncGroup – The update group to add this set() to, pending updateSyncGroup(). If 0, update immediately.