Skip to content

Commit

Permalink
Merge pull request #189 from frc937/gkc-constant-cleanup
Browse files Browse the repository at this point in the history
GKC Constants / Code Cleanup
  • Loading branch information
quackitsquinn authored May 13, 2024
2 parents 762eba4 + 17264d4 commit 13fe373
Show file tree
Hide file tree
Showing 12 changed files with 76 additions and 59 deletions.
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,39 @@ public static class Auto {

/** Time in seconds that we delay our taxi in the delayed taxi auto. */
public static final double TAXI_DELAY_TIME = 10.0;

/** Time in seconds that we wait for FireNoteRoutine to end. */
public static final double DUMP_NOTE_WAIT_TIME = 4.0;

/** Time in seconds that we wait for PickupFromCenter to end. */
public static final double PICKUP_CENTER_WAIT_TIME = 5.0;

/** Time in seconds that we wait for TaxiLongAuto to end. */
public static final double TAXI_LONG_WAIT_TIME = 2.0;

/** Constants for the DriveToAmpBlue auto */
public static class DriveToAmpBlue {
/** The time for the robot to drive left towards the amp. */
public static final double LEFT_WAIT_TIME = 1;

/** The time for the robot to drive forwards towards the amp. */
public static final double FORWARD_WAIT_TIME = 0.5;
}

/** Constants for the DriveToAmpRed auto */
public static class DriveToAmpRed {
/** The time for the robot to drive left towards the amp. */
public static final double LEFT_WAIT_TIME = 1;

/** The time for the robot to drive forwards towards the amp. */
public static final double FORWARD_WAIT_TIME = 0.5;
}

/** Constants for the auto that drives bot to center of field. */
public static class DriveToCenter {
/** The time for the robot to drive to the center. */
public static final double DRIVE_CENTER_WAIT_TIME = 5.0;
}
}

/** Constants for the Intake System */
Expand Down
17 changes: 17 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command;
Expand Down Expand Up @@ -64,6 +66,7 @@
import frc.robot.subsystems.mailbox.Mailbox;
import frc.robot.subsystems.mailbox.MailboxBelts;
import frc.robot.subsystems.mailbox.MailboxPneumatics;
import java.util.Optional;

/** Singleton class that contains all the robot's subsystems, commands, and button bindings. */
@SuppressWarnings("unused")
Expand Down Expand Up @@ -387,4 +390,18 @@ private void configureBindings() {
public Command getAutonomousCommand() {
return autoChooser.getSelected();
}

/**
* Returns true if the robot is on the red alliance. False otherwise.
*
* @return True if the robot is on the red alliance. False otherwise.
*/
public static boolean isRedAlliance() {
Optional<Alliance> alliance = DriverStation.getAlliance();
if (!alliance.isEmpty()) {
return alliance.get() == Alliance.Red;
} else {
return false;
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@

package frc.robot.commands;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.RobotContainer;
Expand Down Expand Up @@ -52,8 +51,7 @@ public void initialize() {
this.oldPipelineNumber = limelight.getLimelightPipeline();
limelight.setLimelightPipeline(seekingPipelineNumber);

var alliance = DriverStation.getAlliance();
if (alliance.isPresent() ? alliance.get() == DriverStation.Alliance.Red : false) {
if (RobotContainer.isRedAlliance()) {
this.rotationRadiansPerSecond = rotationRadiansPerSecond * -1;
}
}
Expand Down
8 changes: 3 additions & 5 deletions src/main/java/frc/robot/commands/auto/DriveToAmpBlue.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,17 @@
import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.commands.drive.DriveFieldOrientedHeadingSnapping;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
/** Auto that manually drives bot to blue amp. Made due to faulty limelight at comp. */
public class DriveToAmpBlue extends SequentialCommandGroup {

/** Creates a new DriveToAmpBlue. */
public DriveToAmpBlue() {
super(
new ParallelDeadlineGroup(
new WaitCommand(1),
new WaitCommand(Constants.Auto.DriveToAmpBlue.LEFT_WAIT_TIME),
new DriveFieldOrientedHeadingSnapping(
() -> 0.0,
() -> 0.0,
Expand All @@ -36,7 +34,7 @@ public DriveToAmpBlue() {
() -> true,
() -> false)),
new ParallelDeadlineGroup(
new WaitCommand(0.5),
new WaitCommand(Constants.Auto.DriveToAmpBlue.FORWARD_WAIT_TIME),
new DriveFieldOrientedHeadingSnapping(
() -> 0.0,
() -> 1.0,
Expand Down
10 changes: 4 additions & 6 deletions src/main/java/frc/robot/commands/auto/DriveToAmpRed.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,19 +14,17 @@
import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.commands.drive.DriveFieldOrientedHeadingSnapping;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
/** Auto that manually drives bot to red amp. Made due to faulty limelight at comp. */
public class DriveToAmpRed extends SequentialCommandGroup {

/** Creates a new DriveToAmpRed. */
public DriveToAmpRed() {
super(
new ParallelDeadlineGroup(
new WaitCommand(1),
new WaitCommand(Constants.Auto.DriveToAmpRed.LEFT_WAIT_TIME),
new DriveFieldOrientedHeadingSnapping(
() -> 0.0,
() -> 0.0,
Expand All @@ -36,14 +34,14 @@ public DriveToAmpRed() {
() -> false,
() -> true)),
new ParallelDeadlineGroup(
new WaitCommand(0.5),
new WaitCommand(Constants.Auto.DriveToAmpRed.FORWARD_WAIT_TIME),
new DriveFieldOrientedHeadingSnapping(
() -> 0.0,
() -> -1.0,
() -> 0.0,
() -> false,
() -> false,
() -> false,
() -> false))); /* TODO: CONSTANTS */
() -> false)));
}
}
8 changes: 2 additions & 6 deletions src/main/java/frc/robot/commands/auto/DriveToCenterAuto.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,20 +14,16 @@
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.commands.drive.DriveFieldOrientedHeadingSnapping;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
/** Auto that drives bot to center of field. */
public class DriveToCenterAuto extends ParallelCommandGroup {
/** Creates a new PickUpFromCenterAuto. */
public DriveToCenterAuto() {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
addCommands(
new ParallelDeadlineGroup(
new WaitCommand(5),
new WaitCommand(Constants.Auto.DriveToCenter.DRIVE_CENTER_WAIT_TIME),
new DriveFieldOrientedHeadingSnapping(
() -> 1.0,
() -> 0.0,
Expand Down
9 changes: 2 additions & 7 deletions src/main/java/frc/robot/commands/auto/DumpNote.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,18 +13,13 @@

import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.commands.mailbox.FireNoteRoutine;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
/** Auto that dumps the preloaded note in the robot after 4 seconds. */
public class DumpNote extends ParallelDeadlineGroup {
/** Creates a new DumpNote. */
public DumpNote() {
// Add the deadline command in the super() call. Add other commands using
// addCommands().
super(new WaitCommand(4), new FireNoteRoutine());
// addCommands(new FooCommand(), new BarCommand());
super(new WaitCommand(Constants.Auto.DUMP_NOTE_WAIT_TIME), new FireNoteRoutine());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -11,23 +11,18 @@

package frc.robot.commands.auto;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.RobotContainer;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
// One piece - the anime thing
/**
* Auto that manually drives to the amp and offloads the note. Made due to faulty limelight at comp.
*/
public class OnePieceAutoButItWorksISwear extends SequentialCommandGroup {
/** Creates a new OnePieceAutoButItWorksISwear. */
public OnePieceAutoButItWorksISwear() {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());
var alliance = DriverStation.getAlliance();
if (alliance.isPresent() ? alliance.get() == DriverStation.Alliance.Red : false) {

if (RobotContainer.isRedAlliance()) {
addCommands(new DriveToAmpRed(), new DumpNote());
} else {
addCommands(new DriveToAmpBlue(), new DumpNote());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,22 +14,19 @@
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.commands.RunIntake;
import frc.robot.commands.drive.DriveFieldOrientedHeadingSnapping;

// NOTE: Consider using this command inline, rather than writing a subclass. For more
// information, see:
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
/** Auto that drives the bot to a note and intakes it. */
public class PickUpFromCenterAuto extends ParallelCommandGroup {
/** Creates a new PickUpFromCenterAuto. */
public PickUpFromCenterAuto() {
// Add your commands in the addCommands() call, e.g.
// addCommands(new FooCommand(), new BarCommand());

addCommands(
new RunIntake(),
new ParallelDeadlineGroup(
new WaitCommand(5),
new WaitCommand(Constants.Auto.PICKUP_CENTER_WAIT_TIME),
new DriveFieldOrientedHeadingSnapping(
() -> 1.0,
() -> 0.0,
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/auto/TaxiLongAuto.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
public class TaxiLongAuto extends ParallelDeadlineGroup {
/** Creates a new TaxiAuto. */
public TaxiLongAuto() {
super(new WaitCommand(2));
super(new WaitCommand(Constants.Auto.TAXI_LONG_WAIT_TIME));
addCommands(
new DriveAutoRobotOriented(
new Translation2d(Constants.Auto.TAXI_AUTO_METERS_PER_SECOND, 0), 0));
Expand Down
16 changes: 5 additions & 11 deletions src/main/java/frc/robot/commands/lightstrip/EnabledLight.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,10 @@

package frc.robot.commands.lightstrip;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants;
import frc.robot.RobotContainer;
import frc.robot.subsystems.AddressableLightStrip;
import java.util.Optional;

/** Activates the light strip when the robot is enabled. */
public class EnabledLight extends Command {
Expand All @@ -32,16 +29,13 @@ public EnabledLight() {
// Called when the command is initially scheduled.
@Override
public void initialize() {
Optional<Alliance> alliance = DriverStation.getAlliance();
if (alliance.isPresent()) {
if (alliance.get() == Alliance.Red) {
robotLights.setStripColor(Constants.LightStrips.Colors.ENABLE_COLOR_RED_ALLIANCE);
} else {
robotLights.setStripColor(Constants.LightStrips.Colors.ENABLE_COLOR_BLUE_ALLIANCE);
}

if (RobotContainer.isRedAlliance()) {
robotLights.setStripColor(Constants.LightStrips.Colors.ENABLE_COLOR_RED_ALLIANCE);
} else {
robotLights.setStripColor(Constants.LightStrips.Colors.ENABLE_COLOR_NO_ALLIANCE);
robotLights.setStripColor(Constants.LightStrips.Colors.ENABLE_COLOR_BLUE_ALLIANCE);
}

robotLights.flush();
robotLights.startLights();
}
Expand Down
8 changes: 2 additions & 6 deletions src/main/java/frc/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,12 @@
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.networktables.GenericEntry;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.RobotContainer;
import java.io.File;
import java.io.IOException;
import swervelib.SwerveDrive;
Expand Down Expand Up @@ -79,11 +79,7 @@ public Drive() {
/* This will flip the path being followed to the red side of the field. */
/* THE ORIGIN WILL REMAIN ON THE BLUE SIDE */

var alliance = DriverStation.getAlliance();
if (alliance.isPresent()) {
return alliance.get() == DriverStation.Alliance.Red;
}
return false;
return RobotContainer.isRedAlliance();
},
this /* Reference to this subsystem to set requirements */);
}
Expand Down

0 comments on commit 13fe373

Please sign in to comment.