From 8366522decd5e2676545e6567087bcbb79c6cd0f Mon Sep 17 00:00:00 2001 From: apoorva <97716935+carokhan@users.noreply.github.com> Date: Thu, 24 Oct 2024 08:07:34 -0400 Subject: [PATCH] idiot --- src/main/java/frc/robot/BuildConstants.java | 10 +++++----- src/main/java/frc/robot/Constants.java | 6 +++--- src/main/java/frc/robot/subsystems/pivot2/Pivot.java | 8 +++++--- 3 files changed, 13 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/BuildConstants.java b/src/main/java/frc/robot/BuildConstants.java index 7f69548..4de55d7 100644 --- a/src/main/java/frc/robot/BuildConstants.java +++ b/src/main/java/frc/robot/BuildConstants.java @@ -5,12 +5,12 @@ public final class BuildConstants { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "Forte-2-5"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 89; - public static final String GIT_SHA = "5eb048c58fec65b3f00463e715a48f1dd720a332"; - public static final String GIT_DATE = "2024-10-23 06:52:00 EDT"; + public static final int GIT_REVISION = 90; + public static final String GIT_SHA = "0633ff8fb4db72688603eca20c002bee66f45e75"; + public static final String GIT_DATE = "2024-10-23 19:32:07 EDT"; public static final String GIT_BRANCH = "main"; - public static final String BUILD_DATE = "2024-10-23 19:29:37 EDT"; - public static final long BUILD_UNIX_TIME = 1729726177390L; + public static final String BUILD_DATE = "2024-10-24 07:54:58 EDT"; + public static final long BUILD_UNIX_TIME = 1729770898939L; public static final int DIRTY = 1; private BuildConstants() {} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 6dfbf38..35a847b 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -281,8 +281,8 @@ public static class ShooterConstants { public static final int pivotCurrentLimit = 15; - public static final double kGPivot = 0.38; - public static final double kVPivot = 0.8; + public static final double kGPivot = 0.381640625; + public static final double kVPivot = 0.875; public static final double kAPivot = 0.00; public static final double kVShooter = 0.0055; // COMP: 0.0055, DEMO: 0.0041875 @@ -292,7 +292,7 @@ public static class ShooterConstants { public static final double kIShooterReal = 0.00000; public static final double kSShooterReal = 0; - public static final double kPPivot = 3.0; + public static final double kPPivot = 2.0; public static final double kPShooterSim = 0.5; public static final double kIShooterSim = 0.0; diff --git a/src/main/java/frc/robot/subsystems/pivot2/Pivot.java b/src/main/java/frc/robot/subsystems/pivot2/Pivot.java index 42c7d32..0923ed3 100644 --- a/src/main/java/frc/robot/subsystems/pivot2/Pivot.java +++ b/src/main/java/frc/robot/subsystems/pivot2/Pivot.java @@ -62,9 +62,11 @@ public Command setPivotTarget(DoubleSupplier radians) { return this.run( () -> { double volts = - pivotPID.calculate(inputs.pivotPosition.getRadians(), radians.getAsDouble()); - // + pivotFF.calculate( - // pivotPID.getSetpoint().position, pivotPID.getSetpoint().velocity); + pivotPID.calculate( + inputs.pivotPosition.getRadians(), + radians.getAsDouble() + + pivotFF.calculate( + pivotPID.getSetpoint().position, pivotPID.getSetpoint().velocity)); io.setPivotVoltage(volts); inputs.pivotAppliedVolts = volts;