Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 734cd58

Browse files
committed
chore: Format.
1 parent ad75032 commit 734cd58

File tree

10 files changed

+49
-40
lines changed

10 files changed

+49
-40
lines changed

src/main/java/frc/lib/controller/VelocityControllerIO.java

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -57,16 +57,12 @@ public static void addToShuffleboard(
5757
velocityController.addDouble(
5858
"Acceleration (dpsps)",
5959
() -> Units.rotationsToDegrees(values.accelerationRotationsPerSecondPerSecond));
60+
velocityController.addDouble("Velocity (rps)", () -> values.velocityRotationsPerSecond);
6061
velocityController.addDouble(
61-
"Velocity (rps)", () -> values.velocityRotationsPerSecond);
62+
"Acceleration (rpsps)", () -> values.accelerationRotationsPerSecondPerSecond);
63+
velocityController.addDouble("Velocity (rpm)", () -> values.velocityRotationsPerSecond * 60);
6264
velocityController.addDouble(
63-
"Acceleration (rpsps)",
64-
() -> values.accelerationRotationsPerSecondPerSecond);
65-
velocityController.addDouble(
66-
"Velocity (rpm)", () -> values.velocityRotationsPerSecond * 60);
67-
velocityController.addDouble(
68-
"Acceleration (rpmpm)",
69-
() -> values.accelerationRotationsPerSecondPerSecond * 60);
65+
"Acceleration (rpmpm)", () -> values.accelerationRotationsPerSecondPerSecond * 60);
7066
velocityController.addDouble("Voltage (V)", () -> values.motorVolts);
7167
velocityController.addDouble("Current (A)", () -> values.motorAmps);
7268
}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
package frc.robot;
22

3-
import edu.wpi.first.wpilibj.XboxController;
43
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
4+
import edu.wpi.first.wpilibj.XboxController;
55
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
66
import edu.wpi.first.wpilibj2.command.Command;
77
import edu.wpi.first.wpilibj2.command.Commands;
@@ -32,7 +32,7 @@ public class RobotContainer {
3232

3333
private final CommandXboxController driverController, operatorController;
3434

35-
private final XboxController rumbleController;
35+
private final XboxController rumbleController;
3636

3737
/** Creates a new instance of the robot container. */
3838
private RobotContainer() {
@@ -103,9 +103,7 @@ private void configureBindings() {
103103

104104
public Command rumble(RumbleType side) {
105105
return Commands.startEnd(
106-
() -> rumbleController.setRumble(side, 1),
107-
() -> rumbleController.setRumble(side, 0)
108-
);
106+
() -> rumbleController.setRumble(side, 1), () -> rumbleController.setRumble(side, 0));
109107
}
110108

111109
/**

src/main/java/frc/robot/arm/Arm.java

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -66,9 +66,7 @@ public void periodic() {
6666
setpoint =
6767
new ArmState(
6868
ShoulderConstants.MOTION_PROFILE.calculate(
69-
dt,
70-
setpoint.shoulderRotations(),
71-
goal.shoulderRotations()));
69+
dt, setpoint.shoulderRotations(), goal.shoulderRotations()));
7270

7371
shoulder.setSetpoint(
7472
setpoint.shoulderRotations().position, setpoint.shoulderRotations().velocity);
@@ -78,7 +76,10 @@ public void periodic() {
7876
public void addToShuffleboard(ShuffleboardTab tab) {
7977
PositionControllerIO.addToShuffleboard(tab, "Shoulder", shoulderValues);
8078

81-
Telemetry.addColumn(tab, "Setpoint").addDouble("Setpoint (deg)", () -> Units.rotationsToDegrees(setpoint.shoulderRotations().position));
79+
Telemetry.addColumn(tab, "Setpoint")
80+
.addDouble(
81+
"Setpoint (deg)",
82+
() -> Units.rotationsToDegrees(setpoint.shoulderRotations().position));
8283
}
8384

8485
public ArmState getState() {

src/main/java/frc/robot/arm/ArmState.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,6 @@
55
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
66
import edu.wpi.first.math.util.Units;
77
import frc.robot.arm.ArmConstants.ShoulderConstants;
8-
98
import java.util.Objects;
109

1110
public record ArmState(State shoulderRotations) {
@@ -36,6 +35,8 @@ public ArmState(Rotation2d shoulder) {
3635

3736
public boolean at(ArmState other) {
3837
return MathUtil.isNear(
39-
shoulderRotations.position, other.shoulderRotations.position, Units.degreesToRotations(2.0));
38+
shoulderRotations.position,
39+
other.shoulderRotations.position,
40+
Units.degreesToRotations(2.0));
4041
}
4142
}

src/main/java/frc/robot/intake/Intake.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ private boolean frontRollerStuck() {
7777
private boolean backRollerStuck() {
7878
return backRollerValues.motorAmps > BackRollerConstants.NOTE_AMPS;
7979
}
80-
80+
8181
public IntakeState getState() {
8282
return new IntakeState(
8383
frontRollerValues.velocityRotationsPerSecond, backRollerValues.velocityRotationsPerSecond);

src/main/java/frc/robot/intake/IntakeState.java

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,17 +3,18 @@
33
import edu.wpi.first.math.MathUtil;
44
import frc.robot.intake.IntakeConstants.BackRollerConstants;
55
import frc.robot.intake.IntakeConstants.FrontRollerConstants;
6-
76
import java.util.Objects;
87

98
public record IntakeState(
109
double frontRollerVelocityRotationsPerSecond, double backRollerVelocityRotationsPerSecond) {
1110

1211
public static final IntakeState IDLE = new IntakeState(0, 0);
1312

14-
public static final IntakeState INTAKE = new IntakeState(FrontRollerConstants.INTAKE_SPEED, BackRollerConstants.INTAKE_SPEED);
13+
public static final IntakeState INTAKE =
14+
new IntakeState(FrontRollerConstants.INTAKE_SPEED, BackRollerConstants.INTAKE_SPEED);
1515

16-
public static final IntakeState EJECT = new IntakeState(FrontRollerConstants.EJECT_SPEED, BackRollerConstants.EJECT_SPEED);
16+
public static final IntakeState EJECT =
17+
new IntakeState(FrontRollerConstants.EJECT_SPEED, BackRollerConstants.EJECT_SPEED);
1718

1819
public IntakeState {
1920
Objects.requireNonNull(frontRollerVelocityRotationsPerSecond);

src/main/java/frc/robot/shooter/Shooter.java

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -62,8 +62,12 @@ public void periodic() {
6262

6363
setpoint = goal;
6464

65-
double flywheelSetpoint = FlywheelConstants.ACCELERATION_LIMITER.calculate(setpoint.flywheelVelocityRotationsPerSecond());
66-
double serializerSetpoint = SerializerConstants.ACCELERATION_LIMITER.calculate(setpoint.serializerVelocityRotationsPerSecond());
65+
double flywheelSetpoint =
66+
FlywheelConstants.ACCELERATION_LIMITER.calculate(
67+
setpoint.flywheelVelocityRotationsPerSecond());
68+
double serializerSetpoint =
69+
SerializerConstants.ACCELERATION_LIMITER.calculate(
70+
setpoint.serializerVelocityRotationsPerSecond());
6771

6872
flywheel.setSetpoint(flywheelSetpoint);
6973
serializer.setSetpoint(serializerSetpoint);
@@ -77,7 +81,7 @@ public void addToShuffleboard(ShuffleboardTab tab) {
7781

7882
public Trigger serializedNote() {
7983
return new Trigger(() -> serializerValues.motorAmps > SerializerConstants.NOTE_AMPS);
80-
}
84+
}
8185

8286
public ShooterState getState() {
8387
return new ShooterState(

src/main/java/frc/robot/shooter/ShooterConstants.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,8 @@ public static class SerializerConstants {
4545
/** Maximum speed in rotations per second. */
4646
public static final double MAXIMUM_SPEED = 45.319;
4747

48-
public static final SlewRateLimiter ACCELERATION_LIMITER = new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1));
48+
public static final SlewRateLimiter ACCELERATION_LIMITER =
49+
new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1));
4950

5051
public static final double NOTE_AMPS = 20;
5152
}
@@ -88,6 +89,7 @@ public static class FlywheelConstants {
8889
/** Maximum speed in rotations per second. */
8990
public static final double MAXIMUM_SPEED = 60;
9091

91-
public static final SlewRateLimiter ACCELERATION_LIMITER = new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1));
92+
public static final SlewRateLimiter ACCELERATION_LIMITER =
93+
new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1));
9294
}
9395
}

src/main/java/frc/robot/shooter/ShooterState.java

Lines changed: 16 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
import edu.wpi.first.math.MathUtil;
44
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
55
import frc.robot.shooter.ShooterConstants.SerializerConstants;
6-
76
import java.util.Objects;
87

98
public record ShooterState(
@@ -13,27 +12,35 @@ public record ShooterState(
1312

1413
public static final ShooterState INTAKE = new ShooterState(0, SerializerConstants.INTAKE_SPEED);
1514

16-
public static final ShooterState PULL = new ShooterState(FlywheelConstants.PULL_SPEED, SerializerConstants.PULL_SPEED);
15+
public static final ShooterState PULL =
16+
new ShooterState(FlywheelConstants.PULL_SPEED, SerializerConstants.PULL_SPEED);
1717

1818
public static final ShooterState EJECT = new ShooterState(0, SerializerConstants.EJECT_SPEED);
1919

20-
public static final ShooterState SPEAKER_READY = new ShooterState(FlywheelConstants.SPEAKER_SPEED, 0);
20+
public static final ShooterState SPEAKER_READY =
21+
new ShooterState(FlywheelConstants.SPEAKER_SPEED, 0);
2122

22-
public static final ShooterState SPEAKER_SHOOT = new ShooterState(FlywheelConstants.SPEAKER_SPEED, SerializerConstants.FAST_FEED_SPEED);
23+
public static final ShooterState SPEAKER_SHOOT =
24+
new ShooterState(FlywheelConstants.SPEAKER_SPEED, SerializerConstants.FAST_FEED_SPEED);
2325

24-
public static final ShooterState PODIUM_READY = new ShooterState(FlywheelConstants.PODIUM_SPEED, 0);
26+
public static final ShooterState PODIUM_READY =
27+
new ShooterState(FlywheelConstants.PODIUM_SPEED, 0);
2528

26-
public static final ShooterState PODIUM_SHOOT = new ShooterState(FlywheelConstants.PODIUM_SPEED, SerializerConstants.FAST_FEED_SPEED);
29+
public static final ShooterState PODIUM_SHOOT =
30+
new ShooterState(FlywheelConstants.PODIUM_SPEED, SerializerConstants.FAST_FEED_SPEED);
2731

2832
public static final ShooterState LOB_READY = new ShooterState(FlywheelConstants.LOB_SPEED, 0);
2933

30-
public static final ShooterState LOB_SHOOT = new ShooterState(FlywheelConstants.LOB_SPEED, SerializerConstants.FAST_FEED_SPEED);
34+
public static final ShooterState LOB_SHOOT =
35+
new ShooterState(FlywheelConstants.LOB_SPEED, SerializerConstants.FAST_FEED_SPEED);
3136

3237
public static final ShooterState SKIM_READY = new ShooterState(FlywheelConstants.SKIM_SPEED, 0);
3338

34-
public static final ShooterState SKIM_SHOOT = new ShooterState(FlywheelConstants.SKIM_SPEED, SerializerConstants.FAST_FEED_SPEED);
39+
public static final ShooterState SKIM_SHOOT =
40+
new ShooterState(FlywheelConstants.SKIM_SPEED, SerializerConstants.FAST_FEED_SPEED);
3541

36-
public static final ShooterState AMP_SHOOT = new ShooterState(FlywheelConstants.AMP_SPEED, SerializerConstants.SLOW_FEED_SPEED);
42+
public static final ShooterState AMP_SHOOT =
43+
new ShooterState(FlywheelConstants.AMP_SPEED, SerializerConstants.SLOW_FEED_SPEED);
3744

3845
public ShooterState {
3946
Objects.requireNonNull(flywheelVelocityRotationsPerSecond);

src/main/java/frc/robot/superstructure/SuperstructureConstants.java

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,7 @@
22

33
public class SuperstructureConstants {
44

5-
public static final double PULL_DURATION = 0.15;
6-
7-
public static final double EJECT_PAUSE = 0.25;
5+
public static final double PULL_DURATION = 0.15;
86

7+
public static final double EJECT_PAUSE = 0.25;
98
}

0 commit comments

Comments
 (0)