Package swervelib
Class SwerveDriveTest
java.lang.Object
swervelib.SwerveDriveTest
Class to perform tests on the swerve drive.
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionstatic voidangleModules(SwerveDrive swerveDrive, Rotation2d moduleAngle) Set the angle of the modules to a givenRotation2dstatic voidcenterModules(SwerveDrive swerveDrive) Set the modules to center to 0.static SysIdRoutine.ConfigcreateConfigCustomTimeout(double timeout) Creates a SysIdRoutine.Config with a custom final timeoutstatic doublefindCouplingRatio(SwerveDrive swerveDrive, double volts, boolean automatic) Find the coupling ratio for all modules.static doublefindDriveMotorKV(SwerveDrive swerveDrive, double minMovement, double testDelaySeconds, double maxVolts) Find the minimum amount of power required to move the swerve drive motors.static CommandgenerateSysIdCommand(SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, double dynamicTimeout) Creates a command that can be mapped to a button or other trigger.static voidlogAngularMotorActivity(SwerveModule module, SysIdRoutineLog log, Supplier<Double> powerSupplied) Logs info about the angle motor to the SysIdRoutineLogstatic voidlogAngularMotorDutyCycle(SwerveModule module, SysIdRoutineLog log) Logs info about the angle motor to the SysIdRoutineLog.static voidlogAngularMotorVoltage(SwerveModule module, SysIdRoutineLog log) Logs info about the angle motor to the SysIdRoutineLogstatic voidlogDriveMotorActivity(SwerveModule module, SysIdRoutineLog log, Supplier<Double> powerSupplied) Logs power, position and velocuty info form the drive motor to the SysIdRoutineLogstatic voidlogDriveMotorDutyCycle(SwerveModule module, SysIdRoutineLog log) Logs output, position and velocuty info form the drive motor to the SysIdRoutineLog
Although SysIdRoutine expects to be logging Voltage, this function logs in Duty-Cycle (percent output) because it results in correctly adjusted values in the analysis for use in this library.static voidlogDriveMotorVoltage(SwerveModule module, SysIdRoutineLog log) Logs voltage, position and velocuty info form the drive motor to the SysIdRoutineLogstatic voidpowerAngleMotorsDutyCycle(SwerveDrive swerveDrive, double percentage) Power the angle motors for the swerve drive to a set percentage.static voidpowerAngleMotorsVoltage(SwerveDrive swerveDrive, double volts) Power the angle motors for the swerve drive to a set voltage.static voidpowerDriveMotorsDutyCycle(SwerveDrive swerveDrive, double percentage) Power the drive motors for the swerve drive to a set duty cycle percentage.static voidpowerDriveMotorsVoltage(SwerveDrive swerveDrive, double volts) Power the drive motors for the swerve drive to a set voltage.static voidrunAngleMotorsCharacterizationOnSimModules(SwerveDrive swerveDrive, double volts) Set the sim modules to center to 0 and power them to drive in a voltage.static voidrunDriveMotorsCharacterizationOnSimModules(SwerveDrive swerveDrive, double volts, boolean testWithSpinning) Set the sim modules to center to 0 and power them to drive in a voltage.static SysIdRoutinesetAngleSysIdRoutine(SysIdRoutine.Config config, SubsystemBase swerveSubsystem, SwerveDrive swerveDrive) Sets up the SysId runner and logger for the angle motorsstatic SysIdRoutinesetDriveSysIdRoutine(SysIdRoutine.Config config, SubsystemBase swerveSubsystem, SwerveDrive swerveDrive, double maxVolts, boolean testWithSpinning) Sets up the SysId runner and logger for the drive motorsstatic voidsetModulesToRotaryPosition(SwerveDrive swerveDrive) Set the modules to their rotary position to allow running sysid and spinning the robot
-
Constructor Details
-
SwerveDriveTest
public SwerveDriveTest()
-
-
Method Details
-
angleModules
Set the angle of the modules to a givenRotation2d- Parameters:
swerveDrive-SwerveDriveto use.moduleAngle-Rotation2dto set every module to.
-
powerDriveMotorsDutyCycle
Power the drive motors for the swerve drive to a set duty cycle percentage.- Parameters:
swerveDrive-SwerveDriveto control.percentage- Duty cycle percentage of voltage to send to drive motors.
-
powerAngleMotorsDutyCycle
Power the angle motors for the swerve drive to a set percentage.- Parameters:
swerveDrive-SwerveDriveto control.percentage- DutyCycle percentage to send to angle motors.
-
powerDriveMotorsVoltage
Power the drive motors for the swerve drive to a set voltage.- Parameters:
swerveDrive-SwerveDriveto control.volts- Voltage to send to drive motors.
-
powerAngleMotorsVoltage
Power the angle motors for the swerve drive to a set voltage.- Parameters:
swerveDrive-SwerveDriveto control.volts- Voltage to send to angle motors.
-
centerModules
Set the modules to center to 0.- Parameters:
swerveDrive- Swerve Drive to control.
-
setModulesToRotaryPosition
Set the modules to their rotary position to allow running sysid and spinning the robot- Parameters:
swerveDrive- Swerve Drive to control.
-
runDriveMotorsCharacterizationOnSimModules
public static void runDriveMotorsCharacterizationOnSimModules(SwerveDrive swerveDrive, double volts, boolean testWithSpinning) Set the sim modules to center to 0 and power them to drive in a voltage. Calling this function in sim is equivalent to callingcenterModules(SwerveDrive)andpowerDriveMotorsVoltage(SwerveDrive, double)on a real robot.- Parameters:
swerveDrive-SwerveDriveto control.volts- Voltage to send to drive motors.testWithSpinning- - Whether to make the robot spin in place instead of driving in a straight line, true to make the robot spin, false to make the robot drive in straight line
-
runAngleMotorsCharacterizationOnSimModules
public static void runAngleMotorsCharacterizationOnSimModules(SwerveDrive swerveDrive, double volts) Set the sim modules to center to 0 and power them to drive in a voltage. Calling this function in sim is equivalent to callingcenterModules(SwerveDrive)andpowerDriveMotorsVoltage(SwerveDrive, double)on a real robot.- Parameters:
swerveDrive-SwerveDriveto control.volts- Voltage to send to angle motors.
-
findDriveMotorKV
public static double findDriveMotorKV(SwerveDrive swerveDrive, double minMovement, double testDelaySeconds, double maxVolts) Find the minimum amount of power required to move the swerve drive motors.- Parameters:
swerveDrive-SwerveDriveto control.minMovement- Minimum amount of movement to drive motors.testDelaySeconds- Time in seconds for the motor to move.maxVolts- The maximum voltage to send to drive motors.- Returns:
- minimum voltage required.
-
findCouplingRatio
Find the coupling ratio for all modules.- Parameters:
swerveDrive-SwerveDriveto operate with.volts- Voltage to send to angle motors to spin.automatic- Attempt to automatically spin the modules.- Returns:
- Average coupling ratio.
-
createConfigCustomTimeout
Creates a SysIdRoutine.Config with a custom final timeout- Parameters:
timeout- - the most a SysIdRoutine should run- Returns:
- A custom SysIdRoutine.Config
-
logDriveMotorDutyCycle
Logs output, position and velocuty info form the drive motor to the SysIdRoutineLog
Although SysIdRoutine expects to be logging Voltage, this function logs in Duty-Cycle (percent output) because it results in correctly adjusted values in the analysis for use in this library.- Parameters:
module- - the swerve module being loggedlog- - the logger
-
logDriveMotorVoltage
Logs voltage, position and velocuty info form the drive motor to the SysIdRoutineLog- Parameters:
module- - the swerve module being loggedlog- - the logger
-
logDriveMotorActivity
public static void logDriveMotorActivity(SwerveModule module, SysIdRoutineLog log, Supplier<Double> powerSupplied) Logs power, position and velocuty info form the drive motor to the SysIdRoutineLog- Parameters:
module- - the swerve module being loggedlog- - the loggerpowerSupplied- - a functional supplier of the power to be logged
-
setDriveSysIdRoutine
public static SysIdRoutine setDriveSysIdRoutine(SysIdRoutine.Config config, SubsystemBase swerveSubsystem, SwerveDrive swerveDrive, double maxVolts, boolean testWithSpinning) Sets up the SysId runner and logger for the drive motors- Parameters:
config- - The SysIdRoutine.Config to useswerveSubsystem- - the subsystem to add to requirementsswerveDrive- - the SwerveDrive from which to access motor infomaxVolts- - The maximum voltage that should be applied to the drive motors.testWithSpinning- - Whether to make the robot spin in place instead of driving in a straight line, true to make the robot spin, false to make the robot drive in straight line- Returns:
- A SysIdRoutine runner
-
logAngularMotorDutyCycle
Logs info about the angle motor to the SysIdRoutineLog.
Although SysIdRoutine expects to be logging Voltage, this function logs in Duty-Cycle (percent output) because it results in correctly adjusted values in the analysis for use in this library.- Parameters:
module- - the swerve module being loggedlog- - the logger
-
logAngularMotorVoltage
Logs info about the angle motor to the SysIdRoutineLog- Parameters:
module- - the swerve module being loggedlog- - the logger
-
logAngularMotorActivity
public static void logAngularMotorActivity(SwerveModule module, SysIdRoutineLog log, Supplier<Double> powerSupplied) Logs info about the angle motor to the SysIdRoutineLog- Parameters:
module- - the swerve module being loggedlog- - the loggerpowerSupplied- - a functional supplier of the power to be logged
-
setAngleSysIdRoutine
public static SysIdRoutine setAngleSysIdRoutine(SysIdRoutine.Config config, SubsystemBase swerveSubsystem, SwerveDrive swerveDrive) Sets up the SysId runner and logger for the angle motors- Parameters:
config- - The SysIdRoutine.Config to useswerveSubsystem- - the subsystem to add to requirementsswerveDrive- - the SwerveDrive from which to access motor info- Returns:
- A SysIdRoutineRunner
-
generateSysIdCommand
public static Command generateSysIdCommand(SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, double dynamicTimeout) Creates a command that can be mapped to a button or other trigger. Delays can be set to customize the length of each part of the SysId Routine- Parameters:
sysIdRoutine- - The Sys Id routine runnerdelay- - seconds between each portion to allow motors to spin down, etc...quasiTimeout- - seconds to run the Quasistatic routines, so robot doesn't get too fardynamicTimeout- - seconds to run the Dynamic routines, 2-3 secs should be enough- Returns:
- A command that can be mapped to a button or other trigger
-