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

Commit

Permalink
idk
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 11, 2024
1 parent 5a6664c commit e9fb11e
Show file tree
Hide file tree
Showing 4 changed files with 16 additions and 11 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public static class ShoulderConstants {
}

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

/** Maximum acceleration of the shoulder in rotations per second per second. */
public static final double MAXIMUM_ACCELERATION =
Expand All @@ -67,6 +67,6 @@ public static class ShoulderConstants {

public static final Rotation2d SKIM = Rotation2d.fromDegrees(30);

public static final Rotation2d AMP = Rotation2d.fromDegrees(60);
public static final Rotation2d AMP = Rotation2d.fromDegrees(80);
}
}
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,9 +62,10 @@ public void periodic() {
setpoint = goal;

double flywheelSetpoint = FlywheelConstants.ACCELERATION_LIMITER.calculate(setpoint.flywheelVelocityRotationsPerSecond());
double serializerSetpoint = SerializerConstants.ACCELERATION_LIMITER.calculate(setpoint.serializerVelocityRotationsPerSecond());

flywheel.setSetpoint(flywheelSetpoint);
serializer.setSetpoint(setpoint.serializerVelocityRotationsPerSecond());
serializer.setSetpoint(serializerSetpoint);
}

@Override
Expand Down
14 changes: 9 additions & 5 deletions src/main/java/frc/robot/shooter/ShooterConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ public static class SerializerConstants {

/** Maximum speed in rotations per second. */
public static final double MAXIMUM_SPEED = 45.319;

public static final SlewRateLimiter ACCELERATION_LIMITER = new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1));
}

/** Constants for the flywheel motor used in the shooter subsystem. */
Expand All @@ -54,7 +56,7 @@ public static class FlywheelConstants {

static {
PIDF.kS = 0.14;
PIDF.kV = 0.2539;
PIDF.kV = 0.1969;
}

/** Flywheel's controller constants. */
Expand All @@ -67,15 +69,17 @@ public static class FlywheelConstants {
CONTROLLER_CONSTANTS.sensorToMechanismRatio = 28.0 / 16.0;
}

public static final double SPEAKER_SPEED = 44;
public static final double PULL_SPEED = -20;

public static final double SPEAKER_SPEED = 60;

public static final double PASS_SPEED = 44;
public static final double PASS_SPEED = 60;

public static final double AMP_SPEED = 20;

/** Maximum speed in rotations per second. */
public static final double MAXIMUM_SPEED = 46.711;
public static final double MAXIMUM_SPEED = 60;

public static final SlewRateLimiter ACCELERATION_LIMITER = new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.25));
public static final SlewRateLimiter ACCELERATION_LIMITER = new SlewRateLimiter(MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.1));
}
}
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/shooter/ShooterState.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ public record ShooterState(

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

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

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

Expand All @@ -34,8 +34,8 @@ public record ShooterState(

public boolean at(ShooterState other) {
return MathUtil.isNear(
flywheelVelocityRotationsPerSecond, other.flywheelVelocityRotationsPerSecond, 2.5)
flywheelVelocityRotationsPerSecond, other.flywheelVelocityRotationsPerSecond, 5)
&& MathUtil.isNear(
serializerVelocityRotationsPerSecond, other.serializerVelocityRotationsPerSecond, 2.5);
serializerVelocityRotationsPerSecond, other.serializerVelocityRotationsPerSecond, 5);
}
}

0 comments on commit e9fb11e

Please sign in to comment.