Skip to content

Commit

Permalink
fixed comments (arun doing from yang fans computer, rachit is the goat)
Browse files Browse the repository at this point in the history
  • Loading branch information
aahFancyGun committed Mar 22, 2024
1 parent 8ba3a81 commit 7707730
Showing 1 changed file with 124 additions and 124 deletions.
248 changes: 124 additions & 124 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,20 +46,20 @@ public class RobotContainer {
Constants.Drive.DRIVE_LOOKAHEAD
);

// private static final ShooterSubsystem SHOOTER_SUBSYSTEM = new ShooterSubsystem(
// ShooterSubsystem.initializeHardware(),
// Constants.Shooter.FLYWHEEL_CONFIG,
// Constants.Shooter.ANGLE_CONFIG,
// Constants.Shooter.ANGLE_MOTION_CONSTRAINT,
// Constants.Shooter.FLYWHEEL_DIAMETER,
// Constants.Shooter.SHOOTER_MAP,
// DRIVE_SUBSYSTEM::getPose,
// () -> speakerSupplier()
// );
// private static final IntakeSubsystem INTAKE_SUBSYSTEM = new IntakeSubsystem(
// IntakeSubsystem.initializeHardware(),
// Constants.Intake.ROLLER_VELOCITY
// );
private static final ShooterSubsystem SHOOTER_SUBSYSTEM = new ShooterSubsystem(
ShooterSubsystem.initializeHardware(),
Constants.Shooter.FLYWHEEL_CONFIG,
Constants.Shooter.ANGLE_CONFIG,
Constants.Shooter.ANGLE_MOTION_CONSTRAINT,
Constants.Shooter.FLYWHEEL_DIAMETER,
Constants.Shooter.SHOOTER_MAP,
DRIVE_SUBSYSTEM::getPose,
() -> speakerSupplier()
);
private static final IntakeSubsystem INTAKE_SUBSYSTEM = new IntakeSubsystem(
IntakeSubsystem.initializeHardware(),
Constants.Intake.ROLLER_VELOCITY
);
private static final VisionSubsystem VISION_SUBSYSTEM = VisionSubsystem.getInstance();

private static final CommandXboxController PRIMARY_CONTROLLER = new CommandXboxController(Constants.HID.PRIMARY_CONTROLLER_PORT);
Expand All @@ -82,13 +82,13 @@ public RobotContainer() {
DRIVE_SUBSYSTEM.configureAutoBuilder();

// Register Named Commands
// NamedCommands.registerCommand(Constants.NamedCommands.INTAKE_COMMAND_NAME, autoIntakeCommand().withTimeout(7));
// NamedCommands.registerCommand(Constants.NamedCommands.PRELOAD_COMMAND_NAME, SHOOTER_SUBSYSTEM.shootSpeakerCommand().withTimeout(1.2));
// NamedCommands.registerCommand(Constants.NamedCommands.SHOOT_COMMAND_NAME, SHOOTER_SUBSYSTEM.shootSpeakerCommand().withTimeout(0.7));
// NamedCommands.registerCommand(Constants.NamedCommands.SPINUP_COMMAND_NAME, SHOOTER_SUBSYSTEM.spinupCommand());
NamedCommands.registerCommand(Constants.NamedCommands.INTAKE_COMMAND_NAME, autoIntakeCommand().withTimeout(7));
NamedCommands.registerCommand(Constants.NamedCommands.PRELOAD_COMMAND_NAME, SHOOTER_SUBSYSTEM.shootSpeakerCommand().withTimeout(1.2));
NamedCommands.registerCommand(Constants.NamedCommands.SHOOT_COMMAND_NAME, SHOOTER_SUBSYSTEM.shootSpeakerCommand().withTimeout(0.7));
NamedCommands.registerCommand(Constants.NamedCommands.SPINUP_COMMAND_NAME, SHOOTER_SUBSYSTEM.spinupCommand());

// NamedCommands.registerCommand(Constants.NamedCommands.FEEDTHROUGH_COMMAND_NAME, feedThroughCommand().withTimeout(2));
// NamedCommands.registerCommand(Constants.NamedCommands.AUTO_SHOOT_COMMAND_NAME, shootCommand().withTimeout(1));
NamedCommands.registerCommand(Constants.NamedCommands.FEEDTHROUGH_COMMAND_NAME, feedThroughCommand().withTimeout(2));
NamedCommands.registerCommand(Constants.NamedCommands.AUTO_SHOOT_COMMAND_NAME, shootCommand().withTimeout(1));

VISION_SUBSYSTEM.setPoseSupplier(() -> DRIVE_SUBSYSTEM.getPose());

Expand All @@ -111,34 +111,34 @@ private void configureBindings() {

// Right trigger button - aim and shoot at speaker, shooting only if speaker tag is visible and robot is in range
// Click right stick to override and shoot now
// PRIMARY_CONTROLLER.rightTrigger().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.b().getAsBoolean()));
PRIMARY_CONTROLLER.rightTrigger().whileTrue(shootCommand(() -> PRIMARY_CONTROLLER.b().getAsBoolean()));

// Right bumper button - amp score, also use for outtake
// PRIMARY_CONTROLLER.rightBumper().whileTrue(SHOOTER_SUBSYSTEM.scoreAmpCommand());
PRIMARY_CONTROLLER.rightBumper().whileTrue(SHOOTER_SUBSYSTEM.scoreAmpCommand());

// Left trigger button - intake game piece
// PRIMARY_CONTROLLER.leftTrigger().whileTrue(intakeCommand());
PRIMARY_CONTROLLER.leftTrigger().whileTrue(intakeCommand());

// Left bumper button - intake game piece from source
// PRIMARY_CONTROLLER.leftBumper().whileTrue(sourceIntakeCommand());
PRIMARY_CONTROLLER.leftBumper().whileTrue(sourceIntakeCommand());

// A button - go to amp and score
// PRIMARY_CONTROLLER.a().whileTrue(
// DRIVE_SUBSYSTEM.goToPoseCommand(
// Constants.Field.AMP,
// SHOOTER_SUBSYSTEM.prepareForAmpCommand(),
// SHOOTER_SUBSYSTEM.scoreAmpCommand()
// )
// );
PRIMARY_CONTROLLER.a().whileTrue(
DRIVE_SUBSYSTEM.goToPoseCommand(
Constants.Field.AMP,
SHOOTER_SUBSYSTEM.prepareForAmpCommand(),
SHOOTER_SUBSYSTEM.scoreAmpCommand()
)
);

// B button - go to source and intake game piece
// PRIMARY_CONTROLLER.b().whileTrue(
// DRIVE_SUBSYSTEM.goToPoseCommand(
// Constants.Field.SOURCE,
// SHOOTER_SUBSYSTEM.sourceIntakeCommand(),
// SHOOTER_SUBSYSTEM.sourceIntakeCommand()
// )
// );
PRIMARY_CONTROLLER.b().whileTrue(
DRIVE_SUBSYSTEM.goToPoseCommand(
Constants.Field.SOURCE,
SHOOTER_SUBSYSTEM.sourceIntakeCommand(),
SHOOTER_SUBSYSTEM.sourceIntakeCommand()
)
);
//B
// PRIMARY_CONTROLLER.b().whileTrue(aimAndIntakeObjectCommand());

Expand All @@ -151,13 +151,13 @@ private void configureBindings() {
);

// X button - shoot note into speaker from against the subwoofer
// PRIMARY_CONTROLLER.x().whileTrue(SHOOTER_SUBSYSTEM.shootSpeakerCommand());
PRIMARY_CONTROLLER.x().whileTrue(SHOOTER_SUBSYSTEM.shootSpeakerCommand());

// Y button - aim and shoot at speaker, regardless if shooting if speaker tag is visible
// PRIMARY_CONTROLLER.y().whileTrue(outtakeCommand());
PRIMARY_CONTROLLER.y().whileTrue(outtakeCommand());

// PRIMARY_CONTROLLER.povUp().whileTrue(SHOOTER_SUBSYSTEM.shootManualCommand(() -> dashboardStateSupplier()));
// PRIMARY_CONTROLLER.povRight().whileTrue(feedThroughCommand());
PRIMARY_CONTROLLER.povUp().whileTrue(SHOOTER_SUBSYSTEM.shootManualCommand(() -> dashboardStateSupplier()));
PRIMARY_CONTROLLER.povRight().whileTrue(feedThroughCommand());
}

/**
Expand All @@ -169,100 +169,100 @@ private void configureBindings() {
* </ul>
* @return Command that will automatically make the controller rumble based on the above conditions
*/
// private Command rumbleCommand() {
// return Commands.run(() -> {
// if (VISION_SUBSYSTEM.getObjectLocation().isPresent())
// PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kLeftRumble, 1.0);
// else PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kLeftRumble, 0.0);
// if (SHOOTER_SUBSYSTEM.isObjectPresent())
// PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kRightRumble, 1.0);
// else PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kRightRumble, 0.0);
// }).finallyDo(() -> PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kBothRumble, 0.0));
// }
private Command rumbleCommand() {
return Commands.run(() -> {
if (VISION_SUBSYSTEM.getObjectLocation().isPresent())
PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kLeftRumble, 1.0);
else PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kLeftRumble, 0.0);
if (SHOOTER_SUBSYSTEM.isObjectPresent())
PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kRightRumble, 1.0);
else PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kRightRumble, 0.0);
}).finallyDo(() -> PRIMARY_CONTROLLER.getHID().setRumble(RumbleType.kBothRumble, 0.0));
}

/**
* Compose command to intake a note and rumble controller appropriately
* @return Command that will automatically intake a note and prepare it for feeding inside the shooter motor
*/
// private Command intakeCommand() {
// return Commands.parallel(
// rumbleCommand(),
// INTAKE_SUBSYSTEM.intakeCommand(),
// SHOOTER_SUBSYSTEM.intakeCommand()
// );
// }
private Command intakeCommand() {
return Commands.parallel(
rumbleCommand(),
INTAKE_SUBSYSTEM.intakeCommand(),
SHOOTER_SUBSYSTEM.intakeCommand()
);
}

/**
* Compose command to intake a note via the source and rumble controller appropriately
* @return Command that will automatically intake a note from source via the shooter flywheels
*/
// private Command sourceIntakeCommand() {
// return Commands.parallel(
// rumbleCommand(),
// SHOOTER_SUBSYSTEM.sourceIntakeCommand()
// );
// }
private Command sourceIntakeCommand() {
return Commands.parallel(
rumbleCommand(),
SHOOTER_SUBSYSTEM.sourceIntakeCommand()
);
}

/**
* Intake until an object is present in autonomous
* @return Command to intake until an object is present
*/
// private Command autoIntakeCommand() {
// return Commands.parallel(
// INTAKE_SUBSYSTEM.intakeCommand(),
// SHOOTER_SUBSYSTEM.intakeCommand()
// ).until(() -> SHOOTER_SUBSYSTEM.isObjectPresent());
// }
private Command autoIntakeCommand() {
return Commands.parallel(
INTAKE_SUBSYSTEM.intakeCommand(),
SHOOTER_SUBSYSTEM.intakeCommand()
).until(() -> SHOOTER_SUBSYSTEM.isObjectPresent());
}

/**
* Compose command to outtake a note
* @return Command that will spit out a note from ground intake
*/
// private Command outtakeCommand() {
// return Commands.parallel(
// rumbleCommand(),
// INTAKE_SUBSYSTEM.outtakeCommand(),
// SHOOTER_SUBSYSTEM.outtakeCommand()
// );
// }
private Command outtakeCommand() {
return Commands.parallel(
rumbleCommand(),
INTAKE_SUBSYSTEM.outtakeCommand(),
SHOOTER_SUBSYSTEM.outtakeCommand()
);
}

/**
* Compose command to shoot note
* @param override Shoot even if target tag is not visible
* @return Command that will automatically aim and shoot note
*/
// private Command shootCommand(BooleanSupplier override) {
// return Commands.parallel(
// DRIVE_SUBSYSTEM.aimAtPointCommand(
// () -> PRIMARY_CONTROLLER.getLeftY(),
// () -> PRIMARY_CONTROLLER.getLeftX(),
// () -> PRIMARY_CONTROLLER.getRightX(),
// () -> speakerSupplier().pose.getTranslation().toTranslation2d(),
// true,
// true
// ),
// SHOOTER_SUBSYSTEM.shootCommand(() -> DRIVE_SUBSYSTEM.isAimed(), override)
// );
// }
private Command shootCommand(BooleanSupplier override) {
return Commands.parallel(
DRIVE_SUBSYSTEM.aimAtPointCommand(
() -> PRIMARY_CONTROLLER.getLeftY(),
() -> PRIMARY_CONTROLLER.getLeftX(),
() -> PRIMARY_CONTROLLER.getRightX(),
() -> speakerSupplier().pose.getTranslation().toTranslation2d(),
true,
true
),
SHOOTER_SUBSYSTEM.shootCommand(() -> DRIVE_SUBSYSTEM.isAimed(), override)
);
}

/**
* Compose command to shoot note, checking if tag is visible and robot is in range
* @return Command that will automatically aim and shoot note
*/
// private Command shootCommand() {
// return shootCommand(() -> false);
// }
private Command shootCommand() {
return shootCommand(() -> false);
}

/**
* Compose command to feed a note through the robot
*/
// private Command feedThroughCommand() {
// return Commands.parallel(
// rumbleCommand(),
// INTAKE_SUBSYSTEM.intakeCommand(),
// SHOOTER_SUBSYSTEM.feedThroughCommand(() -> DRIVE_SUBSYSTEM.isAimed())
// );
// }
private Command feedThroughCommand() {
return Commands.parallel(
rumbleCommand(),
INTAKE_SUBSYSTEM.intakeCommand(),
SHOOTER_SUBSYSTEM.feedThroughCommand(() -> DRIVE_SUBSYSTEM.isAimed())
);
}

/**
* Command to aim at detected game object automatically, driving normally if none is detected
Expand All @@ -287,29 +287,29 @@ private Command aimAtObject() {
* Automatically aim robot heading at object, drive, and intake a game object
* @return Command to aim robot at object, drive, and intake a game object
*/
// private Command aimAndIntakeObjectCommand() {
// return Commands.sequence(
// DRIVE_SUBSYSTEM.aimAtPointCommand(
// () -> PRIMARY_CONTROLLER.getLeftY(),
// () -> PRIMARY_CONTROLLER.getLeftX(),
// () -> PRIMARY_CONTROLLER.getRightX(),
// () -> {
// return VISION_SUBSYSTEM.getObjectLocation().isPresent()
// ? VISION_SUBSYSTEM.getObjectLocation().get()
// : null;
// },
// false,
// false).withTimeout(0.5),
// Commands.parallel(
// Commands.run(() -> {
// DRIVE_SUBSYSTEM.autoDrive(new ChassisSpeeds(3, 0, 0));
// }, DRIVE_SUBSYSTEM)
// // INTAKE_SUBSYSTEM.intakeCommand(),
// // SHOOTER_SUBSYSTEM.intakeCommand()
// )
// // .until(() -> SHOOTER_SUBSYSTEM.isObjectPresent())
// );
// }
private Command aimAndIntakeObjectCommand() {
return Commands.sequence(
DRIVE_SUBSYSTEM.aimAtPointCommand(
() -> PRIMARY_CONTROLLER.getLeftY(),
() -> PRIMARY_CONTROLLER.getLeftX(),
() -> PRIMARY_CONTROLLER.getRightX(),
() -> {
return VISION_SUBSYSTEM.getObjectLocation().isPresent()
? VISION_SUBSYSTEM.getObjectLocation().get()
: null;
},
false,
false).withTimeout(0.5),
Commands.parallel(
Commands.run(() -> {
DRIVE_SUBSYSTEM.autoDrive(new ChassisSpeeds(3, 0, 0));
}, DRIVE_SUBSYSTEM)
// INTAKE_SUBSYSTEM.intakeCommand(),
// SHOOTER_SUBSYSTEM.intakeCommand()
)
// .until(() -> SHOOTER_SUBSYSTEM.isObjectPresent())
);
}

/**
* Get correct speaker for current alliance
Expand Down

0 comments on commit 7707730

Please sign in to comment.