Class TalonSRX
java.lang.Object
com.ctre.phoenix.motorcontrol.can.BaseMotorController
com.ctre.phoenix.motorcontrol.can.BaseTalon
com.ctre.phoenix.motorcontrol.can.TalonSRX
- All Implemented Interfaces:
IFollower
,IMotorController
,IMotorControllerEnhanced
,IInvertable
,IOutputSignal
- Direct Known Subclasses:
WPI_TalonSRX
public class TalonSRX extends BaseTalon
CTRE Talon SRX Motor Controller when used on CAN Bus.
// Example usage of a TalonSRX motor controller
TalonSRX motor = new TalonSRX(0); // creates a new TalonSRX with ID 0
TalonSRXConfiguration config = new TalonSRXConfiguration();
config.peakCurrentLimit = 40; // the peak current, in amps
config.peakCurrentDuration = 1500; // the time at the peak current before the limit triggers, in ms
config.continuousCurrentLimit = 30; // the current to maintain if the peak limit is triggered
motor.configAllSettings(config); // apply the config settings; this selects the quadrature encoder
motor.set(TalonSRXControlMode.PercentOutput, 0.5); // runs the motor at 50% power
System.out.println(motor.getSelectedSensorPosition()); // prints the position of the selected sensor
System.out.println(motor.getSelectedSensorVelocity()); // prints the velocity recorded by the selected sensor
System.out.println(motor.getMotorOutputPercent()); // prints the percent output of the motor (0.5)
System.out.println(motor.getStatorCurrent()); // prints the output current of the motor
ErrorCode error = motor.getLastError(); // gets the last error generated by the motor controller
Faults faults = new Faults();
ErrorCode faultsError = motor.getFaults(faults); // fills faults with the current motor controller faults; returns the last error generated
motor.setStatusFramePeriod(StatusFrame.Status_2_Feedback0, 10); // changes the period of the Status 2 frame (getSelectedSensor*()) to 10ms
-
Field Summary
-
Constructor Summary
Constructors Constructor Description TalonSRX(int deviceNumber)
Constructor for TalonSRX object -
Method Summary
Modifier and Type Method Description ErrorCode
configAllSettings(TalonSRXConfiguration allConfigs)
Configures all persistent settings (overloaded so timeoutMs is 50 ms).ErrorCode
configAllSettings(TalonSRXConfiguration allConfigs, int timeoutMs)
Configures all persistent settings.ErrorCode
configContinuousCurrentLimit(int amps)
Configure the continuous allowable current-draw (when current limit is enabled).ErrorCode
configContinuousCurrentLimit(int amps, int timeoutMs)
Configure the continuous allowable current-draw (when current limit is enabled).ErrorCode
configPeakCurrentDuration(int milliseconds)
Configure the peak allowable duration (when current limit is enabled).ErrorCode
configPeakCurrentDuration(int milliseconds, int timeoutMs)
Configure the peak allowable duration (when current limit is enabled).ErrorCode
configPeakCurrentLimit(int amps)
Configure the peak allowable current (when current limit is enabled).ErrorCode
configPeakCurrentLimit(int amps, int timeoutMs)
Configure the peak allowable current (when current limit is enabled).ErrorCode
configSelectedFeedbackSensor(TalonSRXFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs)
Select the feedback device for the motor controller.ErrorCode
configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitConfigs)
Configures the supply (input) current limit.ErrorCode
configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitConfigs, int timeoutMs)
Configures the supply (input) current limit.protected ErrorCode
configurePID(TalonSRXPIDSetConfiguration pid)
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).protected ErrorCode
configurePID(TalonSRXPIDSetConfiguration pid, int pidIdx, int timeoutMs)
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).void
enableCurrentLimit(boolean enable)
Enable or disable Current Limit.void
getAllConfigs(TalonSRXConfiguration allConfigs)
Gets all persistant settings (overloaded so timeoutMs is 50 ms).void
getAllConfigs(TalonSRXConfiguration allConfigs, int timeoutMs)
Gets all persistant settings.void
getPIDConfigs(TalonSRXPIDSetConfiguration pid)
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).void
getPIDConfigs(TalonSRXPIDSetConfiguration pid, int pidIdx, int timeoutMs)
Gets all PID set persistant settings.SensorCollection
getSensorCollection()
TalonSRXSimCollection
getSimCollection()
void
set(TalonSRXControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.void
set(TalonSRXControlMode mode, double demand0, DemandType demand1Type, double demand1)
Methods inherited from class com.ctre.phoenix.motorcontrol.can.BaseTalon
configAllSettings, configAllSettings, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configurePID, configurePID, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementPeriod, configVelocityMeasurementWindow, configVelocityMeasurementWindow, getAllConfigs, getAllConfigs, getOutputCurrent, getPIDConfigs, getPIDConfigs, getStatorCurrent, getStatusFramePeriod, getStatusFramePeriod, getSupplyCurrent, getTalonFXSensorCollection, getTalonFXSimCollection, getTalonSRXSensorCollection, getTalonSRXSimCollection, isFwdLimitSwitchClosed, isRevLimitSwitchClosed, setStatusFramePeriod, setStatusFramePeriod
Methods inherited from class com.ctre.phoenix.motorcontrol.can.BaseMotorController
baseConfigAllSettings, baseConfigurePID, baseGetAllConfigs, baseGetPIDConfigs, changeMotionControlFramePeriod, clearMotionProfileHasUnderrun, clearMotionProfileHasUnderrun, clearMotionProfileTrajectories, clearStickyFaults, clearStickyFaults, config_IntegralZone, config_IntegralZone, config_kD, config_kD, config_kF, config_kF, config_kI, config_kI, config_kP, config_kP, configAllowableClosedloopError, configAllowableClosedloopError, configAuxPIDPolarity, configAuxPIDPolarity, configClearPositionOnLimitF, configClearPositionOnLimitR, configClearPositionOnQuadIdx, configClosedLoopPeakOutput, configClosedLoopPeakOutput, configClosedLoopPeriod, configClosedLoopPeriod, configClosedloopRamp, configClosedloopRamp, configFactoryDefault, configFactoryDefault, configFeedbackNotContinuous, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardLimitSwitchSource, configForwardSoftLimitEnable, configForwardSoftLimitEnable, configForwardSoftLimitThreshold, configForwardSoftLimitThreshold, configGetCustomParam, configGetCustomParam, configGetParameter, configGetParameter, configGetParameter, configGetParameter, configLimitSwitchDisableNeutralOnLOS, configMaxIntegralAccumulator, configMaxIntegralAccumulator, configMotionAcceleration, configMotionAcceleration, configMotionCruiseVelocity, configMotionCruiseVelocity, configMotionProfileTrajectoryInterpolationEnable, configMotionProfileTrajectoryInterpolationEnable, configMotionProfileTrajectoryPeriod, configMotionProfileTrajectoryPeriod, configMotionSCurveStrength, configMotionSCurveStrength, configNeutralDeadband, configNeutralDeadband, configNominalOutputForward, configNominalOutputForward, configNominalOutputReverse, configNominalOutputReverse, configOpenloopRamp, configOpenloopRamp, configPeakOutputForward, configPeakOutputForward, configPeakOutputReverse, configPeakOutputReverse, configPulseWidthPeriod_EdgesPerRot, configPulseWidthPeriod_FilterWindowSz, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteSensorClosedLoopDisableNeutralOnLOS, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configReverseLimitSwitchSource, configReverseSoftLimitEnable, configReverseSoftLimitEnable, configReverseSoftLimitThreshold, configReverseSoftLimitThreshold, configSelectedFeedbackCoefficient, configSelectedFeedbackCoefficient, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSelectedFeedbackSensor, configSensorTerm, configSensorTerm, configSensorTerm, configSensorTerm, configSetCustomParam, configSetCustomParam, configSetParameter, configSetParameter, configSetParameter, configSetParameter, configSoftLimitDisableNeutralOnLOS, configureFilter, configureFilter, configureFilter, configureSlot, configureSlot, configVoltageCompSaturation, configVoltageCompSaturation, configVoltageMeasurementFilter, configVoltageMeasurementFilter, DestroyObject, enableVoltageCompensation, follow, follow, getActiveTrajectoryArbFeedFwd, getActiveTrajectoryArbFeedFwd, getActiveTrajectoryPosition, getActiveTrajectoryPosition, getActiveTrajectoryVelocity, getActiveTrajectoryVelocity, getBaseID, getBusVoltage, getClosedLoopError, getClosedLoopError, getClosedLoopTarget, getClosedLoopTarget, getControlMode, getDeviceID, getErrorDerivative, getErrorDerivative, getFaults, getFilterConfigs, getFilterConfigs, getFirmwareVersion, getHandle, getIntegralAccumulator, getIntegralAccumulator, getInverted, getLastError, getMotionProfileStatus, getMotionProfileTopLevelBufferCount, getMotorOutputPercent, getMotorOutputVoltage, getSelectedSensorPosition, getSelectedSensorPosition, getSelectedSensorVelocity, getSelectedSensorVelocity, getSlotConfigs, getSlotConfigs, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStatusFramePeriod, getStickyFaults, getTemperature, getVictorSPXSimCollection, hasResetOccurred, isMotionProfileFinished, isMotionProfileTopLevelBufferFull, isVoltageCompensationEnabled, neutralOutput, overrideLimitSwitchesEnable, overrideSoftLimitsEnable, processMotionProfileBuffer, pushMotionProfileTrajectory, selectProfileSlot, set, set, setControlFramePeriod, setControlFramePeriod, setIntegralAccumulator, setIntegralAccumulator, setInverted, setInverted, setNeutralMode, setSelectedSensorPosition, setSelectedSensorPosition, setSensorPhase, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, startMotionProfile, valueUpdated
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
Methods inherited from interface com.ctre.phoenix.motorcontrol.IMotorController
changeMotionControlFramePeriod, clearMotionProfileHasUnderrun, clearMotionProfileTrajectories, clearStickyFaults, config_IntegralZone, config_kD, config_kF, config_kI, config_kP, configAllowableClosedloopError, configAuxPIDPolarity, configClosedLoopPeakOutput, configClosedLoopPeriod, configClosedloopRamp, configForwardLimitSwitchSource, configForwardSoftLimitEnable, configForwardSoftLimitThreshold, configGetCustomParam, configGetParameter, configGetParameter, configMaxIntegralAccumulator, configMotionAcceleration, configMotionCruiseVelocity, configMotionProfileTrajectoryPeriod, configMotionSCurveStrength, configNeutralDeadband, configNominalOutputForward, configNominalOutputReverse, configOpenloopRamp, configPeakOutputForward, configPeakOutputReverse, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configRemoteFeedbackFilter, configReverseLimitSwitchSource, configReverseSoftLimitEnable, configReverseSoftLimitThreshold, configSelectedFeedbackCoefficient, configSelectedFeedbackSensor, configSensorTerm, configSetCustomParam, configSetParameter, configSetParameter, configVoltageCompSaturation, configVoltageMeasurementFilter, enableVoltageCompensation, getActiveTrajectoryPosition, getActiveTrajectoryVelocity, getBaseID, getBusVoltage, getClosedLoopError, getClosedLoopTarget, getControlMode, getDeviceID, getErrorDerivative, getFaults, getFirmwareVersion, getIntegralAccumulator, getInverted, getLastError, getMotionProfileStatus, getMotionProfileTopLevelBufferCount, getMotorOutputPercent, getMotorOutputVoltage, getSelectedSensorPosition, getSelectedSensorVelocity, getStatusFramePeriod, getStickyFaults, getTemperature, hasResetOccurred, isMotionProfileTopLevelBufferFull, neutralOutput, overrideLimitSwitchesEnable, overrideSoftLimitsEnable, processMotionProfileBuffer, pushMotionProfileTrajectory, selectProfileSlot, set, set, setControlFramePeriod, setIntegralAccumulator, setInverted, setInverted, setNeutralMode, setSelectedSensorPosition, setSensorPhase, setStatusFramePeriod
Methods inherited from interface com.ctre.phoenix.motorcontrol.IMotorControllerEnhanced
configSelectedFeedbackSensor
-
Constructor Details
-
TalonSRX
Constructor for TalonSRX object- Parameters:
deviceNumber
- CAN Device ID of Device
-
-
Method Details
-
set
Sets the appropriate output on the talon, depending on the mode.- 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.value
- The setpoint value, as described above. Standard Driving Example: _talonLeft.set(ControlMode.PercentOutput, leftJoy); _talonRght.set(ControlMode.PercentOutput, rghtJoy);
-
set
- 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. Auxiliary PID is always executed as standard Position PID control. 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. AuxPID: Target position in Sensor Units ArbitraryFeedForward: Percent Output between -1.0 and 1.0 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);
-
getSensorCollection
- Returns:
- object that can get/set individual raw sensor values.
-
getSimCollection
- Returns:
- object that can get/set simulation inputs.
-
configSelectedFeedbackSensor
public ErrorCode configSelectedFeedbackSensor(TalonSRXFeedbackDevice feedbackDevice, int pidIdx, int timeoutMs)Select the feedback device for the motor controller.- Parameters:
feedbackDevice
- Talon SRX 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
public ErrorCode configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitConfigs, int timeoutMs)Configures the supply (input) current limit.- Specified by:
configSupplyCurrentLimit
in interfaceIMotorControllerEnhanced
- Overrides:
configSupplyCurrentLimit
in classBaseTalon
- Parameters:
currLimitConfigs
- Current limit configurationtimeoutMs
- 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
Configures the supply (input) current limit.- Parameters:
currLimitConfigs
- Current limit configuration- Returns:
- Error Code generated by function. 0 indicates no error.
-
configPeakCurrentLimit
Configure the peak allowable current (when current limit is enabled). Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX. Current limit is activated when current exceeds the peak limit for longer than the peak duration. Then software will limit to the continuous limit. This ensures current limiting while allowing for momentary excess current events. For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() and set the peak to zero: ConfigPeakCurrentLimit(0).- Parameters:
amps
- Amperes to limit.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.
-
configPeakCurrentLimit
Configure the peak allowable current (when current limit is enabled). Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX. Current limit is activated when current exceeds the peak limit for longer than the peak duration. Then software will limit to the continuous limit. This ensures current limiting while allowing for momentary excess current events. For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() and set the peak to zero: ConfigPeakCurrentLimit(0).- Parameters:
amps
- Amperes to limit.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configPeakCurrentDuration
Configure the peak allowable duration (when current limit is enabled). Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX. Current limit is activated when current exceeds the peak limit for longer than the peak duration. Then software will limit to the continuous limit. This ensures current limiting while allowing for momentary excess current events. For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() and set the peak to zero: ConfigPeakCurrentLimit(0).- Parameters:
milliseconds
- How long to allow current-draw past peak limit.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.
-
configPeakCurrentDuration
Configure the peak allowable duration (when current limit is enabled). Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX. Current limit is activated when current exceeds the peak limit for longer than the peak duration. Then software will limit to the continuous limit. This ensures current limiting while allowing for momentary excess current events. For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() and set the peak to zero: ConfigPeakCurrentLimit(0).- Parameters:
milliseconds
- How long to allow current-draw past peak limit.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configContinuousCurrentLimit
Configure the continuous allowable current-draw (when current limit is enabled). Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX. Current limit is activated when current exceeds the peak limit for longer than the peak duration. Then software will limit to the continuous limit. This ensures current limiting while allowing for momentary excess current events. For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() and set the peak to zero: ConfigPeakCurrentLimit(0).- Parameters:
amps
- Amperes to limit.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.
-
configContinuousCurrentLimit
Configure the continuous allowable current-draw (when current limit is enabled). Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX. Current limit is activated when current exceeds the peak limit for longer than the peak duration. Then software will limit to the continuous limit. This ensures current limiting while allowing for momentary excess current events. For simpler current-limiting (single threshold) use ConfigContinuousCurrentLimit() and set the peak to zero: ConfigPeakCurrentLimit(0).- Parameters:
amps
- Amperes to limit.- Returns:
- Error Code generated by function. 0 indicates no error.
-
enableCurrentLimit
Enable or disable Current Limit. Supply current limiting is also available via configSupplyCurrentLimit(), which is a common routine with Talon FX.- Parameters:
enable
- Enable state of current limit.- See Also:
configPeakCurrentLimit(int,int)
,configPeakCurrentDuration(int,int)
,configContinuousCurrentLimit(int,int)
-
configurePID
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settingspidIdx
- 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.
-
configurePID
Configures all PID set persistent settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getPIDConfigs
Gets all PID set persistant settings.- Parameters:
pid
- Object with all of the PID set persistant settingspidIdx
- 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.
-
getPIDConfigs
Gets all PID set persistant settings (overloaded so timeoutMs is 50 ms and pidIdx is 0).- Parameters:
pid
- Object with all of the PID set persistant settings
-
configAllSettings
Configures all persistent settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- 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.
-
configAllSettings
Configures all persistent settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getAllConfigs
Gets all persistant settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- 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.
-
getAllConfigs
Gets all persistant settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings
-