Fixes spelling, formatting, and funcitonality everywhere
This commit is contained in:
parent
2c4c1f24ea
commit
10130431c2
@ -14,14 +14,15 @@ import frc.robot.subsystems.Drivetrain;
|
||||
import frc.robot.subsystems.Flicker;
|
||||
import frc.robot.subsystems.Shooter;
|
||||
|
||||
|
||||
public class RobotContainer {
|
||||
private Flicker flicker;
|
||||
private Shooter shooter;
|
||||
|
||||
private Drivetrain drivetrain;
|
||||
|
||||
private CommandXboxController driver;
|
||||
public RobotContainer() {
|
||||
//sets up controlers
|
||||
//sets up controllers
|
||||
drivetrain = new Drivetrain();
|
||||
flicker = new Flicker();
|
||||
driver = new CommandXboxController(OIConstants.kDriverUSB);
|
||||
@ -31,38 +32,40 @@ public class RobotContainer {
|
||||
}
|
||||
|
||||
private void configureBindings() {
|
||||
//manual controls for driveing
|
||||
//manual controls for driving
|
||||
drivetrain.setDefaultCommand(
|
||||
drivetrain.driveArcade(
|
||||
driver::getLeftY,
|
||||
driver::getLeftX
|
||||
)
|
||||
);
|
||||
|
||||
flicker.setDefaultCommand(flicker.stop());
|
||||
//manual controls for shooter and flicker
|
||||
driver.a().onTrue(flicker.setSpeed(() ->1));
|
||||
shooter.setDefaultCommand(shooter.stop());
|
||||
driver.rightBumper().onTrue(shooter.setSpeed(()->1));
|
||||
|
||||
|
||||
driver.a().whileTrue(flicker.setSpeed(() ->1 ));
|
||||
|
||||
shooter.setDefaultCommand(shooter.stop());
|
||||
|
||||
driver.rightBumper().whileTrue(shooter.setSpeed(() -> 1));
|
||||
}
|
||||
private void configureShuffleboard() {
|
||||
//sets up the wiget
|
||||
//sets up the widget for the shuffboard
|
||||
ShuffleboardTab robotIndicatorTab = Shuffleboard.getTab(OIConstants.kRobotIndicatorsTabName);
|
||||
robotIndicatorTab.addBoolean("Sensors", flicker::frisbySensor)
|
||||
.withPosition(0, 0).
|
||||
withSize(2, 1).
|
||||
withWidget(BuiltInWidgets.kBooleanBox);
|
||||
|
||||
|
||||
robotIndicatorTab.addBoolean("Frisbee Presence Sensor", flicker::frisbeeSensor)
|
||||
.withPosition(0, 0)
|
||||
.withSize(2, 1)
|
||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||
|
||||
}
|
||||
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
//sets up the anumus command, it drives forward for 2 seconds, spins the shooter mototrs for 1 second, and both shooter and flicker for 3 seconds.
|
||||
return drivetrain.driveTank(() -> .5,() -> .5).withTimeout(2). andThen(
|
||||
shooter.setSpeed(()-> 1)).withTimeout(1).andThen(
|
||||
shooter.setSpeed(()->1)).alongWith(
|
||||
flicker.setSpeed(()->1));
|
||||
//sets up the autonomous command, it drives forward for 2 seconds, spins the shooter mototrs for 1 second, and both shooter and flicker for 3 seconds.
|
||||
return drivetrain.driveTank(() -> .5,() -> .5).withTimeout(2).andThen(
|
||||
shooter.setSpeed(()-> 1).withTimeout(1),
|
||||
shooter.setSpeed(()->1).alongWith(flicker.setSpeed(()->1))
|
||||
.withTimeout(3)
|
||||
);
|
||||
}
|
||||
}
|
||||
|
@ -1,9 +1,8 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class DrivetrainConstants {
|
||||
public static final int kleftFrontPWN = 0;
|
||||
public static final int kleftRearPWN = 1;
|
||||
public static final int kLeftFrontPWM = 0;
|
||||
public static final int kLeftRearPWM = 1;
|
||||
public static final int kRightFrontPWM = 2;
|
||||
public static final int kRightRearPWM = 3;
|
||||
|
||||
}
|
||||
|
@ -1,7 +1,7 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class FlickerConstants {
|
||||
public static final int k3motorPWM = 1;
|
||||
public static final int k3MotorPWM = 6;
|
||||
|
||||
public static int kPhotoSwitch = 1;
|
||||
public static final int kFrisbeeSensor = 0;
|
||||
}
|
||||
|
@ -2,7 +2,6 @@ package frc.robot.constants;
|
||||
|
||||
public class OIConstants {
|
||||
public static final int kDriverUSB = 0;
|
||||
public static final int kOperatorUSB = 1;
|
||||
|
||||
public static final String kRobotIndicatorsTabName = "Robot Indicators";
|
||||
public static final String kRobotIndicatorsTabName = "Sensors";
|
||||
}
|
@ -1,6 +1,6 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class ShooterConstants {
|
||||
public static final int K1MotorPWM = 0;
|
||||
public static final int K2MotorPWM = 0;
|
||||
public static final int k1MotorPWM = 4;
|
||||
public static final int k2MotorPWM = 5;
|
||||
}
|
||||
|
@ -19,8 +19,8 @@ public class Drivetrain extends SubsystemBase {
|
||||
|
||||
public Drivetrain() {
|
||||
//turns the code inputs (like how fast or how to turn) and make it a way that the motors will understand.
|
||||
leftFront = new VictorSP(DrivetrainConstants.kleftFrontPWN);
|
||||
leftRear = new VictorSP(DrivetrainConstants.kleftRearPWN);
|
||||
leftFront = new VictorSP(DrivetrainConstants.kLeftFrontPWM);
|
||||
leftRear = new VictorSP(DrivetrainConstants.kLeftRearPWM);
|
||||
rightFront = new VictorSP(DrivetrainConstants.kRightFrontPWM);
|
||||
rightRear = new VictorSP(DrivetrainConstants.kRightRearPWM);
|
||||
|
||||
@ -37,11 +37,11 @@ public class Drivetrain extends SubsystemBase {
|
||||
drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble());
|
||||
});
|
||||
}
|
||||
public Command driveTank(DoubleSupplier leftspeed, DoubleSupplier rightspeed) {
|
||||
|
||||
public Command driveTank(DoubleSupplier leftSpeed, DoubleSupplier rightSpeed) {
|
||||
return run(() -> {
|
||||
//makes tank steering possible
|
||||
drive.tankDrive(leftspeed.getAsDouble(), rightspeed.getAsDouble());
|
||||
drive.tankDrive(leftSpeed.getAsDouble(), rightSpeed.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -11,27 +11,28 @@ import frc.robot.constants.FlickerConstants;
|
||||
public class Flicker extends SubsystemBase {
|
||||
private VictorSP motor;
|
||||
|
||||
private DigitalInput frisbySensor;
|
||||
private DigitalInput frisbeeSensor;
|
||||
|
||||
public Flicker() {
|
||||
//sets motors and the photo switch
|
||||
motor = new VictorSP(FlickerConstants.k3motorPWM);
|
||||
motor = new VictorSP(FlickerConstants.k3MotorPWM);
|
||||
|
||||
frisbySensor = new DigitalInput(FlickerConstants.kPhotoSwitch);
|
||||
|
||||
frisbeeSensor = new DigitalInput(FlickerConstants.kFrisbeeSensor);
|
||||
}
|
||||
|
||||
public boolean frisbySensor() {
|
||||
//makes the photoswitch useable for the if statment so the code will know if the photoswitch was blocked.
|
||||
return frisbySensor.get();
|
||||
public boolean frisbeeSensor() {
|
||||
/*this uses a photoswitch to see if a frisbbe is there or not,
|
||||
and if not where it is called in in RobotContrainer makes it so it won't shot if no frisbee*/
|
||||
return frisbeeSensor.get();
|
||||
}
|
||||
|
||||
public Command setSpeed(DoubleSupplier speed){
|
||||
//makes it so the motor will run but if the photoswitch can't see the frisby it will stop.
|
||||
//makes it so the motor will run but if the photoswitch can't see the frisbee it will stop.
|
||||
return run(() -> {
|
||||
if (frisbySensor.get()) {
|
||||
motor.set(speed.getAsDouble());
|
||||
} else {
|
||||
motor.set(0);
|
||||
if (frisbeeSensor.get()) {
|
||||
motor.set(speed.getAsDouble());
|
||||
} else {
|
||||
motor.set(0);
|
||||
}
|
||||
});
|
||||
}
|
||||
|
@ -7,23 +7,23 @@ import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ShooterConstants;
|
||||
|
||||
public class Shooter extends SubsystemBase{
|
||||
public class Shooter extends SubsystemBase {
|
||||
//makes the motors varables
|
||||
private VictorSP motor1;
|
||||
private VictorSP motor2;
|
||||
|
||||
public Shooter() {
|
||||
//sets up the motors to be used in the code
|
||||
motor1 = new VictorSP(ShooterConstants.K1MotorPWM);
|
||||
motor2 = new VictorSP(ShooterConstants.K2MotorPWM);
|
||||
motor1 = new VictorSP(ShooterConstants.k1MotorPWM);
|
||||
motor2 = new VictorSP(ShooterConstants.k2MotorPWM);
|
||||
|
||||
motor1.addFollower(motor2);
|
||||
}
|
||||
|
||||
public Command setSpeed(DoubleSupplier speed) {
|
||||
//sets the motors speed
|
||||
//sets the motors speed
|
||||
return run(() -> {
|
||||
motor1.set(speed.getAsDouble());
|
||||
motor1.set(speed.getAsDouble());
|
||||
});
|
||||
}
|
||||
public Command stop() {
|
||||
|
Loading…
Reference in New Issue
Block a user