Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
refactor(swerve): Use subsystem command.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 28, 2024
1 parent 308a0ef commit 4acf4b5
Show file tree
Hide file tree
Showing 4 changed files with 33 additions and 102 deletions.
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.swerve;
package frc.lib;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ private void initializeTelemetry() {

/** Configures subsystem default commands. */
private void configureDefaultCommands() {
swerve.setDefaultCommand(swerve.driveWithController(driverController));
swerve.setDefaultCommand(swerve.teleopDrive(driverController));
}

/** Configures controller bindings. */
Expand Down
98 changes: 0 additions & 98 deletions src/main/java/frc/robot/swerve/DriveCommand.java

This file was deleted.

33 changes: 31 additions & 2 deletions src/main/java/frc/robot/swerve/Swerve.java
Original file line number Diff line number Diff line change
@@ -1,19 +1,25 @@
package frc.robot.swerve;

import java.util.function.Function;

import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.lib.DriveRequest;
import frc.lib.Subsystem;
import frc.lib.Telemetry;
import frc.lib.config.MotionProfileConfig;
import frc.lib.controller.SwerveModuleIO;
import frc.robot.RobotConstants;
import frc.robot.odometry.Odometry;

/** Swerve subsystem. */
public class Swerve extends Subsystem {
Expand Down Expand Up @@ -242,8 +248,31 @@ public Rotation2d maximumRotationVelocity() {
* @param controller the Xbox controller to use.
* @return a command that drives the swerve using an Xbox controller.
*/
public Command driveWithController(CommandXboxController controller) {
return new DriveCommand(controller);
public Command teleopDrive(CommandXboxController controller) {
final SlewRateLimiter xAccelerationLimiter = translationMotionProfileConfig.createAccelerationLimiter();
final SlewRateLimiter yAccelerationLimiter = translationMotionProfileConfig.createAccelerationLimiter();

final Function<Double, Double> rotationVelocityLimiter = rotationMotionProfileConfig.createVelocityClamper();

final Function<ChassisSpeeds, ChassisSpeeds> chassisSpeedsLimiter = chassisSpeeds -> {
return new ChassisSpeeds(
xAccelerationLimiter.calculate(chassisSpeeds.vxMetersPerSecond),
yAccelerationLimiter.calculate(chassisSpeeds.vyMetersPerSecond),
Units.rotationsToRadians(rotationVelocityLimiter.apply(Units.radiansToRotations(chassisSpeeds.omegaRadiansPerSecond)))
);
};

final Function<DriveRequest, ChassisSpeeds> chassisSpeedsGetter = request -> {
return ChassisSpeeds.fromFieldRelativeSpeeds(
request.translationAxis().getX() * translationMotionProfileConfig.maximumVelocity(),
request.translationAxis().getY() * translationMotionProfileConfig.maximumVelocity(),
request.rotationVelocityAxis() * Units.rotationsToRadians(rotationMotionProfileConfig.maximumVelocity()),
Odometry.getInstance().getDriverRelativeHeading());
};

return run(() -> {
setChassisSpeeds(chassisSpeedsLimiter.apply(chassisSpeedsGetter.apply(DriveRequest.fromController(controller))));
});
}

/**
Expand Down

0 comments on commit 4acf4b5

Please sign in to comment.