Package frc.robot.systems.drive
Interface ModuleIO
- All Known Implementing Classes:
ModuleIOFXFXS,ModuleIOKraken,ModuleIOSim
public interface ModuleIO
-
Nested Class Summary
Nested Classes -
Method Summary
Modifier and TypeMethodDescriptiondefault voiddefault voidsetAzimuthPID(double kP, double kI, double kD) default voidsetAzimuthPosition(edu.wpi.first.math.geometry.Rotation2d rotation, double feedforward) default voidsetAzimuthVolts(double votls) default voidsetDriveAmperage(double amps) default voidsetDrivePID(double kP, double kI, double kD) default voidsetDriveVelocity(double velocityMPS, double feedforward) default voidsetDriveVolts(double volts) default voidupdateInputs(ModuleIO.ModuleInputs inputs)
-
Method Details
-
updateInputs
-
setDriveVelocity
default void setDriveVelocity(double velocityMPS, double feedforward) -
setDriveVolts
default void setDriveVolts(double volts) -
setDriveAmperage
default void setDriveAmperage(double amps) -
setDrivePID
default void setDrivePID(double kP, double kI, double kD) -
setAzimuthVolts
default void setAzimuthVolts(double votls) -
setAzimuthPosition
default void setAzimuthPosition(edu.wpi.first.math.geometry.Rotation2d rotation, double feedforward) -
resetAzimuthEncoder
default void resetAzimuthEncoder() -
setAzimuthPID
default void setAzimuthPID(double kP, double kI, double kD)
-