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

Commit

Permalink
feat(arm): Initial re-tune (without shooter).
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 9, 2024
1 parent ff15067 commit 09f1b6c
Show file tree
Hide file tree
Showing 5 changed files with 20 additions and 14 deletions.
8 changes: 7 additions & 1 deletion src/main/java/frc/lib/controller/PositionControllerIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,13 @@ public static class PositionControllerIOConstants {
* Interpret counterclockwise rotation on the motor face as having positive velocity, if set to
* true.
*/
public boolean ccwPositive = true;
public boolean ccwPositiveMotor = true;

/**
* Interpret counterclockwise rotation on the encoder as having positive velocity, if set to
* true.
*/
public boolean ccwPositiveAbsoluteEncoder = true;

/** Use the motor to brake the controlled mechanism on neutral output, if set to true. */
public boolean neutralBrake = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ public void configure(PositionControllerIOConstants constants) {
TalonFXConfiguration motorConfig = new TalonFXConfiguration();

motorConfig.MotorOutput.Inverted =
constants.ccwPositive
constants.ccwPositiveMotor
? InvertedValue.CounterClockwise_Positive
: InvertedValue.Clockwise_Positive;
motorConfig.MotorOutput.NeutralMode =
Expand All @@ -110,7 +110,7 @@ public void configure(PositionControllerIOConstants constants) {

encoderConfig.MagnetSensor.MagnetOffset = constants.absoluteEncoderOffsetRotations;
encoderConfig.MagnetSensor.SensorDirection =
constants.ccwPositive
constants.ccwPositiveAbsoluteEncoder
? SensorDirectionValue.CounterClockwise_Positive
: SensorDirectionValue.Clockwise_Positive;

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,5 +47,5 @@ public enum Subsystem {
EnumSet.of(
Subsystem.ARM, Subsystem.INTAKE, Subsystem.ODOMETRY, Subsystem.SHOOTER, Subsystem.SWERVE);

public static final Set<Subsystem> REAL_SUBSYSTEMS = ALL_SUBSYSTEMS;
public static final Set<Subsystem> REAL_SUBSYSTEMS = EnumSet.of(Subsystem.ARM);
}
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,25 +25,25 @@ public static class ShoulderConstants {

static {
PIDF.kS = 0.14;
PIDF.kG = 0.45;
PIDF.kG = 0.18;
PIDF.kV = 4.0;
PIDF.kP = 20.0;
PIDF.kP = 8.0;
}

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

static {
CONTROLLER_CONSTANTS.ccwPositive = false;
CONTROLLER_CONSTANTS.ccwPositiveMotor = true;
CONTROLLER_CONSTANTS.ccwPositiveAbsoluteEncoder = false;
CONTROLLER_CONSTANTS.neutralBrake = true;
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 39.771428571;
CONTROLLER_CONSTANTS.absoluteEncoderOffsetRotations =
Units.degreesToRotations(-146.77) + Units.degreesToRotations(-27.07);
CONTROLLER_CONSTANTS.absoluteEncoderOffsetRotations = Units.degreesToRotations(-173.135);
}

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

/** Maximum acceleration of the shoulder in rotations per second per second. */
public static final double MAXIMUM_ACCELERATION =
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/arm/ArmState.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,19 +8,19 @@

public record ArmState(State shoulderRotations) {

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

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

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

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

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

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

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

public ArmState {
Objects.requireNonNull(shoulderRotations);
Expand Down

0 comments on commit 09f1b6c

Please sign in to comment.