Skip to content

Commit

Permalink
Code cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
rachitkakkar committed Jan 11, 2024
1 parent 669b866 commit 41c284d
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 23 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,8 @@ public static class DriveHardware {
}

public static class ShooterHardware {
public static final Spark.ID LEFT_MOTOR_ID = new Spark.ID("DriveHardware/Shooter/Left", 11);
public static final Spark.ID RIGHT_MOTOR_ID = new Spark.ID("DriveHardware/Shooter/Right", 12);
public static final Spark.ID LEFT_SLAVE_MOTOR_ID = new Spark.ID("DriveHardware/Shooter/Left", 11);
public static final Spark.ID RIGHT_MASTER_MOTOR_ID = new Spark.ID("DriveHardware/Shooter/Right", 12);

}

Expand Down
42 changes: 21 additions & 21 deletions src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,19 +15,17 @@

public class ShooterSubsystem extends SubsystemBase {
public class Hardware {
Spark leftMotor;
Spark rightMotor;
private Spark lSlaveMotor;
private Spark rMasterMotor;

public Hardware(Spark leftMotor, Spark rightMotor) {
this.leftMotor = leftMotor;
this.rightMotor = rightMotor;

this.leftMotor.follow(this.rightMotor);
public Hardware(Spark lSlaveMotor, Spark rMasterMotor) {
this.lSlaveMotor = lSlaveMotor;
this.rMasterMotor = rMasterMotor;
}
}

Spark m_leftMotor;
Spark m_rightMotor;
private Spark m_lSlaveMotor;
private Spark m_rMasterMotor;

/**
* Create an instance of ShooterSubsystem
Expand All @@ -37,33 +35,35 @@ public Hardware(Spark leftMotor, Spark rightMotor) {
* @param shooterHardware Hardware devices required by shooter
*/
public ShooterSubsystem(Hardware shooterHardware) {
this.m_leftMotor = shooterHardware.leftMotor;
this.m_rightMotor = shooterHardware.rightMotor;
this.m_lSlaveMotor = shooterHardware.lSlaveMotor;
this.m_rMasterMotor = shooterHardware.rMasterMotor;

m_lSlaveMotor.follow(m_rMasterMotor);
}

public Hardware initializeHardware() {
Hardware shooterHardware = new Hardware(
new Spark(Constants.ShooterHardware.LEFT_MOTOR_ID, MotorKind.NEO),
new Spark(Constants.ShooterHardware.RIGHT_MOTOR_ID, MotorKind.NEO)
new Spark(Constants.ShooterHardware.LEFT_SLAVE_MOTOR_ID, MotorKind.NEO),
new Spark(Constants.ShooterHardware.RIGHT_MASTER_MOTOR_ID, MotorKind.NEO)
);

return shooterHardware;
}

private void setPower(double power) {
m_leftMotor.set(power);
private void shoot(double power) {
m_rMasterMotor.set(power);
}

private void stop() {
m_leftMotor.stopMotor();
m_rMasterMotor.stopMotor();
}

public Command shootCommand(DoubleSupplier speed) {
return startEnd(() -> shoot(speed.getAsDouble()), () -> stop());
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}

public Command shootCommand(DoubleSupplier speed) {
return startEnd(() -> setPower(speed.getAsDouble()), () -> stop());
}
}

0 comments on commit 41c284d

Please sign in to comment.