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

Commit

Permalink
refactor: Continue WIP.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 27, 2024
1 parent 1743b6a commit 0908617
Show file tree
Hide file tree
Showing 9 changed files with 110 additions and 93 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
public class RobotContainer {

/** Robot container singleton. */
public static RobotContainer instance = null;
private static RobotContainer instance = null;

/** Arm subsystem reference. */
private final Arm arm;
Expand Down Expand Up @@ -129,7 +129,7 @@ private void configureBindings() {
* @param side the side of the controller to rumble.
* @return a command that rumbles the controller.
*/
public Command rumble(RumbleType side) {
private Command rumble(RumbleType side) {
return Commands.startEnd(
() -> rumbleController.setRumble(side, 1), () -> rumbleController.setRumble(side, 0));
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/arm/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
/** Arm subsystem. */
public class Arm extends Subsystem {

/** Arm singleton. */
/** Arm subsystem singleton. */
private static Arm instance = null;

/** Shoulder controller config. */
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
/** Intake subsystem. */
public class Intake extends Subsystem {

/** Intake singleton. */
/** Intake subsystem singleton. */
private static Intake instance = null;

/** Front roller controller config. */
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/odometry/Odometry.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
/** Odometry subsystem. */
public class Odometry extends Subsystem {

/** Odometry singleton. */
/** Odometry subsystem singleton. */
private static Odometry instance = null;

/** Gyroscope. */
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
/** Shooter subsystem. */
public class Shooter extends Subsystem {

/** Shooter singleton. */
/** Shooter subsystem singleton. */
private static Shooter instance = null;

/** Flywheel controller config. */
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/superstructure/Superstructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
/** Superstructure subsystem. */
public class Superstructure extends Subsystem {

/** Superstructure singleton. */
/** Superstructure subsystem singleton. */
private static Superstructure instance = null;

/** Arm subsystem reference. */
Expand Down
39 changes: 18 additions & 21 deletions src/main/java/frc/robot/swerve/DriveCommand.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,6 @@
package frc.robot.swerve;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
Expand All @@ -11,29 +9,37 @@

/** Drives the swerve using driver input. */
public class DriveCommand extends Command {
/* Swerve subsystem. */
/** Swerve subsystem. */
private final Swerve swerve;
/* Odometry subsystem. */

/** Odometry subsystem. */
private final Odometry odometry;

/* Xbox controller used to get driver input. */
/** Controller used to get driver input. */
private final CommandXboxController driverController;

/** Previous requested chassis speed. */
private ChassisSpeeds previousChassisSpeeds;

/* Current and previous requests from the driver controller. */
/** Request from the driver controller. */
private DriveRequest request;

/**
* Initializes the drive command.
*
* @param driverController controller to use as input.
*/
public DriveCommand(CommandXboxController driverController) {
swerve = Swerve.getInstance();
odometry = Odometry.getInstance();

this.driverController = driverController;

addRequirements(swerve);

previousChassisSpeeds = new ChassisSpeeds();

this.driverController = driverController;
request = DriveRequest.fromController(driverController);
}

@Override
Expand All @@ -43,22 +49,13 @@ public void initialize() {}
public void execute() {
request = DriveRequest.fromController(driverController);

Translation2d translationVelocityMetersPerSecond =
request.translation().times(SwerveConstants.MAXIMUM_SPEED);

Rotation2d driverRelativeHeading = odometry.getDriverRelativeHeading();

Rotation2d omega = new Rotation2d();

omega = request.omega();

ChassisSpeeds chassisSpeeds =
final ChassisSpeeds chassisSpeeds =
clampChassisSpeeds(
ChassisSpeeds.fromFieldRelativeSpeeds(
translationVelocityMetersPerSecond.getX(),
translationVelocityMetersPerSecond.getY(),
omega.getRadians(),
driverRelativeHeading));
request.velocity().getX(),
request.velocity().getY(),
request.omega().getRadians(),
odometry.getDriverRelativeHeading()));

swerve.setChassisSpeeds(chassisSpeeds);

Expand Down
83 changes: 44 additions & 39 deletions src/main/java/frc/robot/swerve/DriveRequest.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,35 +5,52 @@
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;

/** Drive request. */
public record DriveRequest(
DriveRequest.TranslationMode translationMode,
DriveRequest.RotationMode rotationMode,
Translation2d translation,
Translation2d rotation) {
Translation2d translationAxis,
Translation2d rotationAxis) {

public enum TranslationMode {
/** Translation mode. */
private enum TranslationMode {
/** Field-centric driving. */
FIELD_CENTRIC,
/** Robot-centric driving. */
ROBOT_CENTRIC
}

public enum RotationMode {
/** Rotation mode. */
private enum RotationMode {
/** Drifting (no rotation requested). */
DRIFTING,
/** Spinning (velocity requested). */
SPINNING,
SNAPPING
/** Aligning (heading requested). */
ALIGNING
}

/**
* Returns true if no rotation is requested.
*
* @param heading the heading axis.
* @param aligning true if aligning is requested.
* @return
*/
private static boolean isDrifting(Translation2d heading, boolean aligning) {
if (aligning) {
final double kMinHeadingDisplacement = 0.7;

return heading.getNorm() < kMinHeadingDisplacement;
return heading.getNorm() < 0.7;
}

final double kOmegaDeadband = 0.1;

return Math.abs(heading.getY()) < kOmegaDeadband;
return Math.abs(heading.getY()) < 0.1;
}

/**
* Creates a new driver request from controller inputs.
*
* @param controller the input controller.
* @return a new driver request from controller inputs.
*/
public static DriveRequest fromController(CommandXboxController controller) {
boolean snipingRequested = Math.abs(controller.getLeftTriggerAxis()) > 0.5;
boolean aligningRequested = Math.abs(controller.getRightTriggerAxis()) > 0.5;
Expand All @@ -55,8 +72,7 @@ public static DriveRequest fromController(CommandXboxController controller) {

Translation2d translationVector = new Translation2d(translationMagnitude, translationDirection);

TranslationMode translationMode =
snipingRequested ? TranslationMode.ROBOT_CENTRIC : TranslationMode.FIELD_CENTRIC;
TranslationMode translationMode = TranslationMode.FIELD_CENTRIC;

Translation2d rotationVector =
new Translation2d(-controller.getRightY(), -controller.getRightX());
Expand All @@ -66,42 +82,31 @@ public static DriveRequest fromController(CommandXboxController controller) {
if (isDrifting(rotationVector, aligningRequested)) {
rotationMode = RotationMode.DRIFTING;
} else if (aligningRequested) {
rotationMode = RotationMode.SNAPPING;
rotationMode = RotationMode.ALIGNING;
} else {
rotationMode = RotationMode.SPINNING;
}

return new DriveRequest(translationMode, rotationMode, translationVector, rotationVector);
}

public static boolean startedDrifting(DriveRequest past, DriveRequest present) {
return past.rotationMode == RotationMode.SPINNING
&& present.rotationMode == RotationMode.DRIFTING;
}

public boolean isRobotCentric() {
return translationMode == TranslationMode.ROBOT_CENTRIC;
}

public boolean isSpinning() {
return rotationMode == RotationMode.SPINNING;
}

public boolean isSnapping() {
return rotationMode == RotationMode.SNAPPING;
}

public boolean isDrifting() {
return rotationMode == RotationMode.DRIFTING;
/**
* Returns the requested translation velocity in meters per second.
*
* @return the requested translation velocity in meters per second.
*/
public Translation2d velocity() {
return translationAxis.times(SwerveConstants.MAXIMUM_SPEED);
}

/**
* Returns the requested rotation velocity.
*
* @return the requested rotation velocity.
*/
public Rotation2d omega() {
if (Math.abs(this.rotation().getY()) < 0.1) return new Rotation2d();

return SwerveConstants.MAXIMUM_ROTATION_SPEED.times(this.rotation().getY());
}
if (Math.abs(rotationAxis.getY()) < 0.1) return new Rotation2d();

public Rotation2d driverHeading() {
return rotation().getAngle();
return SwerveConstants.MAXIMUM_ROTATION_SPEED.times(rotationAxis.getY());
}
}
Loading

0 comments on commit 0908617

Please sign in to comment.