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

fixed intake to make it better #112

Merged
merged 2 commits into from
Mar 21, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
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
26 changes: 13 additions & 13 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ public class RobotContainer {
DoubleSupplier zeroSup;

BooleanSupplier intakeReverse;
Command autoPickup;
// Replace with CommandPS4Controller or CommandJoystick if needed

/** The container for the robot. Contains subsystems, OI devices, and commands. */
Expand Down Expand Up @@ -287,10 +288,17 @@ private void configureBindings() {
));

if(Preferences.getBoolean("Detector Limelight", false)) {
new Trigger(operatorController::getR1Button).whileTrue(new SequentialCommandGroup(
new CollectNote(driveTrain, limelight),
new DriveTimeCommand(-1, 0, 0, 1, driveTrain)
));
autoPickup = new ParallelRaceGroup(
new AutoGroundIntake(indexer, intake, angleShooterSubsystem),
new SequentialCommandGroup(
new CollectNote(driveTrain, limelight),
new DriveTimeCommand(-1, 0, 0, 1.5, driveTrain),
new DriveTimeCommand(1, 0, 0, 0.5, driveTrain),
new DriveTimeCommand(-1, 0, 0, 0.5, driveTrain),
new WaitCommand(0.5)
)
).withTimeout(4);
new Trigger(operatorController::getR1Button).whileTrue(autoPickup);
}
new Trigger(ForceVisionSup).onTrue(new InstantCommand(()->SmartDashboard.putBoolean("force use limelight", true))).onFalse(new InstantCommand(()->SmartDashboard.putBoolean("force use limelight", false)));
SmartDashboard.putData("force update limelight position", new InstantCommand(()->driveTrain.forceUpdateOdometryWithVision(), driveTrain));
Expand Down Expand Up @@ -445,15 +453,7 @@ private void registerNamedCommands() {
new AutoGroundIntake(indexer, intake, angleShooterSubsystem)
));
if(intakeExists&&indexerExists&&angleShooterExists) {
NamedCommands.registerCommand("autoPickup",new ParallelCommandGroup(
new AutoGroundIntake(indexer, intake, angleShooterSubsystem),
new SequentialCommandGroup(
new CollectNote(driveTrain, limelight),
new DriveTimeCommand(-1, 0, 0, 1.5, driveTrain),
new DriveTimeCommand(1, 0, 0, 0.5, driveTrain)
)
).withTimeout(3.5)
);
NamedCommands.registerCommand("autoPickup", autoPickup);
}
if(intakeExists&&!indexerExists&&!angleShooterExists) {
NamedCommands.registerCommand("groundIntake", new InstantCommand(()->intake.intakeYes(IntakeConstants.INTAKE_SPEED)));
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/settings/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -265,7 +265,7 @@ public static final class ShooterConstants{
public static final double HUMAN_PLAYER_ANGLE = 97;
public static final double HUMAN_PLAYER_RPS = -15;
public static final double SAFE_SHOOTER_ANGLE = 15;
public static final double GROUND_INTAKE_SHOOTER_ANGLE = 90;
public static final double GROUND_INTAKE_SHOOTER_ANGLE = 69;
/**
* the values used when adjusting the shooter's angle based on our speaker distance. Here's how we calculated them:
* <p>
Expand Down
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,7 @@ public IntakeSubsystem() {
} else {
m_DistanceSensor = intake2.getAnalog(Mode.kAbsolute);
}
intake2.follow(intake1);
intake2.setInverted(false);
intake2.setInverted(true);
intake1.setInverted(true);
intake1.setIdleMode(IdleMode.kCoast);
intake2.setIdleMode(IdleMode.kCoast);
Expand All @@ -65,6 +64,7 @@ public IntakeSubsystem() {
*/
public void intakeYes(double intakeRunSpeed) {
intake1.set(intakeRunSpeed);
intake2.set(intakeRunSpeed);
}
/**
* sets the intakes speed
Expand All @@ -73,12 +73,14 @@ public void intakeYes(double intakeRunSpeed) {
*/
public void intakeNo(double intakeRunSpeed) {
intake1.set(-intakeRunSpeed);
intake2.set(-intakeRunSpeed);
}
/**
* sets the intake's power to 0
*/
public void intakeOff() {
intake1.set(0);
intake2.set(0);
}
/**
* uses the distance sensor inside the indexer to tell if there is a note fully inside the indexer
Expand Down
Loading