Package frc.lib5k.components.motors
Class TalonSRXCollection
- java.lang.Object
-
- edu.wpi.first.wpilibj.SpeedControllerGroup
-
- frc.lib5k.components.motors.TalonSRXCollection
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.PIDOutput,edu.wpi.first.wpilibj.Sendable,edu.wpi.first.wpilibj.SpeedController,ICurrentController,IMotorCollection,IMotorGroupSafety,IRampRateController,IVoltageOutputController,IEncoderProvider,Loggable,java.lang.AutoCloseable
public class TalonSRXCollection extends edu.wpi.first.wpilibj.SpeedControllerGroup implements IMotorCollection, ICurrentController, IEncoderProvider, IMotorGroupSafety, IVoltageOutputController, IRampRateController, Loggable
Collection of multiple WPI_TalonSRX controllers that wraps a SpeedControllerGroup
-
-
Constructor Summary
Constructors Constructor Description TalonSRXCollection(com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX master, com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX... slaves)
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description voidenableCurrentLimit(boolean on)Set if current limiting should be enabledvoidenableRampRateLimiting(boolean enabled)Set if ramp rate limiting should be enabled for the controllervoidforEachSlave(java.util.function.Consumer<com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX> consumer)For-Each over each slave controllerEncoderBasegetDefaultEncoder()Get the default encoderEncoderBasegetEncoder(int id, boolean phase)Get an encoder of a specific ID.doublegetEstimatedVoltage()Estimate controller output voltage from speedcom.ctre.phoenix.motorcontrol.can.WPI_TalonSRXgetMaster()Get the master TalonSRXdoublegetRampRate()Get the configured ramp ratevoidlogStatus()Log all component data with RobotLoggervoidpidWrite(double output)voidset(double speed)voidsetBuffer(double speed)Only set on new datavoidsetCompensation(boolean on)Set if voltage compensation should be enabledvoidsetCurrentLimit(int threshold, int duration, int hold, int timeout)Configure a current limitingvoidsetInverted(boolean isInverted)voidsetMasterMotorSafety(boolean enabled)Set the motorsafety mode of the master motor controllervoidsetNeutralMode(com.ctre.phoenix.motorcontrol.NeutralMode mode)voidsetRampRate(double secondsToFull)Set the controller ramp rate.voidsetVoltage(double volts)Set desired controller output in volts.voidupdateTelemetry()Push telemetry data to NetworkTables-
Methods inherited from class edu.wpi.first.wpilibj.SpeedControllerGroup
close, disable, get, getInverted, initSendable, stopMotor
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
-
-
-
Method Detail
-
set
public void set(double speed)
- Specified by:
setin interfaceedu.wpi.first.wpilibj.SpeedController- Overrides:
setin classedu.wpi.first.wpilibj.SpeedControllerGroup
-
setBuffer
public void setBuffer(double speed)
Description copied from interface:IMotorCollectionOnly set on new data- Specified by:
setBufferin interfaceIMotorCollection- Parameters:
speed- Motor speed
-
setInverted
public void setInverted(boolean isInverted)
- Specified by:
setInvertedin interfaceedu.wpi.first.wpilibj.SpeedController- Overrides:
setInvertedin classedu.wpi.first.wpilibj.SpeedControllerGroup
-
pidWrite
public void pidWrite(double output)
- Specified by:
pidWritein interfaceedu.wpi.first.wpilibj.PIDOutput- Overrides:
pidWritein classedu.wpi.first.wpilibj.SpeedControllerGroup
-
setVoltage
public void setVoltage(double volts)
Description copied from interface:IVoltageOutputControllerSet desired controller output in volts. Negative voltage will result in reverse output- Specified by:
setVoltagein interfaceIVoltageOutputController- Specified by:
setVoltagein interfaceedu.wpi.first.wpilibj.SpeedController- Parameters:
volts- Controller output
-
getEstimatedVoltage
public double getEstimatedVoltage()
Description copied from interface:IVoltageOutputControllerEstimate controller output voltage from speed- Specified by:
getEstimatedVoltagein interfaceIVoltageOutputController- Returns:
- Controller output voltage
-
setCurrentLimit
public void setCurrentLimit(int threshold, int duration, int hold, int timeout)Description copied from interface:ICurrentControllerConfigure a current limiting- Specified by:
setCurrentLimitin interfaceICurrentController- Parameters:
threshold- Threshold to trigger limitduration- How long the value must pass the threshold to be limitedhold- Amperage to hold the controller at while limitingtimeout- Timeout (can be 0)
-
enableCurrentLimit
public void enableCurrentLimit(boolean on)
Set if current limiting should be enabled- Specified by:
enableCurrentLimitin interfaceICurrentController- Parameters:
on- Should enable?
-
setCompensation
public void setCompensation(boolean on)
Set if voltage compensation should be enabled- Specified by:
setCompensationin interfaceICurrentController- Parameters:
on- Should enable?
-
setRampRate
public void setRampRate(double secondsToFull)
Description copied from interface:IRampRateControllerSet the controller ramp rate.- Specified by:
setRampRatein interfaceIRampRateController- Parameters:
secondsToFull- Minimum desired time to go from neutral to full output.
-
getRampRate
public double getRampRate()
Description copied from interface:IRampRateControllerGet the configured ramp rate- Specified by:
getRampRatein interfaceIRampRateController- Returns:
- Configured rate in seconds
-
enableRampRateLimiting
public void enableRampRateLimiting(boolean enabled)
Description copied from interface:IRampRateControllerSet if ramp rate limiting should be enabled for the controller- Specified by:
enableRampRateLimitingin interfaceIRampRateController- Parameters:
enabled- Should enable limiting?
-
setMasterMotorSafety
public void setMasterMotorSafety(boolean enabled)
Description copied from interface:IMotorGroupSafetySet the motorsafety mode of the master motor controller- Specified by:
setMasterMotorSafetyin interfaceIMotorGroupSafety- Parameters:
enabled- MotorSafety enabled
-
getMaster
public com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX getMaster()
Get the master TalonSRX- Returns:
- Master
-
forEachSlave
public void forEachSlave(java.util.function.Consumer<com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX> consumer)
For-Each over each slave controller- Parameters:
consumer- Method to run
-
getDefaultEncoder
public EncoderBase getDefaultEncoder()
Description copied from interface:IEncoderProviderGet the default encoder- Specified by:
getDefaultEncoderin interfaceIEncoderProvider- Returns:
- Default encoder
-
getEncoder
public EncoderBase getEncoder(int id, boolean phase)
Description copied from interface:IEncoderProviderGet an encoder of a specific ID. This is useful if a system has more than one sensor, or if it has more than one input, but only one sensor. If the system only has one sensor, this should probably just return getDefaultEncoder()- Specified by:
getEncoderin interfaceIEncoderProvider- Parameters:
id- Encoder ID- Returns:
- Encoder
-
setNeutralMode
public void setNeutralMode(com.ctre.phoenix.motorcontrol.NeutralMode mode)
-
logStatus
public void logStatus()
Log all component data with RobotLogger
-
updateTelemetry
public void updateTelemetry()
Description copied from interface:LoggablePush telemetry data to NetworkTables- Specified by:
updateTelemetryin interfaceLoggable
-
-