Skip to content

Commit

Permalink
misc
Browse files Browse the repository at this point in the history
  • Loading branch information
ori-coval committed Feb 27, 2024
1 parent 352e9b7 commit 76bc408
Show file tree
Hide file tree
Showing 5 changed files with 12 additions and 52 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ public static final class IntakeArmConstants {
// set points
public static final double AmpSetPoint = 2;
public static final double SafeSetPoint = 0;
public static final double intakeSetPoint = -175;
public static final double intakeSetPoint = -152;


}
Expand Down
51 changes: 5 additions & 46 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
import frc.Utils.PathPlanner.PathPlannerHelper;
import frc.robot.Constants.IntakeArmConstants;
import frc.robot.aRobotOperations.CollectToFeeder;
import frc.robot.aRobotOperations.EStop;
import frc.robot.aRobotOperations.PrepareForShoot;
import frc.robot.aRobotOperations.ShootTouchingBase;
import frc.robot.basicCommands.IntakeArmCommands.IntakeArmDown;
Expand Down Expand Up @@ -44,6 +45,7 @@ public class RobotContainer {
Trigger driverBackTrigger = driver.back();
Trigger driverPovLeftTrigger = driver.povLeft();
Trigger driverPovRightTrigger = driver.povRight();
Trigger driverStart = driver.start();

// Operator Triggers
Trigger operatorXTrigger = operator.x();
Expand All @@ -52,6 +54,7 @@ public class RobotContainer {
Trigger operatorRightBumperTrigger = operator.rightBumper();
Trigger operatorLeftBumperTrigger = operator.leftBumper();
Trigger operatorBTrigger = operator.b();
Trigger operatorStart = operator.start();

PathPlannerHelper pathPlannerHelper = PathPlannerHelper.getInstace();

Expand All @@ -74,49 +77,6 @@ public RobotContainer() {
() -> driver.getHID().getRightTriggerAxis() > 0.5));


//IntakeArmSubsystem.getInstance().setDefaultCommand(new IntakeArmSetSpeed(()-> -test.getRightX()));



// ShooterArmSubsystem.getInstance().setDefaultCommand(new InstantCommand(()->{
// ShooterArmSubsystem.getInstance().setSpeedArm(()-> test.getLeftX() / 10);
// }, ShooterArmSubsystem.getInstance()));
// test.b().onTrue(new ZeroShooterArm());

// ShooterSubsystem.getInstance().setDefaultCommand(new InstantCommand(()->{
// ShooterSubsystem.getInstance().manualSetShooterSpeed(()-> test.getRightY());
// }, ShooterSubsystem.getInstance()));

// IntakeSubsystem.getInstance().setDefaultCommand(new IntakeSetSpeed(()->
// -test.getLeftY()));

// test.a().onTrue(new CollectToIntake());

// Configure the button bindings
// test.x().onTrue(new MoveShooterArmTo(29));

// driver.leftBumper().onTrue(new FeederSetSpeed(()->1));
// test.rightBumper().onTrue(new FeederSetSpeed(()->0));
// driver.start().onTrue(new ZeroShooterArm());
// driver.x().whileTrue(new InstantCommand(()->
// ShooterSubsystem.getInstance().setShooterSpeed(100,100),
// ShooterSubsystem.getInstance()));
// test.start().whileTrue(new InstantCommand(()->
// ShooterSubsystem.getInstance().setShooterSpeed(0, 0),
// ShooterSubsystem.getInstance()));

// driver.leftTrigger().whileTrue(new AlignToSpeaker());
// driver.x().onTrue(new ShooterArmSpeakerAngle());
// driver.b().onTrue(new CollectToFeeder());
// driver.a().onTrue(new ShootSpeaker());

// test.b().onTrue(new IntakeArmUP());
// test.x().onTrue(new IntakeArmDown());

// driver.a().whileTrue(new InstantCommand(() -> ShooterSubsystem.getInstance().setShooterSpeed(100, 100),
// ShooterSubsystem.getInstance()));
// // test.leftBumper().onTrue(new ShootTouchingBase());

configureButtonBindings();
}

Expand All @@ -132,18 +92,17 @@ public RobotContainer() {
private void configureButtonBindings() {

// Driver Button Bindings
driverStart.onTrue(new EStop());
driverYTrigger.onTrue(new InstantCommand(() -> swerve.zeroGyro()));
driverXTrigger.onTrue(new ShootTouchingBase());
driverRightBumperTrigger.whileTrue(new FeederSetSpeed(()->1).repeatedly());
driverLeftTriggerToggle.toggleOnTrue(new AlignToSpeaker());
driverBackTrigger.onTrue(swerve.disableHeadingCommand());
driverPovLeftTrigger.onTrue(new ZeroIntakeArm());
driverPovRightTrigger.onTrue(new ZeroShooterArm());
driver.start().onTrue(new InstantCommand(()->ShooterSubsystem.getInstance().setShooterSpeed(70, 70
),ShooterSubsystem.getInstance()));

// Operator Button Bindings
operator.start().whileTrue(new AlignToAngle(Rotation2d.fromDegrees(90)));
operatorStart.onTrue(new EStop());
operatorXTrigger.onTrue(new CollectToFeeder());
operatorYTrigger.toggleOnTrue(new PrepareForShoot().repeatedly());
operatorATrigger
Expand Down
4 changes: 1 addition & 3 deletions src/main/java/frc/robot/aRobotOperations/EStop.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,7 @@ public EStop() {
new IntakeArmSetSpeed(()->0),
new IntakeSetSpeed(()->0),
new ShooterArmSetSpeed(()-> 0),
new ShooterSetSpeed(0),
new TrapArmSetSpeed(0),
new TrapSetSpeed(0)
new ShooterSetSpeed(0)
);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ public void end(boolean interrupted) {

@Override
public boolean isFinished() {
return Math.abs(intakeArm.getPose() + 175)<10;
return Math.abs(intakeArm.getPose() + intakeSetPoint)<10;
}

}
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.FeederSubsystem;
import frc.robot.subsystems.ShooterArmSubsystem;
import frc.robot.subsystems.ShooterSubsystem;

import static frc.robot.Constants.FeederConstants.*;

public class FeedToShooterBase extends Command {
Expand Down Expand Up @@ -37,7 +39,8 @@ public void initialize() {
public void execute() {
if (!startedShooting &&
timer.hasElapsed(1)
&&shooterArmSubsystem.getArmPose()<2) {
&&shooterArmSubsystem.isArmReady()&&
ShooterSubsystem.getInstance().checkIfShooterAtSpeed()) {

feederSubsystem.setSpeed(FeederShootSpeed);
startedShooting = true;
Expand Down

0 comments on commit 76bc408

Please sign in to comment.