Skip to content

Commit

Permalink
Google Java Format
Browse files Browse the repository at this point in the history
  • Loading branch information
github-actions committed Dec 19, 2023
1 parent f05e5fc commit eeef98d
Show file tree
Hide file tree
Showing 12 changed files with 97 additions and 88 deletions.
11 changes: 6 additions & 5 deletions src/main/java/frc/robot/subsystems/intake/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -60,11 +60,12 @@ public Command intakeScoreCommand(ScoringState scoringState, IntakeGamepieces ex
SmartDashboard.putString("INTAKE STATE", scoringState.getStateName());

return run(() -> {
Commands.runOnce(
() -> outtakeCommand(scoringState.getOuttakeSpeed(expectedGamepiece)), this)
.andThen(Commands.waitSeconds(0.5))
.andThen(stopIntakeCommand());
}).andThen(stopIntakeCommand());
Commands.runOnce(
() -> outtakeCommand(scoringState.getOuttakeSpeed(expectedGamepiece)), this)
.andThen(Commands.waitSeconds(0.5))
.andThen(stopIntakeCommand());
})
.andThen(stopIntakeCommand());
}

/**
Expand Down
105 changes: 55 additions & 50 deletions src/main/java/frc/robot/subsystems/intake/states/ScoringState.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,59 +3,64 @@
import frc.robot.subsystems.intake.enums.IntakeGamepieces;

public abstract class ScoringState {
double outtakeSpeed;
double cubeOuttakeSpeed;
double coneOuttakeSpeed;

String stateName;

/**
* Creates a scoring state with the same outtake speed for cubes and cones
* @param outtakeSpeed The speed that should be used to outtake the gamepiece
* @param stateName The name of the scoring state that should be used for logging
*/
protected ScoringState(double outtakeSpeed, String stateName) {
this.outtakeSpeed = outtakeSpeed;
this.stateName = stateName;
}
double outtakeSpeed;
double cubeOuttakeSpeed;
double coneOuttakeSpeed;

/**
* Creates a scoring state with different outtake speeds for cubes and cones
* @param cubeOuttakeSpeed The speed that should be used to outtake the cube gamepiece
* @param coneOuttakeSpeed The speed that should be used to outtake the cone gamepiece
* @param stateName The name of the scoring state that should be used for logging
*/
protected ScoringState(double cubeOuttakeSpeed, double coneOuttakeSpeed, String stateName) {
this.cubeOuttakeSpeed = cubeOuttakeSpeed;
this.coneOuttakeSpeed = coneOuttakeSpeed;
this.stateName = stateName;
}
String stateName;

/**
* Creates a scoring state with the same outtake speed for cubes and cones
*
* @param outtakeSpeed The speed that should be used to outtake the gamepiece
* @param stateName The name of the scoring state that should be used for logging
*/
protected ScoringState(double outtakeSpeed, String stateName) {
this.outtakeSpeed = outtakeSpeed;
this.stateName = stateName;
}

/**
* Creates a scoring state with different outtake speeds for cubes and cones
*
* @param cubeOuttakeSpeed The speed that should be used to outtake the cube gamepiece
* @param coneOuttakeSpeed The speed that should be used to outtake the cone gamepiece
* @param stateName The name of the scoring state that should be used for logging
*/
protected ScoringState(double cubeOuttakeSpeed, double coneOuttakeSpeed, String stateName) {
this.cubeOuttakeSpeed = cubeOuttakeSpeed;
this.coneOuttakeSpeed = coneOuttakeSpeed;
this.stateName = stateName;
}

/**
* Gets the name of the scoring state
*
* @return The name of the scoring state
*/
public String getStateName() {
return this.stateName;
}

/**
* Gets the name of the scoring state
* @return The name of the scoring state
*/
public String getStateName() {
return this.stateName;
/**
* Gets the outtake speed for the scoring state depending on the gamepiece that is expected to be
* scored
*
* @return The outtake speed for the scoring state
*/
public double getOuttakeSpeed(IntakeGamepieces expectedGamepiece) {
if (expectedGamepiece == null) {
return this.outtakeSpeed;
}

/**
* Gets the outtake speed for the scoring state depending on the gamepiece that is expected to be scored
* @return The outtake speed for the scoring state
*/
public double getOuttakeSpeed(IntakeGamepieces expectedGamepiece) {
if (expectedGamepiece == null) {
return this.outtakeSpeed;
}

// Based on the gamepiece that is expected to be scored, return the appropriate outtake speed
switch(expectedGamepiece) {
case CUBE:
return this.cubeOuttakeSpeed;
case CONE:
return this.coneOuttakeSpeed;
default:
return 0.0;
}
// Based on the gamepiece that is expected to be scored, return the appropriate outtake speed
switch (expectedGamepiece) {
case CUBE:
return this.cubeOuttakeSpeed;
case CONE:
return this.coneOuttakeSpeed;
default:
return 0.0;
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
import frc.robot.subsystems.intake.states.ScoringState;

public class HighCone extends ScoringState {
HighCone() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CONE, "High Cone");
}

HighCone() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CONE, "High Cone");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class HighConeAuto extends ScoringState {

HighConeAuto() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CONE_AUTO, "High Cone Auto");
}
HighConeAuto() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CONE_AUTO, "High Cone Auto");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class MidCone extends ScoringState {

MidCone() {
super(IntakeConstants.OuttakeSpeeds.MID_CONE, "Mid Cone");
}
MidCone() {
super(IntakeConstants.OuttakeSpeeds.MID_CONE, "Mid Cone");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class MidConeTipped extends ScoringState {

MidConeTipped() {
super(IntakeConstants.OuttakeSpeeds.MID_CONE_TIPPED, "Mid Cone Tipped");
}
MidConeTipped() {
super(IntakeConstants.OuttakeSpeeds.MID_CONE_TIPPED, "Mid Cone Tipped");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class HighCube extends ScoringState {

HighCube() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CUBE, "High Cube");
}
HighCube() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CUBE, "High Cube");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class HighCubeAuto extends ScoringState {

HighCubeAuto() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CUBE, "High Cube Auto");
}
HighCubeAuto() {
super(IntakeConstants.OuttakeSpeeds.HIGH_CUBE, "High Cube Auto");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
import frc.robot.subsystems.intake.states.ScoringState;

public class MidCube extends ScoringState {
MidCube() {
super(IntakeConstants.OuttakeSpeeds.MID_CUBE, "Mid Cube");
}

MidCube() {
super(IntakeConstants.OuttakeSpeeds.MID_CUBE, "Mid Cube");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
import frc.robot.subsystems.intake.states.ScoringState;

public class MidCubeAuto extends ScoringState {
MidCubeAuto() {
super(IntakeConstants.OuttakeSpeeds.MID_CUBE, "Mid Cube Auto");
}

MidCubeAuto() {
super(IntakeConstants.OuttakeSpeeds.MID_CUBE, "Mid Cube Auto");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

public class Low extends ScoringState {

Low() {
super(IntakeConstants.OuttakeSpeeds.LOW_CUBE, IntakeConstants.OuttakeSpeeds.LOW_CONE, "Low");
}
Low() {
super(IntakeConstants.OuttakeSpeeds.LOW_CUBE, IntakeConstants.OuttakeSpeeds.LOW_CONE, "Low");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,10 @@

public class LowAuto extends ScoringState {

LowAuto() {
super(IntakeConstants.OuttakeSpeeds.LOW_CUBE_AUTO, IntakeConstants.OuttakeSpeeds.LOW_CONE_AUTO, "Low Auto");
}
LowAuto() {
super(
IntakeConstants.OuttakeSpeeds.LOW_CUBE_AUTO,
IntakeConstants.OuttakeSpeeds.LOW_CONE_AUTO,
"Low Auto");
}
}

0 comments on commit eeef98d

Please sign in to comment.