Fixed formatting and code errors

This commit is contained in:
Noah 2024-10-18 00:44:58 +00:00
parent e74fa27d9d
commit 7f5af86800
8 changed files with 23 additions and 23 deletions

View File

@ -9,10 +9,10 @@ import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.Constants.OIConstants;
import frc.robot.Subsystems.Drivetrain;
import frc.robot.Subsystems.Flipper;
import frc.robot.Subsystems.Shooter;
import frc.robot.constants.OIConstants;
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Flipper;
import frc.robot.subsystems.Shooter;
public class RobotContainer {
@ -35,12 +35,12 @@ public class RobotContainer {
configureShuffleboard();
}
//runs our autonomous command//
//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()
.alongWith(flipper.runFlipper()).withTimeout(3));
.andThen(shooter.runShooter()).withTimeout(1)
.andThen(shooter.runShooter()
.alongWith(flipper.runFlipper()).withTimeout(3));
}
//sets up the default commands for each subsystem//
@ -62,11 +62,11 @@ public class RobotContainer {
//creates tabs and transforms them on the shuffleboard//
private void configureShuffleboard() {
ShuffleboardTab robotIndicatorTab = Shuffleboard.getTab(OIConstants.kSensorsTab);
ShuffleboardTab sensorTab = Shuffleboard.getTab(OIConstants.kSensorsTab);
robotIndicatorTab.addBoolean("Frisbee Loaded?", flipper::getPhotoSwitch1)
.withPosition(0, 0)
.withSize(2, 1)
.withWidget(BuiltInWidgets.kBooleanBox);
sensorTab.addBoolean("Frisbee Loaded?", flipper::getPhotoSwitch1)
.withPosition(0, 0)
.withSize(2, 1)
.withWidget(BuiltInWidgets.kBooleanBox);
}
}

View File

@ -1,4 +1,4 @@
package frc.robot.Constants;
package frc.robot.constants;
public class DrivetrainConstants {
public static final int kLeftFrontPWM = 0;

View File

@ -1,4 +1,4 @@
package frc.robot.Constants;
package frc.robot.constants;
public class FlipperConstants {
public static final int kFlipperPhotoSwitch = 0;

View File

@ -1,4 +1,4 @@
package frc.robot.Constants;
package frc.robot.constants;
public class OIConstants {
public static final int kDriverUSB = 0;

View File

@ -1,4 +1,4 @@
package frc.robot.Constants;
package frc.robot.constants;
public class ShooterConstants {
public static final int frontMotorPWM = 4;

View File

@ -1,4 +1,4 @@
package frc.robot.Subsystems;
package frc.robot.subsystems;
import java.util.function.DoubleSupplier;
@ -6,7 +6,7 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
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.DrivetrainConstants;
import frc.robot.constants.DrivetrainConstants;
public class Drivetrain extends SubsystemBase {

View File

@ -1,10 +1,10 @@
package frc.robot.Subsystems;
package frc.robot.subsystems;
import edu.wpi.first.wpilibj.DigitalInput;
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.FlipperConstants;
import frc.robot.constants.FlipperConstants;
public class Flipper extends SubsystemBase{

View File

@ -1,9 +1,9 @@
package frc.robot.Subsystems;
package frc.robot.subsystems;
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;
import frc.robot.constants.ShooterConstants;
public class Shooter extends SubsystemBase{