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

Commit

Permalink
refactor(superstructure): Move speeds and positions to constants.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 9, 2024
1 parent 09f1b6c commit 3c9b273
Show file tree
Hide file tree
Showing 7 changed files with 60 additions and 21 deletions.
13 changes: 13 additions & 0 deletions src/main/java/frc/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.arm;

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

/** Motion profile of the shoulder. */
public static final TrapezoidProfile MOTION_PROFILE = new TrapezoidProfile(CONSTRAINTS);

public static final Rotation2d STOW = Rotation2d.fromDegrees(-25);

public static final Rotation2d SPEAKER = Rotation2d.fromDegrees(-15);

public static final Rotation2d PASS = Rotation2d.fromDegrees(0);

public static final Rotation2d EJECT = Rotation2d.fromDegrees(0);

public static final Rotation2d AMP = Rotation2d.fromDegrees(80);

public static final Rotation2d CLIMB = Rotation2d.fromDegrees(60);
}
}
16 changes: 9 additions & 7 deletions src/main/java/frc/robot/arm/ArmState.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,23 +4,25 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile.State;
import edu.wpi.first.math.util.Units;
import frc.robot.arm.ArmConstants.ShoulderConstants;

import java.util.Objects;

public record ArmState(State shoulderRotations) {

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

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

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

public static final ArmState PASS = new ArmState(Rotation2d.fromDegrees(0));
public static final ArmState PASS = new ArmState(ShoulderConstants.PASS);

public static final ArmState EJECT = new ArmState(Rotation2d.fromDegrees(0));
public static final ArmState EJECT = new ArmState(ShoulderConstants.EJECT);

public static final ArmState AMP = new ArmState(Rotation2d.fromDegrees(80));
public static final ArmState AMP = new ArmState(ShoulderConstants.AMP);

public static final ArmState CLIMB = new ArmState(Rotation2d.fromDegrees(80));
public static final ArmState CLIMB = new ArmState(ShoulderConstants.CLIMB);

public ArmState {
Objects.requireNonNull(shoulderRotations);
Expand Down
10 changes: 7 additions & 3 deletions src/main/java/frc/robot/intake/IntakeConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,11 @@ public static class FrontRollerConstants {
CONTROLLER_CONSTANTS.neutralBrake = true;
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 24.0 / 16.0;
}

public static final double INTAKE_SPEED = 34;

/** Maximum speed of the roller in rotations per second. */
public static final double MAXIMUM_SPEED = 67;
}

/** Constants for the back roller. */
Expand All @@ -52,10 +57,9 @@ public static class BackRollerConstants {
CONTROLLER_CONSTANTS.neutralBrake = true;
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 24.0 / 16.0;
}
}

/** Constants for the roller motor. */
public static class RollerConstants {
public static final double INTAKE_SPEED = 34;

/** Maximum speed of the roller in rotations per second. */
public static final double MAXIMUM_SPEED = 67;
}
Expand Down
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/intake/IntakeState.java
Original file line number Diff line number Diff line change
@@ -1,14 +1,17 @@
package frc.robot.intake;

import edu.wpi.first.math.MathUtil;
import frc.robot.intake.IntakeConstants.BackRollerConstants;
import frc.robot.intake.IntakeConstants.FrontRollerConstants;

import java.util.Objects;

public record IntakeState(
double frontRollerVelocityRotationsPerSecond, double backRollerVelocityRotationsPerSecond) {

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

public static final IntakeState INTAKE = new IntakeState(34, 34);
public static final IntakeState INTAKE = new IntakeState(FrontRollerConstants.INTAKE_SPEED, BackRollerConstants.INTAKE_SPEED);

public IntakeState {
Objects.requireNonNull(frontRollerVelocityRotationsPerSecond);
Expand Down
14 changes: 14 additions & 0 deletions src/main/java/frc/robot/shooter/ShooterConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,14 @@ public static class SerializerConstants {
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 36.0 / 16.0;
}

public static final double INTAKE_SPEED = 34;

public static final double PULL_SPEED = -20;

public static final double EJECT_SPEED = -44;

public static final double FEED_SPEED = 20;

/** Maximum speed in rotations per second. */
public static final double MAXIMUM_SPEED = 45.319;
}
Expand Down Expand Up @@ -57,6 +65,12 @@ public static class FlywheelConstants {
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 36.0 / 16.0;
}

public static final double SPEAKER_SPEED = 44;

public static final double PASS_SPEED = 44;

public static final double AMP_SPEED = 20;

/** Maximum speed in rotations per second. */
public static final double MAXIMUM_SPEED = 46.711;
}
Expand Down
19 changes: 11 additions & 8 deletions src/main/java/frc/robot/shooter/ShooterState.java
Original file line number Diff line number Diff line change
@@ -1,28 +1,31 @@
package frc.robot.shooter;

import edu.wpi.first.math.MathUtil;
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
import frc.robot.shooter.ShooterConstants.SerializerConstants;

import java.util.Objects;

public record ShooterState(
double flywheelVelocityRotationsPerSecond, double serializerVelocityRotationsPerSecond) {

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

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

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

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

public static final ShooterState SPEAKER_READY = new ShooterState(44, 0);
public static final ShooterState SPEAKER_READY = new ShooterState(FlywheelConstants.SPEAKER_SPEED, 0);

public static final ShooterState SPEAKER_SHOOT = new ShooterState(44, 20);
public static final ShooterState SPEAKER_SHOOT = new ShooterState(FlywheelConstants.SPEAKER_SPEED, SerializerConstants.FEED_SPEED);

public static final ShooterState PASS_READY = new ShooterState(44, 0);
public static final ShooterState PASS_READY = new ShooterState(FlywheelConstants.PASS_SPEED, 0);

public static final ShooterState PASS_SHOOT = new ShooterState(44, 20);
public static final ShooterState PASS_SHOOT = new ShooterState(FlywheelConstants.PASS_SPEED, SerializerConstants.FEED_SPEED);

public static final ShooterState AMP_SHOOT = new ShooterState(20, 20);
public static final ShooterState AMP_SHOOT = new ShooterState(FlywheelConstants.AMP_SPEED, SerializerConstants.FEED_SPEED);

public ShooterState {
Objects.requireNonNull(flywheelVelocityRotationsPerSecond);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import edu.wpi.first.wpilibj.util.Color8Bit;
import frc.lib.InterpolatableColor;
import frc.robot.RobotConstants;
import frc.robot.intake.IntakeConstants.RollerConstants;
import frc.robot.intake.IntakeConstants.FrontRollerConstants;
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
import frc.robot.shooter.ShooterConstants.SerializerConstants;

Expand Down Expand Up @@ -161,6 +161,6 @@ public void updateSuperstructure(SuperstructureState state) {
rollers.setColor(
new Color8Bit(
ROLLERS_COLOR.sample(
Math.abs(averageRollerVelocity), 0, RollerConstants.MAXIMUM_SPEED)));
Math.abs(averageRollerVelocity), 0, FrontRollerConstants.MAXIMUM_SPEED)));
}
}

0 comments on commit 3c9b273

Please sign in to comment.