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

Commit 19bab75

Browse files
committed
Merge branch '4_7_2024_refactor' of https://github.com/Gongoliers/Robot2024 into 4_7_2024_refactor
2 parents d0a74bc + 3fa5ec7 commit 19bab75

12 files changed

+97
-36
lines changed

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

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,13 @@ public static class PositionControllerIOConstants {
1414
* Interpret counterclockwise rotation on the motor face as having positive velocity, if set to
1515
* true.
1616
*/
17-
public boolean ccwPositive = true;
17+
public boolean ccwPositiveMotor = true;
18+
19+
/**
20+
* Interpret counterclockwise rotation on the encoder as having positive velocity, if set to
21+
* true.
22+
*/
23+
public boolean ccwPositiveAbsoluteEncoder = true;
1824

1925
/** Use the motor to brake the controlled mechanism on neutral output, if set to true. */
2026
public boolean neutralBrake = false;

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,7 @@ public void configure(PositionControllerIOConstants constants) {
8383
TalonFXConfiguration motorConfig = new TalonFXConfiguration();
8484

8585
motorConfig.MotorOutput.Inverted =
86-
constants.ccwPositive
86+
constants.ccwPositiveMotor
8787
? InvertedValue.CounterClockwise_Positive
8888
: InvertedValue.Clockwise_Positive;
8989
motorConfig.MotorOutput.NeutralMode =
@@ -110,7 +110,7 @@ public void configure(PositionControllerIOConstants constants) {
110110

111111
encoderConfig.MagnetSensor.MagnetOffset = constants.absoluteEncoderOffsetRotations;
112112
encoderConfig.MagnetSensor.SensorDirection =
113-
constants.ccwPositive
113+
constants.ccwPositiveAbsoluteEncoder
114114
? SensorDirectionValue.CounterClockwise_Positive
115115
: SensorDirectionValue.Clockwise_Positive;
116116

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

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,16 @@ public static void addToShuffleboard(
5757
velocityController.addDouble(
5858
"Acceleration (dpsps)",
5959
() -> Units.rotationsToDegrees(values.accelerationRotationsPerSecondPerSecond));
60+
velocityController.addDouble(
61+
"Velocity (rps)", () -> values.velocityRotationsPerSecond);
62+
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);
6070
velocityController.addDouble("Voltage (V)", () -> values.motorVolts);
6171
velocityController.addDouble("Current (A)", () -> values.motorAmps);
6272
}

src/main/java/frc/robot/RobotConstants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,5 +47,5 @@ public enum Subsystem {
4747
EnumSet.of(
4848
Subsystem.ARM, Subsystem.INTAKE, Subsystem.ODOMETRY, Subsystem.SHOOTER, Subsystem.SWERVE);
4949

50-
public static final Set<Subsystem> REAL_SUBSYSTEMS = ALL_SUBSYSTEMS;
50+
public static final Set<Subsystem> REAL_SUBSYSTEMS = EnumSet.of(Subsystem.INTAKE);
5151
}

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

Lines changed: 19 additions & 6 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;
@@ -25,25 +26,25 @@ public static class ShoulderConstants {
2526

2627
static {
2728
PIDF.kS = 0.14;
28-
PIDF.kG = 0.45;
29+
PIDF.kG = 0.18;
2930
PIDF.kV = 4.0;
30-
PIDF.kP = 20.0;
31+
PIDF.kP = 8.0;
3132
}
3233

3334
/** Shoulder's controller constants. */
3435
public static final PositionControllerIOConstants CONTROLLER_CONSTANTS =
3536
new PositionControllerIOConstants();
3637

3738
static {
38-
CONTROLLER_CONSTANTS.ccwPositive = false;
39+
CONTROLLER_CONSTANTS.ccwPositiveMotor = true;
40+
CONTROLLER_CONSTANTS.ccwPositiveAbsoluteEncoder = false;
3941
CONTROLLER_CONSTANTS.neutralBrake = true;
4042
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 39.771428571;
41-
CONTROLLER_CONSTANTS.absoluteEncoderOffsetRotations =
42-
Units.degreesToRotations(-146.77) + Units.degreesToRotations(-27.07);
43+
CONTROLLER_CONSTANTS.absoluteEncoderOffsetRotations = Units.degreesToRotations(-173.135);
4344
}
4445

4546
/** Maximum speed of the shoulder in rotations per second. */
46-
public static final double MAXIMUM_SPEED = Units.degreesToRotations(60.0);
47+
public static final double MAXIMUM_SPEED = Units.degreesToRotations(120.0);
4748

4849
/** Maximum acceleration of the shoulder in rotations per second per second. */
4950
public static final double MAXIMUM_ACCELERATION =
@@ -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(-26.45));
13+
public static final ArmState INITIAL = new ArmState(ShoulderConstants.STOW);
1214

13-
public static final ArmState STOW = new ArmState(Rotation2d.fromDegrees(-26.45));
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(90));
23+
public static final ArmState AMP = new ArmState(ShoulderConstants.AMP);
2224

23-
public static final ArmState CLIMB = new ArmState(Rotation2d.fromDegrees(90));
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: 12 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ public static class FrontRollerConstants {
1717
static {
1818
PIDF.kS = 0.13;
1919
PIDF.kV = 0.1683;
20+
PIDF.kP = 0.1;
2021
}
2122

2223
/** Front roller's controller constants. */
@@ -25,22 +26,28 @@ public static class FrontRollerConstants {
2526

2627
static {
2728
CONTROLLER_CONSTANTS.ccwPositive = false;
28-
CONTROLLER_CONSTANTS.neutralBrake = true;
29+
CONTROLLER_CONSTANTS.neutralBrake = false;
2930
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 24.0 / 16.0;
3031
}
32+
33+
public static final double INTAKE_SPEED = 34;
34+
35+
/** Maximum speed of the roller in rotations per second. */
36+
public static final double MAXIMUM_SPEED = 67;
3137
}
3238

3339
/** Constants for the back roller. */
3440
public static class BackRollerConstants {
3541
/** Back roller's CAN. */
36-
public static final CAN CAN = new CAN(50);
42+
public static final CAN CAN = new CAN(40);
3743

3844
/** Back roller's PIDF constants. */
3945
public static final PIDFConstants PIDF = new PIDFConstants();
4046

4147
static {
4248
PIDF.kS = 0.13;
4349
PIDF.kV = 0.1759;
50+
PIDF.kP = 0.1;
4451
}
4552

4653
/** Back roller's controller constants. */
@@ -49,13 +56,12 @@ public static class BackRollerConstants {
4956

5057
static {
5158
CONTROLLER_CONSTANTS.ccwPositive = false;
52-
CONTROLLER_CONSTANTS.neutralBrake = true;
59+
CONTROLLER_CONSTANTS.neutralBrake = false;
5360
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 24.0 / 16.0;
5461
}
55-
}
5662

57-
/** Constants for the roller motor. */
58-
public static class RollerConstants {
63+
public static final double INTAKE_SPEED = 34;
64+
5965
/** Maximum speed of the roller in rotations per second. */
6066
public static final double MAXIMUM_SPEED = 67;
6167
}

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

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,22 +1,25 @@
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);
1518
Objects.requireNonNull(backRollerVelocityRotationsPerSecond);
1619
}
1720

1821
public boolean at(IntakeState other) {
19-
final double kToleranceRotationsPerSecond = 2.5;
22+
final double kToleranceRotationsPerSecond = 1;
2023

2124
return MathUtil.isNear(
2225
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 = 28.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/Superstructure.java

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,8 +65,12 @@ public void addToShuffleboard(ShuffleboardTab tab) {
6565
ShuffleboardLayout state = Telemetry.addColumn(tab, "State");
6666

6767
state.addString(
68-
"Running Command",
68+
"State",
6969
() -> this.getCurrentCommand() != null ? this.getCurrentCommand().getName() : "NONE");
70+
71+
ShuffleboardLayout at = Telemetry.addColumn(tab, "At Goal?");
72+
73+
at.addBoolean("At Goal?", () -> at(goal));
7074
}
7175

7276
private void addStateToShuffleboard(

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)