diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index e1de070..e6d6448 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -26,6 +26,7 @@ public class RobotContainer { private CommandXboxController driver; + //constructor// public RobotContainer() { drivetrain = new Drivetrain(); indexer = new Indexer(); @@ -39,6 +40,7 @@ public class RobotContainer { } private void configureBindings() { + //default commands// drivetrain.setDefaultCommand( drivetrain.driveArcade( null, @@ -68,6 +70,7 @@ public class RobotContainer { driver.x().onTrue(smartShooter()); } + //configures shuffleboard// private void configureShuffleboard() { ShuffleboardTab robotIndicatorTab = Shuffleboard.getTab(OIConstants.kRobotIndicatorsTabName); diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index e341aa7..fb7b044 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -67,6 +67,7 @@ public class Drivetrain extends SubsystemBase { drive = new DifferentialDrive(leftFront, rightFront); } + //getters/ public double getGyroAngle() { return gyro.getAngle() * (DrivetrainConstants.kInvertGyro ? -1 : 1); } diff --git a/src/main/java/frc/robot/subsystems/Indexer.java b/src/main/java/frc/robot/subsystems/Indexer.java index b080efb..a159006 100644 --- a/src/main/java/frc/robot/subsystems/Indexer.java +++ b/src/main/java/frc/robot/subsystems/Indexer.java @@ -9,10 +9,12 @@ import frc.robot.constants.IndexerConstants; public class Indexer extends SubsystemBase { private WPI_VictorSPX motor1; + //construtor// public Indexer(){ motor1 = new WPI_VictorSPX(IndexerConstants.kIndexerMotorCAN); } + //indexer commands// public Command runIndexer(double speed) { return run(() -> { motor1.set(speed); diff --git a/src/main/java/frc/robot/subsystems/Intake.java b/src/main/java/frc/robot/subsystems/Intake.java index fd203eb..12562c1 100644 --- a/src/main/java/frc/robot/subsystems/Intake.java +++ b/src/main/java/frc/robot/subsystems/Intake.java @@ -9,10 +9,12 @@ import frc.robot.constants.IntakeConstants; public class Intake extends SubsystemBase { private WPI_VictorSPX motor1; + //constructor// public Intake() { motor1 = new WPI_VictorSPX(IntakeConstants.kIntakeMotorCAN); } + //intake commands// public Command runIntake(double speed) { return run(() -> { motor1.set(speed); diff --git a/src/main/java/frc/robot/subsystems/Shooter.java b/src/main/java/frc/robot/subsystems/Shooter.java index f961168..0e142a4 100644 --- a/src/main/java/frc/robot/subsystems/Shooter.java +++ b/src/main/java/frc/robot/subsystems/Shooter.java @@ -19,6 +19,7 @@ public class Shooter extends SubsystemBase { private Encoder frontMotorEncoder; private Encoder rearMotorEncoder; + //constructor// public Shooter() { frontMotor = new WPI_VictorSPX(ShooterConstants.kFrontMotorCAN); rearMotor = new WPI_VictorSPX(ShooterConstants.kRearMotorCAN); @@ -48,6 +49,7 @@ public class Shooter extends SubsystemBase { rearMotorEncoder.setDistancePerPulse(ShooterConstants.kDistancePerPulse); } + //getters// public double getFrontEncoder() { return frontMotorEncoder.getRate(); } @@ -60,6 +62,7 @@ public class Shooter extends SubsystemBase { return (frontMotorEncoder.getRate() + rearMotorEncoder.getRate()) / 2 >= ShooterConstants.kShooterFireSpeed; } + //shooter commands// public Command runAutoShooter() { return run(() -> { double output = bangBangController.calculate(