Comments added
This commit is contained in:
parent
c47d35120c
commit
496891cce4
@ -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);
|
||||
|
||||
|
@ -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);
|
||||
}
|
||||
|
@ -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);
|
||||
|
@ -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);
|
||||
|
@ -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(
|
||||
|
Loading…
Reference in New Issue
Block a user