Skip to content

Commit

Permalink
Allow drop sequence, motor sequence to take BaseDrivetrain
Browse files Browse the repository at this point in the history
Drop sequences should be able to take `BaseDrivetrain` anyways (since all they need is to back up), but the command sequence is only able to do so if swerve testing remains permanently removed from the sequence.
  • Loading branch information
ky28059 committed Mar 8, 2023
1 parent c567d63 commit 35a3c2d
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 36 deletions.
19 changes: 4 additions & 15 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -122,15 +122,7 @@ public RobotContainer() {
superstructure = new Superstructure(rollerSubsystem, tiltedElevatorSubsystem, signalLEDSubsystem, switchableCamera);

balancerCommand = new DefaultBalancerCommand(driveSubsystem);
if (driveSubsystem instanceof BaseSwerveSubsystem) {
testCommand = new MotorTestCommand(
(BaseSwerveSubsystem) driveSubsystem,
tiltedElevatorSubsystem,
rollerSubsystem
);
} else {
testCommand = null;
}
testCommand = new MotorTestCommand(driveSubsystem, tiltedElevatorSubsystem, rollerSubsystem);

// Configure button bindings
configureDriveBindings();
Expand Down Expand Up @@ -161,8 +153,8 @@ public RobotContainer() {
// autonChooser.addOption("Blue bottom auton (2-piece)", new BottomTwoPieceAutonSequence(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem, false));
// autonChooser.addOption("Blue bottom balance auton", new BottomBalanceAutonSequence(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem, false));

// autonChooser.addOption("10\" straight-line path", new TenFeetStraightLinePath(swerveSubsystem));
// autonChooser.addOption("20\" straight-line path", new TwentyFeetStraightLinePath(swerveSubsystem));
// autonChooser.addOption("10' straight-line path", new TenFeetStraightLinePath(swerveSubsystem));
// autonChooser.addOption("20' straight-line path", new TwentyFeetStraightLinePath(swerveSubsystem));
// autonChooser.addOption("High rotation straight-line path", new HighRotationLinePath(swerveSubsystem));
// autonChooser.addOption("Rotating S-curve", new RotatingSCurveAutonSequence(swerveSubsystem));
// autonChooser.addOption("Box auton", new BoxAutonSequence(swerveSubsystem));
Expand Down Expand Up @@ -234,10 +226,7 @@ private void configureDriveBindings() {
* Configures button bindings for the roller / elevator mechs and controller.
*/
private void configureMechBindings() {
if (driveSubsystem instanceof BaseSwerveSubsystem) {
BaseSwerveSubsystem swerveSubsystem = (BaseSwerveSubsystem) driveSubsystem;
mechAButton.onTrue(new DropperChooserCommand(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem));
}
mechAButton.onTrue(new DropperChooserCommand(driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem));

rollerSubsystem.setDefaultCommand(new RunCommand(() -> {
double forwardPower = 0.95 * mechController.getRightTriggerAxis();
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/commands/dropping/DropSequence.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
import frc.robot.commands.grabber.RollerPlaceCommand;
import frc.robot.commands.mover.TiltedElevatorCommand;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.drivetrain.BaseDrivetrain;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState.OffsetState;
Expand All @@ -24,19 +24,19 @@ public class DropSequence extends SequentialCommandGroup {
* 7. Moves to GROUND
*/
public DropSequence(
BaseSwerveSubsystem swerveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem,
BaseDrivetrain driveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem,
double waitAfterAtDropHeight, double outtakePower, double outtakeDuration, double waitAfterPlacing, double backTime
) {
addRequirements(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem);
addRequirements(driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem);

addCommands(
new TiltedElevatorCommand(tiltedElevatorSubsystem, OffsetState.DROPPING),
new WaitCommand(waitAfterAtDropHeight),
new RollerPlaceCommand(rollerSubsystem, -outtakePower, outtakeDuration),
new WaitCommand(waitAfterPlacing),
new InstantCommand(() -> swerveSubsystem.setDrivePowers(-0.2, 0, 0, true)),
new InstantCommand(() -> driveSubsystem.setDrivePowers(-0.2)),
new WaitCommand(backTime),
new InstantCommand(() -> swerveSubsystem.setDrivePowers(0, 0, 0, true)),
new InstantCommand(() -> driveSubsystem.setDrivePowers(0)),
new InstantCommand(() -> tiltedElevatorSubsystem.setState(ElevatorState.GROUND))
);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,17 @@
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;

import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.drivetrain.BaseDrivetrain;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;

public class DropperChooserCommand extends InstantCommand {
public DropperChooserCommand(
BaseSwerveSubsystem swerveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem
BaseDrivetrain driveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem
) {
super(() -> {
getSequence(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem).schedule();
}, rollerSubsystem, tiltedElevatorSubsystem, swerveSubsystem);
getSequence(driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem).schedule();
}, rollerSubsystem, tiltedElevatorSubsystem, driveSubsystem);
}

/**
Expand All @@ -24,10 +24,10 @@ public DropperChooserCommand(
* @return The `SequentialCommandGroup` representing dropping the piece as a sequence.
*/
public static SequentialCommandGroup getSequence(
BaseSwerveSubsystem swerveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem
BaseDrivetrain driveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem
) {
ElevatorState state = tiltedElevatorSubsystem.getState();
return getSequence(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem, state);
return getSequence(driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem, state);
}

/**
Expand All @@ -38,32 +38,32 @@ public static SequentialCommandGroup getSequence(
* @return The `SequentialCommandGroup` representing dropping the piece as a sequence.
*/
public static SequentialCommandGroup getSequence(
BaseSwerveSubsystem swerveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem,
BaseDrivetrain driveSubsystem, RollerSubsystem rollerSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem,
ElevatorState state
) {
return switch (state) {
case CONE_HIGH -> new DropSequence(
swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
0, 0, 0, 0.2, 0.5
);

case CONE_MID -> new DropSequence(
swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
0, 0, 0, 0.2, 0.5
);

case CUBE_HIGH -> new DropSequence(
swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
0, 0.2, 0.5, 0.2, 0.5
);

case CUBE_MID -> new DropSequence(
swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
0, 0.2, 0.5, 0.2, 0.5
);

default -> new DropSequence(
swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem,
0, 0, 0, 0, 0.5
);
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import frc.robot.commands.grabber.RollerIntakeCommand;
import frc.robot.commands.mover.TiltedElevatorCommand;
import frc.robot.subsystems.RollerSubsystem;
import frc.robot.subsystems.drivetrain.BaseDrivetrain;
import frc.robot.subsystems.drivetrain.BaseSwerveSubsystem;
import frc.robot.subsystems.tiltedelevator.ElevatorState;
import frc.robot.subsystems.tiltedelevator.TiltedElevatorSubsystem;
Expand All @@ -19,12 +20,12 @@ public class MotorTestCommand extends SequentialCommandGroup {
private static final double SWERVE_DRIVE_POWER = 0.5;
private static final double SWERVE_DRIVE_TIME_SECS = 3;

public MotorTestCommand(BaseSwerveSubsystem swerveSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem, RollerSubsystem rollerSubsystem) {
addRequirements(swerveSubsystem, tiltedElevatorSubsystem, rollerSubsystem);
public MotorTestCommand(BaseDrivetrain driveSubsystem, TiltedElevatorSubsystem tiltedElevatorSubsystem, RollerSubsystem rollerSubsystem) {
addRequirements(driveSubsystem, tiltedElevatorSubsystem, rollerSubsystem);

addCommands(
// Lock swerve
new InstantCommand(swerveSubsystem::applyLock, swerveSubsystem),
// new InstantCommand(swerveSubsystem::applyLock, swerveSubsystem),

// Run tilted elevator to all heights
// GROUND - CHUTE - INTAKE CONE - SUBSTATION - CUBEMID - CUBEHIGH - CONEMID - CONEHIGH - CONEMID
Expand Down Expand Up @@ -57,7 +58,7 @@ public MotorTestCommand(BaseSwerveSubsystem swerveSubsystem, TiltedElevatorSubsy
new WaitCommand(TEST_DELAY_SECS),

// Test dropper command from `CONE_MID`
DropperChooserCommand.getSequence(swerveSubsystem, rollerSubsystem, tiltedElevatorSubsystem),
DropperChooserCommand.getSequence(driveSubsystem, rollerSubsystem, tiltedElevatorSubsystem),
new WaitCommand(MECH_DELAY_SECS)

// // Sweep rollers from [-1.0, 1.0] over 2 seconds
Expand Down

0 comments on commit 35a3c2d

Please sign in to comment.