Class PWMTalonSRX
java.lang.Object
edu.wpi.first.wpilibj.MotorSafety
edu.wpi.first.wpilibj.motorcontrol.PWMMotorController
edu.wpi.first.wpilibj.motorcontrol.PWMTalonSRX
- All Implemented Interfaces:
Sendable
,MotorController
,SpeedController
,AutoCloseable
public class PWMTalonSRX extends PWMMotorController
Cross the Road Electronics (CTRE) Talon SRX Motor Controller with PWM control.
Note that 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"
-
Field Summary
-
Constructor Summary
Constructors Constructor Description PWMTalonSRX(int channel)
Constructor for a TalonSRX connected via PWM. -
Method Summary
Methods inherited from class edu.wpi.first.wpilibj.motorcontrol.PWMMotorController
close, disable, enableDeadbandElimination, get, getChannel, getDescription, getInverted, getPwmHandle, initSendable, set, setInverted, stopMotor
Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Constructor Details
-
PWMTalonSRX
Constructor for a TalonSRX connected via PWM.- Parameters:
channel
- The PWM channel that the Talon SRX is attached to. 0-9 are on-board, 10-19 are on the MXP port
-