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

Commit 3c9b273

Browse files
committed
refactor(superstructure): Move speeds and positions to constants.
1 parent 09f1b6c commit 3c9b273

File tree

7 files changed

+60
-21
lines changed

7 files changed

+60
-21
lines changed

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

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

3+
import edu.wpi.first.math.geometry.Rotation2d;
34
import edu.wpi.first.math.trajectory.TrapezoidProfile;
45
import edu.wpi.first.math.util.Units;
56
import frc.lib.CAN;
@@ -55,5 +56,17 @@ public static class ShoulderConstants {
5556

5657
/** Motion profile of the shoulder. */
5758
public static final TrapezoidProfile MOTION_PROFILE = new TrapezoidProfile(CONSTRAINTS);
59+
60+
public static final Rotation2d STOW = Rotation2d.fromDegrees(-25);
61+
62+
public static final Rotation2d SPEAKER = Rotation2d.fromDegrees(-15);
63+
64+
public static final Rotation2d PASS = Rotation2d.fromDegrees(0);
65+
66+
public static final Rotation2d EJECT = Rotation2d.fromDegrees(0);
67+
68+
public static final Rotation2d AMP = Rotation2d.fromDegrees(80);
69+
70+
public static final Rotation2d CLIMB = Rotation2d.fromDegrees(60);
5871
}
5972
}

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

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -4,23 +4,25 @@
44
import edu.wpi.first.math.geometry.Rotation2d;
55
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
66
import edu.wpi.first.math.util.Units;
7+
import frc.robot.arm.ArmConstants.ShoulderConstants;
8+
79
import java.util.Objects;
810

911
public record ArmState(State shoulderRotations) {
1012

11-
public static final ArmState INITIAL = new ArmState(Rotation2d.fromDegrees(-25));
13+
public static final ArmState INITIAL = new ArmState(ShoulderConstants.STOW);
1214

13-
public static final ArmState STOW = new ArmState(Rotation2d.fromDegrees(-25));
15+
public static final ArmState STOW = new ArmState(ShoulderConstants.STOW);
1416

15-
public static final ArmState SPEAKER = new ArmState(Rotation2d.fromDegrees(-15));
17+
public static final ArmState SPEAKER = new ArmState(ShoulderConstants.SPEAKER);
1618

17-
public static final ArmState PASS = new ArmState(Rotation2d.fromDegrees(0));
19+
public static final ArmState PASS = new ArmState(ShoulderConstants.PASS);
1820

19-
public static final ArmState EJECT = new ArmState(Rotation2d.fromDegrees(0));
21+
public static final ArmState EJECT = new ArmState(ShoulderConstants.EJECT);
2022

21-
public static final ArmState AMP = new ArmState(Rotation2d.fromDegrees(80));
23+
public static final ArmState AMP = new ArmState(ShoulderConstants.AMP);
2224

23-
public static final ArmState CLIMB = new ArmState(Rotation2d.fromDegrees(80));
25+
public static final ArmState CLIMB = new ArmState(ShoulderConstants.CLIMB);
2426

2527
public ArmState {
2628
Objects.requireNonNull(shoulderRotations);

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

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,11 @@ public static class FrontRollerConstants {
2828
CONTROLLER_CONSTANTS.neutralBrake = true;
2929
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 24.0 / 16.0;
3030
}
31+
32+
public static final double INTAKE_SPEED = 34;
33+
34+
/** Maximum speed of the roller in rotations per second. */
35+
public static final double MAXIMUM_SPEED = 67;
3136
}
3237

3338
/** Constants for the back roller. */
@@ -52,10 +57,9 @@ public static class BackRollerConstants {
5257
CONTROLLER_CONSTANTS.neutralBrake = true;
5358
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 24.0 / 16.0;
5459
}
55-
}
5660

57-
/** Constants for the roller motor. */
58-
public static class RollerConstants {
61+
public static final double INTAKE_SPEED = 34;
62+
5963
/** Maximum speed of the roller in rotations per second. */
6064
public static final double MAXIMUM_SPEED = 67;
6165
}

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

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,17 @@
11
package frc.robot.intake;
22

33
import edu.wpi.first.math.MathUtil;
4+
import frc.robot.intake.IntakeConstants.BackRollerConstants;
5+
import frc.robot.intake.IntakeConstants.FrontRollerConstants;
6+
47
import java.util.Objects;
58

69
public record IntakeState(
710
double frontRollerVelocityRotationsPerSecond, double backRollerVelocityRotationsPerSecond) {
811

912
public static final IntakeState IDLE = new IntakeState(0, 0);
1013

11-
public static final IntakeState INTAKE = new IntakeState(34, 34);
14+
public static final IntakeState INTAKE = new IntakeState(FrontRollerConstants.INTAKE_SPEED, BackRollerConstants.INTAKE_SPEED);
1215

1316
public IntakeState {
1417
Objects.requireNonNull(frontRollerVelocityRotationsPerSecond);

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

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,14 @@ public static class SerializerConstants {
3030
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 36.0 / 16.0;
3131
}
3232

33+
public static final double INTAKE_SPEED = 34;
34+
35+
public static final double PULL_SPEED = -20;
36+
37+
public static final double EJECT_SPEED = -44;
38+
39+
public static final double FEED_SPEED = 20;
40+
3341
/** Maximum speed in rotations per second. */
3442
public static final double MAXIMUM_SPEED = 45.319;
3543
}
@@ -57,6 +65,12 @@ public static class FlywheelConstants {
5765
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 36.0 / 16.0;
5866
}
5967

68+
public static final double SPEAKER_SPEED = 44;
69+
70+
public static final double PASS_SPEED = 44;
71+
72+
public static final double AMP_SPEED = 20;
73+
6074
/** Maximum speed in rotations per second. */
6175
public static final double MAXIMUM_SPEED = 46.711;
6276
}

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

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,28 +1,31 @@
11
package frc.robot.shooter;
22

33
import edu.wpi.first.math.MathUtil;
4+
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
5+
import frc.robot.shooter.ShooterConstants.SerializerConstants;
6+
47
import java.util.Objects;
58

69
public record ShooterState(
710
double flywheelVelocityRotationsPerSecond, double serializerVelocityRotationsPerSecond) {
811

912
public static final ShooterState IDLE = new ShooterState(0, 0);
1013

11-
public static final ShooterState INTAKE = new ShooterState(0, 34);
14+
public static final ShooterState INTAKE = new ShooterState(0, SerializerConstants.INTAKE_SPEED);
1215

13-
public static final ShooterState PULL = new ShooterState(0, -20);
16+
public static final ShooterState PULL = new ShooterState(0, SerializerConstants.PULL_SPEED);
1417

15-
public static final ShooterState EJECT = new ShooterState(0, -44);
18+
public static final ShooterState EJECT = new ShooterState(0, SerializerConstants.EJECT_SPEED);
1619

17-
public static final ShooterState SPEAKER_READY = new ShooterState(44, 0);
20+
public static final ShooterState SPEAKER_READY = new ShooterState(FlywheelConstants.SPEAKER_SPEED, 0);
1821

19-
public static final ShooterState SPEAKER_SHOOT = new ShooterState(44, 20);
22+
public static final ShooterState SPEAKER_SHOOT = new ShooterState(FlywheelConstants.SPEAKER_SPEED, SerializerConstants.FEED_SPEED);
2023

21-
public static final ShooterState PASS_READY = new ShooterState(44, 0);
24+
public static final ShooterState PASS_READY = new ShooterState(FlywheelConstants.PASS_SPEED, 0);
2225

23-
public static final ShooterState PASS_SHOOT = new ShooterState(44, 20);
26+
public static final ShooterState PASS_SHOOT = new ShooterState(FlywheelConstants.PASS_SPEED, SerializerConstants.FEED_SPEED);
2427

25-
public static final ShooterState AMP_SHOOT = new ShooterState(20, 20);
28+
public static final ShooterState AMP_SHOOT = new ShooterState(FlywheelConstants.AMP_SPEED, SerializerConstants.FEED_SPEED);
2629

2730
public ShooterState {
2831
Objects.requireNonNull(flywheelVelocityRotationsPerSecond);

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@
1010
import edu.wpi.first.wpilibj.util.Color8Bit;
1111
import frc.lib.InterpolatableColor;
1212
import frc.robot.RobotConstants;
13-
import frc.robot.intake.IntakeConstants.RollerConstants;
13+
import frc.robot.intake.IntakeConstants.FrontRollerConstants;
1414
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
1515
import frc.robot.shooter.ShooterConstants.SerializerConstants;
1616

@@ -161,6 +161,6 @@ public void updateSuperstructure(SuperstructureState state) {
161161
rollers.setColor(
162162
new Color8Bit(
163163
ROLLERS_COLOR.sample(
164-
Math.abs(averageRollerVelocity), 0, RollerConstants.MAXIMUM_SPEED)));
164+
Math.abs(averageRollerVelocity), 0, FrontRollerConstants.MAXIMUM_SPEED)));
165165
}
166166
}

0 commit comments

Comments
 (0)