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

Commit

Permalink
refactor: Extract constants.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Mar 5, 2024
1 parent dd550c3 commit 04310aa
Show file tree
Hide file tree
Showing 7 changed files with 14 additions and 41 deletions.
4 changes: 4 additions & 0 deletions src/main/java/frc/lib/SingleJointedArmFeedforward.java
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,10 @@ public SingleJointedArmFeedforwardConstants withKa(double kA) {

private final SingleJointedArmFeedforwardConstants constants;

public SingleJointedArmFeedforward() {
this.constants = new SingleJointedArmFeedforwardConstants();
}

public SingleJointedArmFeedforward(SingleJointedArmFeedforwardConstants constants) {
this.constants = constants;
}
Expand Down
16 changes: 0 additions & 16 deletions src/main/java/frc/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import frc.lib.CAN;
import frc.lib.JointConstants;
import frc.lib.MotionProfileCalculator;

Expand All @@ -14,9 +13,6 @@ public class ArmConstants {

/** Constants for the shoulder motor. */
public static class ShoulderMotorConstants {
/** Shoulder motor CAN. */
public static final CAN CAN = new CAN(2);

/** Joint constants for the shoulder joint. */
public static final JointConstants JOINT_CONSTANTS =
new JointConstants(
Expand All @@ -41,9 +37,6 @@ public static class ShoulderMotorConstants {
public static final Translation2d SHOULDER_TO_ORIGIN =
new Translation2d(Units.inchesToMeters(-11.361), Units.inchesToMeters(7.721));

/** Proportional gain in volts per rotation. */
public static final double KP = 36.0;

/** Maximum speed of the shoulder joint in rotations per second. */
public static final double MAXIMUM_SPEED = 0.5;

Expand All @@ -61,12 +54,6 @@ public static class ShoulderMotorConstants {

/** Constants for the wrist motor. */
public static class WristMotorConstants {
/** Wrist motor CAN. */
public static final CAN CAN = new CAN(1);

/** If true, invert the motor. */
public static final boolean MOTOR_INVERT = true;

/** Joint constants for the wrist joint. */
public static final JointConstants JOINT_CONSTANTS =
new JointConstants(
Expand All @@ -87,9 +74,6 @@ public static class WristMotorConstants {
/** Tolerance of the wrist joint. */
public static final Rotation2d TOLERANCE = Rotation2d.fromDegrees(5.0);

/** Proportional gain in volts per rotation. */
public static final double KP = 36.0;

/** Maximum speed of the wrist joint in rotations per second. */
public static final double MAXIMUM_SPEED = 1.2;

Expand Down
7 changes: 3 additions & 4 deletions src/main/java/frc/robot/arm/ShoulderMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import frc.lib.AccelerationCalculator;
import frc.lib.Configurator;
import frc.lib.SingleJointedArmFeedforward;
import frc.lib.SingleJointedArmFeedforward.SingleJointedArmFeedforwardConstants;
import frc.robot.arm.ArmConstants.ShoulderMotorConstants;

/** Shoulder motor using a Spark Max. */
Expand All @@ -27,11 +26,11 @@ public class ShoulderMotorIOSparkMax implements ShoulderMotorIO {

/** Creates a new shoulder motor using a Spark Max. */
public ShoulderMotorIOSparkMax() {
sparkMax = new CANSparkMax(ShoulderMotorConstants.CAN.id(), MotorType.kBrushless);
sparkMax = new CANSparkMax(2, MotorType.kBrushless);

feedback = new PIDController(ShoulderMotorConstants.KP, 0, 0);
feedback = new PIDController(36.0, 0, 0);

feedforward = new SingleJointedArmFeedforward(new SingleJointedArmFeedforwardConstants());
feedforward = new SingleJointedArmFeedforward();

accelerationCalculator = new AccelerationCalculator();
}
Expand Down
7 changes: 3 additions & 4 deletions src/main/java/frc/robot/arm/WristMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import frc.lib.AccelerationCalculator;
import frc.lib.Configurator;
import frc.lib.SingleJointedArmFeedforward;
import frc.lib.SingleJointedArmFeedforward.SingleJointedArmFeedforwardConstants;
import frc.robot.arm.ArmConstants.WristMotorConstants;

public class WristMotorIOSparkMax implements WristMotorIO {
Expand All @@ -27,9 +26,9 @@ public WristMotorIOSparkMax() {
// TODO Temporary fix, using one of the climber Sparks
sparkMax = new CANSparkMax(6, MotorType.kBrushless);

feedback = new PIDController(WristMotorConstants.KP, 0, 0);
feedback = new PIDController(36.0, 0, 0);

feedforward = new SingleJointedArmFeedforward(new SingleJointedArmFeedforwardConstants());
feedforward = new SingleJointedArmFeedforward();

accelerationCalculator = new AccelerationCalculator();
}
Expand All @@ -38,7 +37,7 @@ public WristMotorIOSparkMax() {
public void configure() {
Configurator.configureREV(sparkMax::restoreFactoryDefaults);

sparkMax.setInverted(WristMotorConstants.MOTOR_INVERT);
sparkMax.setInverted(true);

Configurator.configureREV(() -> sparkMax.setIdleMode(IdleMode.kBrake));

Expand Down
13 changes: 0 additions & 13 deletions src/main/java/frc/robot/intake/IntakeConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
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;
import frc.lib.MotionProfileCalculator;
import frc.lib.MotorCurrentLimits;

Expand All @@ -12,9 +11,6 @@ public class IntakeConstants {

/** Constants for the pivot motor. */
public static class PivotMotorConstants {
/** Pivot motor's CAN identifier. */
public static final CAN CAN = new CAN(8);

/** If true, invert the pivot motor. */
public static final boolean IS_MOTOR_INVERTED = false;

Expand Down Expand Up @@ -58,19 +54,10 @@ public static class PivotMotorConstants {

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

/** Proportional gain of the arm in volts per rotation. */
public static final double KP = 16.0;
}

/** Constants for the roller motor. */
public static class RollerMotorConstants {
/** Roller motor's CAN identifier. */
public static final CAN CAN = new CAN(5);

/** If true, invert the roller motor. */
public static final boolean IS_INVERTED = false;

/** Gearing between the roller motor and the rollers. */
public static final double GEARING = 4.5;

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/intake/PivotMotorIOTalonSRX.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,9 @@ public class PivotMotorIOTalonSRX implements PivotMotorIO {
private final SingleJointedArmFeedforward feedforward;

public PivotMotorIOTalonSRX() {
talonSRX = new TalonSRX(PivotMotorConstants.CAN.id());
talonSRX = new TalonSRX(8);

feedback = new PIDController(PivotMotorConstants.KP, 0, 0);
feedback = new PIDController(16.0, 0, 0);

SingleJointedArmFeedforwardConstants constants =
new SingleJointedArmFeedforwardConstants().withKg(Rotation2d.fromDegrees((26)), 1.8);
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/intake/RollerMotorIOSparkMax.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ public class RollerMotorIOSparkMax implements RollerMotorIO {
private final CANSparkMax sparkMax;

public RollerMotorIOSparkMax() {
sparkMax = new CANSparkMax(RollerMotorConstants.CAN.id(), MotorType.kBrushless);
sparkMax = new CANSparkMax(5, MotorType.kBrushless);
}

@Override
public void configure() {
Configurator.configureREV(sparkMax::restoreFactoryDefaults);

sparkMax.setInverted(RollerMotorConstants.IS_INVERTED);
sparkMax.setInverted(false);

Configurator.configureREV(
() ->
Expand Down

0 comments on commit 04310aa

Please sign in to comment.