package frc.robot.subsystems; import static edu.wpi.first.units.Units.*; import java.util.function.Supplier; import com.ctre.phoenix6.SignalLogger; import com.ctre.phoenix6.Utils; import com.ctre.phoenix6.swerve.SwerveDrivetrainConstants; import com.ctre.phoenix6.swerve.SwerveModuleConstants; import com.ctre.phoenix6.swerve.SwerveRequest; import com.pathplanner.lib.auto.AutoBuilder; import com.pathplanner.lib.config.PIDConstants; import com.pathplanner.lib.config.RobotConfig; import com.pathplanner.lib.controllers.PPHolonomicDriveController; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.Notifier; import edu.wpi.first.wpilibj.RobotController; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Subsystem; import frc.robot.TunerConstants.TunerConstants.TunerSwerveDrivetrain; /** * Class that extends the Phoenix 6 SwerveDrivetrain class and implements * Subsystem so it can easily be used in command-based projeScts. */ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Subsystem { private static final double kSimLoopPeriod = 0.005; // 5 ms private Notifier m_simNotifier = null; private double m_lastSimTime; /* Blue alliance sees forward as 0 degrees (toward red alliance wall) */ private static final Rotation2d kBlueAlliancePerspectiveRotation = Rotation2d.kZero; /* Red alliance sees forward as 180 degrees (toward blue alliance wall) */ private static final Rotation2d kRedAlliancePerspectiveRotation = Rotation2d.k180deg; /* Keep track if we've ever applied the operator perspective before or not */ private boolean m_hasAppliedOperatorPerspective = false; private final SwerveRequest.ApplyRobotSpeeds m_pathApplyRobotSpeeds = new SwerveRequest.ApplyRobotSpeeds(); /* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */ private void configureAutoBuilder() { try { var config = RobotConfig.fromGUISettings(); AutoBuilder.configure( () -> getState().Pose, // Supplier of current robot pose this::resetPose, // Consumer for seeding pose against auto () -> getState().Speeds, // Supplier of current robot speeds // Consumer of ChassisSpeeds and feedforwards to drive the robot (speeds, feedforwards) -> setControl( m_pathApplyRobotSpeeds.withSpeeds(speeds) .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons()) .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons()) ), new PPHolonomicDriveController( // PID constants for translation new PIDConstants(63.167, 0, 0.54521), // PID constants for rotation new PIDConstants(7.9735, 0, 0.038499) ), config, // Assume the path needs to be flipped for Red vs Blue, this is normally the case () -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red, this // Subsystem for requirements ); } catch (Exception ex) { DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.getStackTrace()); } PPHolonomicDriveController.overrideRotationFeedback(()->{ return 0; }); } /** * Constructs a CTRE SwerveDrivetrain using the specified constants. *

* This constructs the underlying hardware devices, so users should not construct * the devices themselves. If they need the devices, they can access them through * getters in the classes. * * @param drivetrainConstants Drivetrain-wide constants for the swerve drive * @param modules Constants for each specific module */ public CommandSwerveDrivetrain( SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules ) { super(drivetrainConstants, modules); if (Utils.isSimulation()) { startSimThread(); } configureAutoBuilder(); } /** * Constructs a CTRE SwerveDrivetrain using the specified constants. *

* This constructs the underlying hardware devices, so users should not construct * the devices themselves. If they need the devices, they can access them through * getters in the classes. * * @param drivetrainConstants Drivetrain-wide constants for the swerve drive * @param odometryUpdateFrequency The frequency to run the odometry loop. If * unspecified or set to 0 Hz, this is 250 Hz on * CAN FD, and 100 Hz on CAN 2.0. * @param modules Constants for each specific module */ public CommandSwerveDrivetrain( SwerveDrivetrainConstants drivetrainConstants, double odometryUpdateFrequency, SwerveModuleConstants... modules ) { super(drivetrainConstants, odometryUpdateFrequency, modules); if (Utils.isSimulation()) { startSimThread(); } configureAutoBuilder(); } /** * Constructs a CTRE SwerveDrivetrain using the specified constants. *

* This constructs the underlying hardware devices, so users should not construct * the devices themselves. If they need the devices, they can access them through * getters in the classes. * * @param drivetrainConstants Drivetrain-wide constants for the swerve drive * @param odometryUpdateFrequency The frequency to run the odometry loop. If * unspecified or set to 0 Hz, this is 250 Hz on * CAN FD, and 100 Hz on CAN 2.0. * @param odometryStandardDeviation The standard deviation for odometry calculation * in the form [x, y, theta]ᵀ, with units in meters * and radians * @param visionStandardDeviation The standard deviation for vision calculation * in the form [x, y, theta]ᵀ, with units in meters * and radians * @param modules Constants for each specific module */ public CommandSwerveDrivetrain( SwerveDrivetrainConstants drivetrainConstants, double odometryUpdateFrequency, Matrix odometryStandardDeviation, Matrix visionStandardDeviation, SwerveModuleConstants... modules ) { super(drivetrainConstants, odometryUpdateFrequency, odometryStandardDeviation, visionStandardDeviation, modules); if (Utils.isSimulation()) { startSimThread(); } configureAutoBuilder(); } /** * Returns a command that applies the specified control request to this swerve drivetrain. * * @param request Function returning the request to apply * @return Command to run */ public Command applyRequest(Supplier requestSupplier) { return run(() -> this.setControl(requestSupplier.get())); } @Override public void periodic() { /* * Periodically try to apply the operator perspective. * If we haven't applied the operator perspective before, then we should apply it regardless of DS state. * This allows us to correct the perspective in case the robot code restarts mid-match. * Otherwise, only check and apply the operator perspective if the DS is disabled. * This ensures driving behavior doesn't change until an explicit disable event occurs during testing. */ if (!m_hasAppliedOperatorPerspective || DriverStation.isDisabled()) { DriverStation.getAlliance().ifPresent(allianceColor -> { setOperatorPerspectiveForward( allianceColor == Alliance.Red ? kRedAlliancePerspectiveRotation : kBlueAlliancePerspectiveRotation ); m_hasAppliedOperatorPerspective = true; }); } } private void startSimThread() { m_lastSimTime = Utils.getCurrentTimeSeconds(); /* Run simulation at a faster rate so PID gains behave more reasonably */ m_simNotifier = new Notifier(() -> { final double currentTime = Utils.getCurrentTimeSeconds(); double deltaTime = currentTime - m_lastSimTime; m_lastSimTime = currentTime; /* use the measured time delta, get battery voltage from WPILib */ updateSimState(deltaTime, RobotController.getBatteryVoltage()); }); m_simNotifier.startPeriodic(kSimLoopPeriod); } }