Class Swerve

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.robot.subsystems.Swerve
All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj2.command.Subsystem

public class Swerve extends edu.wpi.first.wpilibj2.command.SubsystemBase
Manages the robot's swerve drive system, providing control over movement, autonomous path following, and odometry tracking. This subsystem handles both autonomous and teleoperated drive control, integrating with PathPlanner for advanced autonomous capabilities.

Features include:

  • Field-oriented drive control
  • Autonomous path following and path finding
  • Odometry tracking and pose estimation
  • Wheel locking for stability

Uses YAGSL (Yet Another Generic Swerve Library) for underlying swerve drive implementation and PathPlanner for autonomous navigation.

  • Constructor Summary

    Constructors
    Constructor
    Description
    Creates a new Swerve subsystem that manages drive control, path following, and odometry.
  • Method Summary

    Modifier and Type
    Method
    Description
    Supplier<edu.wpi.first.math.geometry.Rotation2d>
    Deprecated.
    Supplier<edu.wpi.first.math.geometry.Rotation2d>
    Creates a supplier that returns a Rotation2d pointing toward the closest POI with a specific tag.
    edu.wpi.first.wpilibj2.command.Command
    driveFieldOriented(Supplier<edu.wpi.first.math.kinematics.ChassisSpeeds> velocity)
    Creates a command to drive the robot in field-oriented mode.
    edu.wpi.first.wpilibj2.command.Command
    driveToPose(edu.wpi.first.math.geometry.Pose2d targetPose)
    Creates a command to autonomously drive the robot to a specific pose using PathPlanner.
    edu.wpi.first.math.geometry.Pose2d
    getClosestPOI(POI[] points)
    Finds the closest point from an array of field POIs to the robot's current position.
    edu.wpi.first.math.geometry.Pose2d
    getClosestPOIByTag(POI[] points, String tag)
    Finds the closest POI with a specific tag to the robot's current position.
    edu.wpi.first.math.geometry.Pose2d
    getClosestPoint(edu.wpi.first.math.geometry.Pose2d[] points)
    Finds the closest point from an array of positions to the robot's current position.
    edu.wpi.first.wpilibj.smartdashboard.Field2d
    Get the drivebase's field 2d object.
    static Swerve
    Returns the singleton instance of the Swerve subsystem.
    edu.wpi.first.math.geometry.Pose2d
    Retrieves the current estimated pose of the robot on the field.
    edu.wpi.first.math.kinematics.ChassisSpeeds
    Gets the current velocity of the robot.
    swervelib.SwerveDrive
    Gets the underlying SwerveDrive object.
    void
    Locks the swerve modules in an X pattern to prevent the robot from moving.
    void
    Resets the odometry if the robot has not received a global pose from the AprilTag system.
    void
    Resets the robot's odometry to the center of the field (8.774m, 4.026m), with rotation based on alliance (0° for blue, 180° for red).
    void
    resetOdometry(edu.wpi.first.math.geometry.Pose2d pose)
    Resets the robot's odometry to a specific pose.
    void
    Configures PathPlanner for autonomous path following.

    Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase

    addChild, getName, getSubsystem, initSendable, setName, setSubsystem

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait

    Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem

    defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
  • Constructor Details

    • Swerve

      public Swerve()
      Creates a new Swerve subsystem that manages drive control, path following, and odometry. Initializes the swerve drive with high telemetry verbosity and configures various drive parameters.
      Throws:
      RuntimeException - if swerve drive creation fails
  • Method Details

    • getInstance

      public static Swerve getInstance()
      Returns the singleton instance of the Swerve subsystem. Creates a new instance if one does not exist.
      Returns:
      the Swerve subsystem instance
    • setupPathPlanner

      public void setupPathPlanner()
      Configures PathPlanner for autonomous path following. Sets up the necessary callbacks and controllers for autonomous navigation, including pose estimation, odometry reset, and velocity control. Also initializes path finding warm-up for better initial performance.
    • driveFieldOriented

      public edu.wpi.first.wpilibj2.command.Command driveFieldOriented(Supplier<edu.wpi.first.math.kinematics.ChassisSpeeds> velocity)
      Creates a command to drive the robot in field-oriented mode.

      Example:

      
       Swerve.getInstance().driveFieldOriented(() -> new ChassisSpeeds(1.0, 0.0, 0.5));
       
      Parameters:
      velocity - a supplier that provides the desired chassis speeds in field-oriented coordinates
      Returns:
      a command that continuously updates drive output based on supplied velocities
      See Also:
      • ChassisSpeeds
    • lockWheels

      public void lockWheels()
      Locks the swerve modules in an X pattern to prevent the robot from moving. Useful for maintaining position or preparing for disable.

      Example:

      
       Swerve.getInstance().lockWheels();
       
    • resetOdometry

      public void resetOdometry()
      Resets the robot's odometry to the center of the field (8.774m, 4.026m), with rotation based on alliance (0° for blue, 180° for red). This is typically used at the start of autonomous routines.

      Example:

      
       Swerve.getInstance().resetOdometry();
       
    • getPose

      public edu.wpi.first.math.geometry.Pose2d getPose()
      Retrieves the current estimated pose of the robot on the field.

      Example:

      
       Pose2d currentPose = Swerve.getInstance().getPose();
       
      Returns:
      the current Pose2d representing the robot's position and rotation
    • resetOdometry

      public void resetOdometry(edu.wpi.first.math.geometry.Pose2d pose)
      Resets the robot's odometry to a specific pose.

      Example:

      
       Swerve.getInstance().resetOdometry(new Pose2d(new Translation2d(8.0, 4.0), Rotation2d.fromDegrees(90)));
       
      Parameters:
      pose - the Pose2d to set as the robot's current position and rotation
    • getRobotVelocity

      public edu.wpi.first.math.kinematics.ChassisSpeeds getRobotVelocity()
      Gets the current velocity of the robot.

      Example:

      
       ChassisSpeeds speeds = Swerve.getInstance().getRobotVelocity();
       
      Returns:
      the ChassisSpeeds representing the robot's current velocity
    • getSwerveDrive

      public swervelib.SwerveDrive getSwerveDrive()
      Gets the underlying SwerveDrive object.

      Example:

      
       SwerveDrive drive = Swerve.getInstance().getSwerveDrive();
       
      Returns:
      the SwerveDrive instance used by this subsystem
    • driveToPose

      public edu.wpi.first.wpilibj2.command.Command driveToPose(edu.wpi.first.math.geometry.Pose2d targetPose)
      Creates a command to autonomously drive the robot to a specific pose using PathPlanner.

      Example:

      
       Command autoDrive = Swerve.getInstance()
               .driveToPose(new Pose2d(new Translation2d(6.0, 3.0), Rotation2d.fromDegrees(45)));
       
      Parameters:
      targetPose - the target Pose2d to drive to
      Returns:
      a Command that will drive the robot to the specified pose
    • getClosestPoint

      public edu.wpi.first.math.geometry.Pose2d getClosestPoint(edu.wpi.first.math.geometry.Pose2d[] points)
      Finds the closest point from an array of positions to the robot's current position. Uses squared distance for optimization to avoid expensive square root operations.
      Parameters:
      points - Array of Pose2d positions to check
      Returns:
      The closest Pose2d from the array, or null if the array is empty
    • getClosestPOI

      public edu.wpi.first.math.geometry.Pose2d getClosestPOI(POI[] points)
      Finds the closest point from an array of field POIs to the robot's current position. Takes alliance into account and optimizes calculations for frequent calls.
      Parameters:
      points - Array of POI objects to check
      Returns:
      The Pose2d of the closest POI, or null if the array is empty
    • getClosestPOIByTag

      public edu.wpi.first.math.geometry.Pose2d getClosestPOIByTag(POI[] points, String tag)
      Finds the closest POI with a specific tag to the robot's current position. Highly optimized for frequent calls in control loops.
      Parameters:
      points - Array of POI objects to check
      tag - The tag to filter by, or null to check all POIs
      Returns:
      The Pose2d of the closest matching POI, or null if none found
    • createPointToClosestSupplier

      public Supplier<edu.wpi.first.math.geometry.Rotation2d> createPointToClosestSupplier(POI[] points, String tag)
      Creates a supplier that returns a Rotation2d pointing toward the closest POI with a specific tag.
      Parameters:
      points - Array of POIs to target
      tag - The tag to filter by, or null to consider all POIs
      Returns:
      A supplier that provides the rotation toward the closest matching POI when called
    • createPointToClosestSupplier

      @Deprecated public Supplier<edu.wpi.first.math.geometry.Rotation2d> createPointToClosestSupplier(POI[] points)
      Deprecated.
      For backward compatibility.
      Parameters:
      points - Array of POIs to target.
      Returns:
      A supplier that provides the rotation toward the closest matching POI when called.
    • getField2d

      public edu.wpi.first.wpilibj.smartdashboard.Field2d getField2d()
      Get the drivebase's field 2d object.
      Returns:
      the field 2d object
    • periodic

      public void periodic()
      Resets the odometry if the robot has not received a global pose from the AprilTag system.