Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Rumble to Intake #71

Merged
merged 18 commits into from
Mar 19, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 3 additions & 10 deletions src/main/java/frc/team2412/robot/Controls.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,17 +11,14 @@
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.team2412.robot.commands.intake.AllInCommand;
import frc.team2412.robot.commands.intake.AllInRumbleCommand;
import frc.team2412.robot.commands.intake.AllReverseCommand;
import frc.team2412.robot.commands.intake.AllStopCommand;
import frc.team2412.robot.commands.intake.FeederInCommand;
import frc.team2412.robot.commands.intake.IntakeRejectCommand;
import frc.team2412.robot.commands.intake.StopRumbleCommand;
import frc.team2412.robot.commands.launcher.SetAngleAmpLaunchCommand;
import frc.team2412.robot.commands.launcher.SetAngleCommand;
import frc.team2412.robot.commands.launcher.SetAngleLaunchCommand;
Expand Down Expand Up @@ -124,15 +121,11 @@ private void bindDrivebaseControls() {
private void bindIntakeControls() {
// CommandScheduler.getInstance()
// .setDefaultCommand(s.intakeSubsystem, new IntakeStopCommand(s.intakeSubsystem));
driveIntakeInButton.onTrue(
Commands.sequence(
new AllInCommand(s.intakeSubsystem, this),
new WaitCommand(0.5),
new StopRumbleCommand(this)));
driveIntakeInButton.onTrue(new AllInRumbleCommand(s.intakeSubsystem, this));
driveIntakeStopButton.onTrue(new AllStopCommand(s.intakeSubsystem));
driveIntakeReverseButton.onTrue(new AllReverseCommand(s.intakeSubsystem));
driveIntakeRejectButton.onTrue(new IntakeRejectCommand(s.intakeSubsystem));
codriveIntakeInButton.onTrue(new AllInCommand(s.intakeSubsystem, this));
codriveIntakeInButton.onTrue(new AllInRumbleCommand(s.intakeSubsystem, this));
codriveIntakeStopButton.onTrue(new AllStopCommand(s.intakeSubsystem));
codriveIntakeReverseButton.onTrue(new AllReverseCommand(s.intakeSubsystem));
codriveIntakeRejectButton.onTrue(new IntakeRejectCommand(s.intakeSubsystem));
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
package frc.team2412.robot.commands.intake;

import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.team2412.robot.Controls;
import frc.team2412.robot.subsystems.IntakeSubsystem;

public class AllInRumbleCommand extends SequentialCommandGroup {
private final IntakeSubsystem intakeSubsystem;
private final Controls controls;

public AllInRumbleCommand(IntakeSubsystem intakeSubsystem, Controls controls) {
this.intakeSubsystem = intakeSubsystem;
this.controls = controls;
addRequirements(intakeSubsystem);
eddiert1239 marked this conversation as resolved.
Show resolved Hide resolved

addCommands(new AllInCommand(intakeSubsystem, controls), new WaitCommand(0.5));
}

public void end() {
eddiert1239 marked this conversation as resolved.
Show resolved Hide resolved
controls.vibrateDriveController(0.0);
}
}

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,7 @@ public class IntakeSubsystem extends SubsystemBase {
.getEntry();

public IntakeSubsystem() {

intakeMotorFront = new CANSparkMax(INTAKE_MOTOR_FRONT, MotorType.kBrushless);
intakeMotorBack = new CANSparkMax(INTAKE_MOTOR_BACK, MotorType.kBrushless);
intakeMotorLeft = new CANSparkMax(INTAKE_MOTOR_LEFT, MotorType.kBrushless);
Expand Down
Loading