Fixed formatting error
This commit is contained in:
parent
7f5af86800
commit
111d2c9d6f
@ -15,7 +15,6 @@ import frc.robot.subsystems.Flipper;
|
||||
import frc.robot.subsystems.Shooter;
|
||||
|
||||
public class RobotContainer {
|
||||
|
||||
//creates instanced variables//
|
||||
private Drivetrain drivetrain;
|
||||
private Flipper flipper;
|
||||
@ -38,8 +37,8 @@ public class RobotContainer {
|
||||
//moves forwards at half speed for 2 seconds, runs the shooter for 1 second, then runs the shooter & flipper for 3 seconds//
|
||||
public Command getAutonomousCommand() {
|
||||
return drivetrain.driveTank(() -> .5, () -> .5).withTimeout(2)
|
||||
.andThen(shooter.runShooter()).withTimeout(1)
|
||||
.andThen(shooter.runShooter()
|
||||
.andThen(shooter.runShooter(() -> true)).withTimeout(1)
|
||||
.andThen(shooter.runShooter(() -> true)
|
||||
.alongWith(flipper.runFlipper()).withTimeout(3));
|
||||
}
|
||||
|
||||
@ -57,14 +56,14 @@ public class RobotContainer {
|
||||
|
||||
//configures our controller to run commands when their respective trigger is activated//
|
||||
driver.a().whileTrue(flipper.runFlipper());
|
||||
driver.rightBumper().whileTrue(shooter.runShooter());
|
||||
driver.rightBumper().whileTrue(shooter.runShooter(flipper::getHasFrisbee));
|
||||
}
|
||||
|
||||
//creates tabs and transforms them on the shuffleboard//
|
||||
private void configureShuffleboard() {
|
||||
ShuffleboardTab sensorTab = Shuffleboard.getTab(OIConstants.kSensorsTab);
|
||||
|
||||
sensorTab.addBoolean("Frisbee Loaded?", flipper::getPhotoSwitch1)
|
||||
sensorTab.addBoolean("Frisbee Loaded?", flipper::getHasFrisbee)
|
||||
.withPosition(0, 0)
|
||||
.withSize(2, 1)
|
||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||
|
@ -11,27 +11,31 @@ public class Flipper extends SubsystemBase{
|
||||
//creates instanced variables//
|
||||
private VictorSP motor1;
|
||||
|
||||
private DigitalInput photoSwitch1;
|
||||
private DigitalInput hasFrisbee;
|
||||
|
||||
|
||||
public Flipper() {
|
||||
|
||||
//creates instances of all our hardware//
|
||||
motor1 = new VictorSP(FlipperConstants.kFlipperPWM);
|
||||
|
||||
photoSwitch1 = new DigitalInput(FlipperConstants.kFlipperPhotoSwitch);
|
||||
hasFrisbee = new DigitalInput(FlipperConstants.kFlipperPhotoSwitch);
|
||||
}
|
||||
|
||||
//a method that returns the state of photoSwitch1//
|
||||
public boolean getPhotoSwitch1() {
|
||||
return photoSwitch1.get();
|
||||
//a method that returns the state of hasFrisbee//
|
||||
public boolean getHasFrisbee() {
|
||||
return hasFrisbee.get();
|
||||
}
|
||||
|
||||
//commands that start and stop our flipper//
|
||||
//commands that start and stop our flipper. will only start if the photo switch detects a frisbee//
|
||||
public Command runFlipper() {
|
||||
return run(() -> {
|
||||
motor1.set(1);})
|
||||
.onlyWhile(photoSwitch1::get);
|
||||
if (getHasFrisbee()) {
|
||||
motor1.set(1);
|
||||
}
|
||||
else {
|
||||
motor1.set(0);
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
public Command stopFlipper(){
|
||||
|
@ -1,12 +1,13 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.function.BooleanSupplier;
|
||||
|
||||
import edu.wpi.first.wpilibj.motorcontrol.VictorSP;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ShooterConstants;
|
||||
|
||||
public class Shooter extends SubsystemBase{
|
||||
|
||||
//creates instanced variables//
|
||||
private VictorSP frontMotor;
|
||||
private VictorSP rearMotor;
|
||||
@ -21,9 +22,14 @@ public class Shooter extends SubsystemBase{
|
||||
}
|
||||
|
||||
//commands that start and stop our shooter//
|
||||
public Command runShooter(){
|
||||
public Command runShooter(BooleanSupplier hasFrisbee){
|
||||
return run(() -> {
|
||||
frontMotor.set(1);
|
||||
if (hasFrisbee.getAsBoolean()) {
|
||||
frontMotor.set(1);
|
||||
}
|
||||
else {
|
||||
frontMotor.set(0);
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user