Skip to content
This repository has been archived by the owner on Jan 2, 2025. It is now read-only.

Commit

Permalink
update deps + calibrate shooter
Browse files Browse the repository at this point in the history
  • Loading branch information
jack60612 committed Feb 22, 2024
1 parent b68d719 commit 842973f
Show file tree
Hide file tree
Showing 4 changed files with 15 additions and 14 deletions.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,8 @@ public static final class CANConstants {
// Digital Ports

// Shooter Speeds (M/s)
public static final double SHOOTERSOURCE = -5.0;
public static final double SHOOTERAMP = 3.0;
public static final double SHOOTERSPEAKER = 5.0;
public static final double SHOOTERDEFAULT = 5.0;
public static final double SHOOTERSOURCE = -20.0;
public static final double SHOOTERAMP = 20.0;
public static final double SHOOTERSPEAKER = 8.0;
public static final double SHOOTERDEFAULT = 8.0;
}
1 change: 1 addition & 0 deletions src/main/java/frc/robot/commands/ShooterCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ public void execute() {
@Override
public void end(boolean interrupted) {
m_shooterState.shooting = false;
m_shooterSubsystem.StopShooter();
}

// Returns true when the command should end.
Expand Down
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,16 @@ public class ShooterSubsystem extends SubsystemBase {
// general drive constants
// https://www.chiefdelphi.com/t/encoders-velocity-to-m-s/390332/2
// https://sciencing.com/convert-rpm-linear-speed-8232280.html
private final double kWheelDiameter = Units.inchesToMeters(6); // meters
private final double kWheelDiameter = Units.inchesToMeters(4); // meters
private final double kGearRatio = 4; // TBD
// basically converted from rotations to to radians to then meters using the wheel diameter.
// the diameter is already *2 so we don't need to multiply by 2 again.
private final double kVelocityConversionRatio = (Math.PI * kWheelDiameter) / kGearRatio / 60;

// setup feedforward
private final double ksShooterVolts = 0.0;
private final double kvDriveVoltSecondsPerMeter = 0.0;
private final double kaDriveVoltSecondsSquaredPerMeter = 0.0;
private final double ksShooterVolts = 0.17875;
private final double kvDriveVoltSecondsPerMeter = 1.5442;
private final double kaDriveVoltSecondsSquaredPerMeter = 0.019079;

SimpleMotorFeedforward m_shooterFeedForward =
new SimpleMotorFeedforward(
Expand Down Expand Up @@ -65,7 +65,7 @@ public ShooterSubsystem() {
m_ShooterMainEncoder = m_ShooterMotorMain.getEncoder();
m_ShooterMainEncoder.setVelocityConversionFactor(kVelocityConversionRatio);
// PID coefficients
kP = 6e-5;
kP = 0.00032423;
kI = 0;
kD = 0;
kIz = 0;
Expand Down
10 changes: 5 additions & 5 deletions vendordeps/photonlib.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "photonlib.json",
"name": "photonlib",
"version": "v2024.2.4",
"version": "v2024.2.6",
"uuid": "515fe07e-bfc6-11fa-b3de-0242ac130004",
"frcYear": "2024",
"mavenUrls": [
Expand All @@ -14,7 +14,7 @@
{
"groupId": "org.photonvision",
"artifactId": "photonlib-cpp",
"version": "v2024.2.4",
"version": "v2024.2.6",
"libName": "photonlib",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -29,7 +29,7 @@
{
"groupId": "org.photonvision",
"artifactId": "photontargeting-cpp",
"version": "v2024.2.4",
"version": "v2024.2.6",
"libName": "photontargeting",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -46,12 +46,12 @@
{
"groupId": "org.photonvision",
"artifactId": "photonlib-java",
"version": "v2024.2.4"
"version": "v2024.2.6"
},
{
"groupId": "org.photonvision",
"artifactId": "photontargeting-java",
"version": "v2024.2.4"
"version": "v2024.2.6"
}
]
}

0 comments on commit 842973f

Please sign in to comment.