Package swervelib.motors
Class TalonSRXSwerve
java.lang.Object
swervelib.motors.SwerveMotor
swervelib.motors.TalonSRXSwerve
- All Implemented Interfaces:
AutoCloseable
WPI_TalonSRX Swerve Motor.-
Field Summary
Fields inherited from class swervelib.motors.SwerveMotor
isDriveMotor, maximumRetries, simMotor -
Constructor Summary
ConstructorsConstructorDescriptionTalonSRXSwerve(int id, boolean isDriveMotor, DCMotor motorType) Construct the TalonSRX swerve motor given the ID.TalonSRXSwerve(WPI_TalonSRX motor, boolean isDriveMotor, DCMotor motorType) Constructor for TalonSRX swerve motor. -
Method Summary
Modifier and TypeMethodDescriptionvoidSave the configurations from flash to EEPROM.voidClear the sticky faults on the motor controller.voidclose()voidconfigureCANStatusFrames(int CANStatus1) Set the CAN status frames.voidconfigureCANStatusFrames(int CANStatus1, int CANStatus2, int CANStatus3, int CANStatus4, int CANStatus8, int CANStatus10, int CANStatus12, int CANStatus13, int CANStatus14, int CANStatus21, int CANStatusCurrent) Set the CAN status frames.voidconfigureIntegratedEncoder(double positionConversionFactor) Configure the integrated encoder for the swerve module.voidconfigurePIDF(PIDFConfig config) Configure the PIDF values for the closed loop controller.voidconfigurePIDWrapping(double minInput, double maxInput) Configure the PID wrapping for the position closed loop controller.doubleconvertToNativeSensorUnits(double setpoint, double position) Convert the setpoint into native sensor units.voidDisable PID Wrapping on the motor.voidConfigure the factory defaults.doubleGet the applied dutycycle output.getMotor()Get the motor object from the module.doubleGet the position of the integrated encoder.Get theDCMotorof the motor class.doubleGet the velocity of the integrated encoder.doubleGet the voltage output of the motor controller.voidset(double percentOutput) Set the percentage output.setAbsoluteEncoder(SwerveAbsoluteEncoder encoder) Set the absolute encoder to be a compatible absolute encoder.voidsetCurrentLimit(int currentLimit) Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation.voidsetInverted(boolean inverted) Set the motor to be inverted.voidsetLoopRampRate(double rampRate) Set the maximum rate the open/closed loop output can change by.voidsetMotorBrake(boolean isBrakeMode) Set the idle mode.voidsetPosition(double position) Set the integrated encoder position.voidsetReference(double setpoint, double feedforward) Set the closed loop PID controller reference point.voidsetReference(double setpoint, double feedforward, double position) Set the closed loop PID controller reference point.voidsetSelectedFeedbackDevice(FeedbackDevice feedbackDevice) Set the selected feedback device for the TalonSRX.voidsetVoltage(double voltage) Set the voltage of the motor.voidsetVoltageCompensation(double nominalVoltage) Set the voltage compensation for the swerve module motor.booleanQueries whether the absolute encoder is directly attached to the motor controller.
-
Constructor Details
-
TalonSRXSwerve
Constructor for TalonSRX swerve motor.- Parameters:
motor- Motor to use.isDriveMotor- Whether this motor is a drive motor.motorType-DCMotorwhich theWPI_TalonSRXis attached to.
-
TalonSRXSwerve
Construct the TalonSRX swerve motor given the ID.- Parameters:
id- ID of the TalonSRX on the canbus.isDriveMotor- Whether the motor is a drive or steering motor.motorType-DCMotorwhich theWPI_TalonSRXis attached to.
-
-
Method Details
-
close
public void close()- Specified by:
closein interfaceAutoCloseable- Specified by:
closein classSwerveMotor
-
factoryDefaults
public void factoryDefaults()Configure the factory defaults.- Specified by:
factoryDefaultsin classSwerveMotor
-
clearStickyFaults
public void clearStickyFaults()Clear the sticky faults on the motor controller.- Specified by:
clearStickyFaultsin classSwerveMotor
-
setAbsoluteEncoder
Set the absolute encoder to be a compatible absolute encoder.- Specified by:
setAbsoluteEncoderin classSwerveMotor- Parameters:
encoder- The encoder to use.- Returns:
- The
SwerveMotorfor single line configuration.
-
configureIntegratedEncoder
public void configureIntegratedEncoder(double positionConversionFactor) Configure the integrated encoder for the swerve module. Sets the conversion factors for position and velocity.- Specified by:
configureIntegratedEncoderin classSwerveMotor- Parameters:
positionConversionFactor- The conversion factor to apply for position.
Degrees:
360 / (angleGearRatio * encoderTicksPerRotation)
Meters:
(Math.PI * wheelDiameter) / (driveGearRatio * encoderTicksPerRotation)
-
configureCANStatusFrames
public void configureCANStatusFrames(int CANStatus1) Set the CAN status frames.- Parameters:
CANStatus1- Applied Motor Output, Fault Information, Limit Switch Information
-
configureCANStatusFrames
public void configureCANStatusFrames(int CANStatus1, int CANStatus2, int CANStatus3, int CANStatus4, int CANStatus8, int CANStatus10, int CANStatus12, int CANStatus13, int CANStatus14, int CANStatus21, int CANStatusCurrent) Set the CAN status frames.- Parameters:
CANStatus1- Applied Motor Output, Fault Information, Limit Switch InformationCANStatus2- Selected Sensor Position (PID 0), Selected Sensor Velocity (PID 0), Brushed Supply Current Measurement, Sticky Fault InformationCANStatus3- Quadrature InformationCANStatus4- Analog Input, Supply Battery Voltage, Controller TemperatureCANStatus8- Pulse Width InformationCANStatus10- Motion Profiling/Motion Magic InformationCANStatus12- Selected Sensor Position (Aux PID 1), Selected Sensor Velocity (Aux PID 1)CANStatus13- PID0 (Primary PID) InformationCANStatus14- PID1 (Auxiliary PID) InformationCANStatus21- Integrated Sensor Position (Talon FX), Integrated Sensor Velocity (Talon FX)CANStatusCurrent- Brushless Supply Current Measurement, Brushless Stator Current Measurement
-
configurePIDF
Configure the PIDF values for the closed loop controller. 0 is disabled or off.- Specified by:
configurePIDFin classSwerveMotor- Parameters:
config- Configuration class holding the PIDF values.
-
configurePIDWrapping
public void configurePIDWrapping(double minInput, double maxInput) Configure the PID wrapping for the position closed loop controller.- Specified by:
configurePIDWrappingin classSwerveMotor- Parameters:
minInput- Minimum PID input.maxInput- Maximum PID input.
-
disablePIDWrapping
public void disablePIDWrapping()Disable PID Wrapping on the motor.- Specified by:
disablePIDWrappingin classSwerveMotor
-
setMotorBrake
public void setMotorBrake(boolean isBrakeMode) Set the idle mode.- Specified by:
setMotorBrakein classSwerveMotor- Parameters:
isBrakeMode- Set the brake mode.
-
setInverted
public void setInverted(boolean inverted) Set the motor to be inverted.- Specified by:
setInvertedin classSwerveMotor- Parameters:
inverted- State of inversion.
-
burnFlash
public void burnFlash()Save the configurations from flash to EEPROM.- Specified by:
burnFlashin classSwerveMotor
-
set
public void set(double percentOutput) Set the percentage output.- Specified by:
setin classSwerveMotor- Parameters:
percentOutput- percent out for the motor controller.
-
convertToNativeSensorUnits
public double convertToNativeSensorUnits(double setpoint, double position) Convert the setpoint into native sensor units.- Parameters:
setpoint- Setpoint to mutate. In meters per second or degrees.position- Position in degrees, only used on angle motors.- Returns:
- Setpoint as native sensor units. Encoder ticks per 100ms, or Encoder tick.
-
setReference
public void setReference(double setpoint, double feedforward) Set the closed loop PID controller reference point.- Specified by:
setReferencein classSwerveMotor- Parameters:
setpoint- Setpoint in MPS or Angle in degrees.feedforward- Feedforward in volt-meter-per-second or kV.
-
setReference
public void setReference(double setpoint, double feedforward, double position) Set the closed loop PID controller reference point.- Specified by:
setReferencein classSwerveMotor- Parameters:
setpoint- Setpoint in meters per second or angle in degrees.feedforward- Feedforward in volt-meter-per-second or kV.position- Only used on the angle motor, the position of the motor in degrees.
-
getVoltage
public double getVoltage()Get the voltage output of the motor controller.- Specified by:
getVoltagein classSwerveMotor- Returns:
- Voltage output.
-
setVoltage
public void setVoltage(double voltage) Set the voltage of the motor.- Specified by:
setVoltagein classSwerveMotor- Parameters:
voltage- Voltage to set.
-
getAppliedOutput
public double getAppliedOutput()Get the applied dutycycle output.- Specified by:
getAppliedOutputin classSwerveMotor- Returns:
- Applied dutycycle output to the motor.
-
getVelocity
public double getVelocity()Get the velocity of the integrated encoder.- Specified by:
getVelocityin classSwerveMotor- Returns:
- velocity in Meters Per Second, or Degrees per Second.
-
getPosition
public double getPosition()Get the position of the integrated encoder.- Specified by:
getPositionin classSwerveMotor- Returns:
- Position in Meters or Degrees.
-
setPosition
public void setPosition(double position) Set the integrated encoder position.- Specified by:
setPositionin classSwerveMotor- Parameters:
position- Integrated encoder position. Should be angle in degrees or meters.
-
setVoltageCompensation
public void setVoltageCompensation(double nominalVoltage) Set the voltage compensation for the swerve module motor.- Specified by:
setVoltageCompensationin classSwerveMotor- Parameters:
nominalVoltage- Nominal voltage for operation to output to.
-
setCurrentLimit
public void setCurrentLimit(int currentLimit) Set the current limit for the swerve drive motor, remember this may cause jumping if used in conjunction with voltage compensation. This is useful to protect the motor from current spikes.- Specified by:
setCurrentLimitin classSwerveMotor- Parameters:
currentLimit- Current limit in AMPS at free speed.
-
setLoopRampRate
public void setLoopRampRate(double rampRate) Set the maximum rate the open/closed loop output can change by.- Specified by:
setLoopRampRatein classSwerveMotor- Parameters:
rampRate- Time in seconds to go from 0 to full throttle.
-
setSelectedFeedbackDevice
Set the selected feedback device for the TalonSRX.- Parameters:
feedbackDevice- Feedback device to select.
-
getMotor
Get the motor object from the module.- Specified by:
getMotorin classSwerveMotor- Returns:
- Motor object.
-
getSimMotor
Get theDCMotorof the motor class.- Specified by:
getSimMotorin classSwerveMotor- Returns:
DCMotorof this type.
-
usingExternalFeedbackSensor
public boolean usingExternalFeedbackSensor()Queries whether the absolute encoder is directly attached to the motor controller.- Specified by:
usingExternalFeedbackSensorin classSwerveMotor- Returns:
- connected absolute encoder state.
-