Package swervelib

Class SwerveDriveTest

java.lang.Object
swervelib.SwerveDriveTest

public class SwerveDriveTest extends Object
Class to perform tests on the swerve drive.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Angle>
    Tracks the rotations of an angular motor
    private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Velocity<edu.wpi.first.units.Angle>>
    Tracks the velocity of an angular motor
    private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Voltage>
    Tracks the voltage being applied to a motor
    private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Distance>
    Tracks the distance travelled of a position motor
    private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Velocity<edu.wpi.first.units.Distance>>
    Tracks the velocity of a positional motor
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    static void
    angleModules(SwerveDrive swerveDrive, edu.wpi.first.math.geometry.Rotation2d moduleAngle)
    Set the angle of the modules to a given Rotation2d
    static void
    Set the modules to center to 0.
    static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config
    createConfigCustomTimeout(double timeout)
    Creates a SysIdRoutine.Config with a custom final timeout
    static double
    findCouplingRatio(SwerveDrive swerveDrive, double volts, boolean automatic)
    Find the coupling ratio for all modules.
    static double
    findDriveMotorKV(SwerveDrive swerveDrive, double minMovement, double testDelaySeconds, double maxVolts)
    Find the minimum amount of power required to move the swerve drive motors.
    static edu.wpi.first.wpilibj2.command.Command
    generateSysIdCommand(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine sysIdRoutine, double delay, double quasiTimeout, double dynamicTimeout)
    Creates a command that can be mapped to a button or other trigger.
    static void
    logAngularMotorActivity(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log, Supplier<Double> powerSupplied)
    Logs info about the angle motor to the SysIdRoutineLog
    static void
    logAngularMotorDutyCycle(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log)
    Logs info about the angle motor to the SysIdRoutineLog.
    static void
    logAngularMotorVoltage(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log)
    Logs info about the angle motor to the SysIdRoutineLog
    static void
    logDriveMotorActivity(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log, Supplier<Double> powerSupplied)
    Logs power, position and velocuty info form the drive motor to the SysIdRoutineLog
    static void
    logDriveMotorDutyCycle(SwerveModule module, edu.wpi.first.wpilibj.sysid.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 void
    logDriveMotorVoltage(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log)
    Logs voltage, position and velocuty info form the drive motor to the SysIdRoutineLog
    static void
    powerAngleMotorsDutyCycle(SwerveDrive swerveDrive, double percentage)
    Power the angle motors for the swerve drive to a set percentage.
    static void
    powerAngleMotorsVoltage(SwerveDrive swerveDrive, double volts)
    Power the angle motors for the swerve drive to a set voltage.
    static void
    powerDriveMotorsDutyCycle(SwerveDrive swerveDrive, double percentage)
    Power the drive motors for the swerve drive to a set duty cycle percentage.
    static void
    powerDriveMotorsVoltage(SwerveDrive swerveDrive, double volts)
    Power the drive motors for the swerve drive to a set voltage.
    static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine
    setAngleSysIdRoutine(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config config, edu.wpi.first.wpilibj2.command.SubsystemBase swerveSubsystem, SwerveDrive swerveDrive)
    Sets up the SysId runner and logger for the angle motors
    static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine
    setDriveSysIdRoutine(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config config, edu.wpi.first.wpilibj2.command.SubsystemBase swerveSubsystem, SwerveDrive swerveDrive, double maxVolts)
    Sets up the SysId runner and logger for the drive motors

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • m_appliedVoltage

      private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Voltage> m_appliedVoltage
      Tracks the voltage being applied to a motor
    • m_distance

      private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Distance> m_distance
      Tracks the distance travelled of a position motor
    • m_velocity

      private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Velocity<edu.wpi.first.units.Distance>> m_velocity
      Tracks the velocity of a positional motor
    • m_anglePosition

      private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Angle> m_anglePosition
      Tracks the rotations of an angular motor
    • m_angVelocity

      private static final edu.wpi.first.units.MutableMeasure<edu.wpi.first.units.Velocity<edu.wpi.first.units.Angle>> m_angVelocity
      Tracks the velocity of an angular motor
  • Constructor Details

    • SwerveDriveTest

      public SwerveDriveTest()
  • Method Details

    • angleModules

      public static void angleModules(SwerveDrive swerveDrive, edu.wpi.first.math.geometry.Rotation2d moduleAngle)
      Set the angle of the modules to a given Rotation2d
      Parameters:
      swerveDrive - SwerveDrive to use.
      moduleAngle - Rotation2d to set every module to.
    • powerDriveMotorsDutyCycle

      public static void powerDriveMotorsDutyCycle(SwerveDrive swerveDrive, double percentage)
      Power the drive motors for the swerve drive to a set duty cycle percentage.
      Parameters:
      swerveDrive - SwerveDrive to control.
      percentage - Duty cycle percentage of voltage to send to drive motors.
    • powerAngleMotorsDutyCycle

      public static void powerAngleMotorsDutyCycle(SwerveDrive swerveDrive, double percentage)
      Power the angle motors for the swerve drive to a set percentage.
      Parameters:
      swerveDrive - SwerveDrive to control.
      percentage - DutyCycle percentage to send to angle motors.
    • powerDriveMotorsVoltage

      public static void powerDriveMotorsVoltage(SwerveDrive swerveDrive, double volts)
      Power the drive motors for the swerve drive to a set voltage.
      Parameters:
      swerveDrive - SwerveDrive to control.
      volts - DutyCycle percentage of voltage to send to drive motors.
    • powerAngleMotorsVoltage

      public static void powerAngleMotorsVoltage(SwerveDrive swerveDrive, double volts)
      Power the angle motors for the swerve drive to a set voltage.
      Parameters:
      swerveDrive - SwerveDrive to control.
      volts - Voltage to send to angle motors.
    • centerModules

      public static void centerModules(SwerveDrive swerveDrive)
      Set the modules to center to 0.
      Parameters:
      swerveDrive - Swerve Drive to control.
    • 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 - SwerveDrive to 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

      public static double findCouplingRatio(SwerveDrive swerveDrive, double volts, boolean automatic)
      Find the coupling ratio for all modules.
      Parameters:
      swerveDrive - SwerveDrive to operate with.
      volts - Voltage to send to angle motors to spin.
      automatic - Attempt to automatically spin the modules.
      Returns:
      Average coupling ratio.
    • createConfigCustomTimeout

      public static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config createConfigCustomTimeout(double timeout)
      Creates a SysIdRoutine.Config with a custom final timeout
      Parameters:
      timeout - - the most a SysIdRoutine should run
      Returns:
      A custom SysIdRoutine.Config
    • logDriveMotorDutyCycle

      public static void logDriveMotorDutyCycle(SwerveModule module, edu.wpi.first.wpilibj.sysid.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.
      Parameters:
      module - - the swerve module being logged
      log - - the logger
    • logDriveMotorVoltage

      public static void logDriveMotorVoltage(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log)
      Logs voltage, position and velocuty info form the drive motor to the SysIdRoutineLog
      Parameters:
      module - - the swerve module being logged
      log - - the logger
    • logDriveMotorActivity

      public static void logDriveMotorActivity(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log, Supplier<Double> powerSupplied)
      Logs power, position and velocuty info form the drive motor to the SysIdRoutineLog
      Parameters:
      module - - the swerve module being logged
      log - - the logger
      powerSupplied - - a functional supplier of the power to be logged
    • setDriveSysIdRoutine

      public static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine setDriveSysIdRoutine(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config config, edu.wpi.first.wpilibj2.command.SubsystemBase swerveSubsystem, SwerveDrive swerveDrive, double maxVolts)
      Sets up the SysId runner and logger for the drive motors
      Parameters:
      config - - The SysIdRoutine.Config to use
      swerveSubsystem - - the subsystem to add to requirements
      swerveDrive - - the SwerveDrive from which to access motor info
      maxVolts - - The maximum voltage that should be applied to the drive motors.
      Returns:
      A SysIdRoutine runner
    • logAngularMotorDutyCycle

      public static void logAngularMotorDutyCycle(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log)
      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 logged
      log - - the logger
    • logAngularMotorVoltage

      public static void logAngularMotorVoltage(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log)
      Logs info about the angle motor to the SysIdRoutineLog
      Parameters:
      module - - the swerve module being logged
      log - - the logger
    • logAngularMotorActivity

      public static void logAngularMotorActivity(SwerveModule module, edu.wpi.first.wpilibj.sysid.SysIdRoutineLog log, Supplier<Double> powerSupplied)
      Logs info about the angle motor to the SysIdRoutineLog
      Parameters:
      module - - the swerve module being logged
      log - - the logger
      powerSupplied - - a functional supplier of the power to be logged
    • setAngleSysIdRoutine

      public static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine setAngleSysIdRoutine(edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Config config, edu.wpi.first.wpilibj2.command.SubsystemBase swerveSubsystem, SwerveDrive swerveDrive)
      Sets up the SysId runner and logger for the angle motors
      Parameters:
      config - - The SysIdRoutine.Config to use
      swerveSubsystem - - the subsystem to add to requirements
      swerveDrive - - the SwerveDrive from which to access motor info
      Returns:
      A SysIdRoutineRunner
    • generateSysIdCommand

      public static edu.wpi.first.wpilibj2.command.Command generateSysIdCommand(edu.wpi.first.wpilibj2.command.sysid.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 runner
      delay - - seconds between each portion to allow motors to spin down, etc...
      quasiTimeout - - seconds to run the Quasistatic routines, so robot doesn't get too far
      dynamicTimeout - - 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