Package com.ctre.phoenix.motorcontrol
Interface IMotorControllerEnhanced
- All Superinterfaces:
IFollower
,IInvertable
,IMotorController
,IOutputSignal
- All Known Implementing Classes:
BaseTalon
,TalonFX
,TalonSRX
,WPI_TalonFX
,WPI_TalonSRX
public interface IMotorControllerEnhanced extends IMotorController
Interface for enhanced motor controllers
-
Method Summary
Modifier and Type Method Description ErrorCode
configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)
Configures the forward limit switch for a remote source.ErrorCode
configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)
Configures the reverse limit switch for a remote source.ErrorCode
configSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx, int timeoutMs)
Select the feedback device for the motor controller.ErrorCode
configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs)
Configures the supply (input) current limit.ErrorCode
configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs)
Deprecated.Use the overload with SensorVelocityMeasPeriod instead.ErrorCode
configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs)
Sets the period over which velocity measurements are taken.ErrorCode
configVelocityMeasurementWindow(int windowSize, int timeoutMs)
Sets the number of velocity samples used in the rolling average velocity measurement.double
getOutputCurrent()
Deprecated.Use getStatorCurrent/getSupplyCurrent instead.int
getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs)
Gets the period of the given status frame.ErrorCode
setStatusFramePeriod(StatusFrameEnhanced frame, int periodMs, int timeoutMs)
Sets the period of the given status frame.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
-
Method Details
-
configSelectedFeedbackSensor
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
Configures the supply (input) current limit.- Parameters:
currLimitCfg
- 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.
-
setStatusFramePeriod
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.
-
getStatusFramePeriod
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.
-
getOutputCurrent
Deprecated.Use getStatorCurrent/getSupplyCurrent instead.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.- Returns:
- The output current (in amps).
-
configVelocityMeasurementPeriod
Sets the period over which velocity measurements are taken.- Parameters:
period
- Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriodtimeoutMs
- 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
Deprecated.Use the overload with SensorVelocityMeasPeriod instead.Sets the period over which velocity measurements are taken.- Parameters:
period
- Desired period for the velocity measurement. @see com.ctre.phoenix.sensors.SensorVelocityMeasPeriodtimeoutMs
- 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
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.
-
configForwardLimitSwitchSource
ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)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
ErrorCode configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs)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.
-