]> git.taranathan.com Git - FRC2026.git/commitdiff
new interpolation map with hood extension
authorWesleyWong-972 <wesleycwong@gmail.com>
Sat, 18 Apr 2026 18:54:24 +0000 (11:54 -0700)
committerWesleyWong-972 <wesleycwong@gmail.com>
Sat, 18 Apr 2026 18:54:24 +0000 (11:54 -0700)
src/main/java/frc/robot/constants/ShotInterpolation.java
src/main/java/frc/robot/subsystems/Intake/Intake.java
src/main/java/frc/robot/subsystems/hood/Hood.java
src/main/java/frc/robot/subsystems/hood/HoodConstants.java
src/main/java/frc/robot/subsystems/shooter/Shooter.java

index 84e86d9c242535f6ef6e1e781ac897ee066cf91a..c7301b7ceb338fe6266398c1017a4e6f702afdd4 100644 (file)
@@ -44,25 +44,24 @@ public class ShotInterpolation {
         exitVelocityMap.put(25.0, 25.0* 3.2);
 
         // currently regresses to y = 1.34959x + 9.79618
-        shooterVelocityMap.put(0.0, 9.55);
-        shooterVelocityMap.put(1.00, 11.5);
-        shooterVelocityMap.put(2.00, 12.3);
-        shooterVelocityMap.put(3.00, 14.0);
-        shooterVelocityMap.put(4.00, 15.5);
-        shooterVelocityMap.put(5.00, 17.0);
-        shooterVelocityMap.put(5.60, 18.0);
-        shooterVelocityMap.put(25.0, 43.44);
+        shooterVelocityMap.put(0.0, 9.55 * 1.05);
+        shooterVelocityMap.put(1.00, 11.5 * 1.05);
+        shooterVelocityMap.put(2.00, 12.3 * 1.1);
+        shooterVelocityMap.put(3.00, 14.0 * 1.075);
+        shooterVelocityMap.put(4.00, 15.5 * 1.075);
+        shooterVelocityMap.put(5.00, 17.0 * 1.05);
+        shooterVelocityMap.put(5.60, 18.0 * 1.05);
+        shooterVelocityMap.put(25.0, 43.44 * 1.05);
 
-        newHoodMap.put(1.00, 78.0);
-        newHoodMap.put(1.49, 72.0);
-        newHoodMap.put(2.09, 70.0);
-        newHoodMap.put(2.95, 68.0);
-        newHoodMap.put(5.05, 60.0);
-        newHoodMap.put(5.79, 59.0);
-        newHoodMap.put(4.07, 65.0);
 
         newHoodMap.put(0.0, 75.9);
+        newHoodMap.put(1.00, 78.0);
+        newHoodMap.put(1.49, 72.0 - 2.0 - 1.0);
+        newHoodMap.put(2.09, 70.0 - 4.0 - 2.0);
+        newHoodMap.put(2.95, 68.0 - 4.0 - 2.0);
+        newHoodMap.put(4.07, 65.0 - 3.0 - 2.0);
+        newHoodMap.put(5.05, 60.0 - 1.0 - 1.0);
+        newHoodMap.put(5.79, 59.0 - 2.0);
         newHoodMap.put(27.99, 0.0);
-
     }
 }
index d373bb90612707014a3c430c98e1972dcd494699..12d4ab33c2b05807b48e022ea29932366eb59393 100644 (file)
@@ -110,7 +110,7 @@ public class Intake extends SubsystemBase implements IntakeIO{
 
         // config Slot 0 PID params
         var rollerSlot0Configs = config.Slot0;
-        rollerSlot0Configs.kP = 5.0;
+        rollerSlot0Configs.kP = 0.5;
         rollerSlot0Configs.kI = 0.0;
         rollerSlot0Configs.kD = 0.0;
         rollerSlot0Configs.kV = 0.0;
index e0b8bdda4a58be8771689becd0f32936a2f5d904..15cfe5bb63cc82b679583bdc039b30013bd2ea5c 100644 (file)
@@ -116,6 +116,7 @@ public class Hood extends SubsystemBase implements HoodIO {
                        goalVelocityRadPerSec = 0.0;
                }
 
+
                double setpointRad = goalAngle.getRadians();
 
         // calculate shortest angular delta
index 8d199f01bd437f61ad3ca1b70a1e6efb44cce86f..c170a0d7a86b7a58221f1294cdce4d8f49fd1641 100644 (file)
@@ -12,8 +12,8 @@ public class HoodConstants {
     public static final double MAX_VELOCITY = 25; // rad/s
     public static final double MAX_ACCELERATION = 160; // rad/s^2
 
-    public static final double MAX_ANGLE = 82; // degrees
-    public static final double MIN_ANGLE = 58.5; // degrees
+    public static final double MAX_ANGLE = 78.0; // degrees
+    public static final double MIN_ANGLE = 54.5; // degrees
 
     public static final double FEEDFORWARD_KV = 0.12;
 
index ab2b34d918195967dd4080e381e2819a841d2bb3..81eeb2a24497d3840a5b17297e3329aae735adfc 100644 (file)
@@ -35,8 +35,7 @@ public class Shooter extends SubsystemBase implements ShooterIO {
 
     private final ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged();
 
-
-    LoggedNetworkNumber powerModifier = new LoggedNetworkNumber("OPERATOR: Shooter Power Modifier", 1.05);
+    double powerModifier = 1.00;
 
     public Shooter() {
         updateInputs();
@@ -83,7 +82,7 @@ public class Shooter extends SubsystemBase implements ShooterIO {
 
         
         // Convert to RPS
-        double targetVelocityRPS = Units.radiansToRotations(shooterTargetSpeed / (ShooterConstants.SHOOTER_LAUNCH_DIAMETER/2)) * powerModifier.get();
+        double targetVelocityRPS = Units.radiansToRotations(shooterTargetSpeed / (ShooterConstants.SHOOTER_LAUNCH_DIAMETER/2)) * powerModifier;
 
         if (!Constants.DISABLE_SMART_DASHBOARD) {
             SmartDashboard.putNumber("Target Velocity RPS", targetVelocityRPS);
@@ -106,7 +105,9 @@ public class Shooter extends SubsystemBase implements ShooterIO {
             SmartDashboard.putBoolean("Shooter At Speed", atTargetSpeed());
             SmartDashboard.putBoolean("Shooter Running", shooterTargetSpeed > 0);
         }
-        
+        powerModifier = SmartDashboard.getNumber("OPERATOR: Shooter Power Modifier", powerModifier);
+        SmartDashboard.putNumber("OPERATOR: Shooter Power Modifier", powerModifier);
+
         // keep this
         SmartDashboard.putString("WON AUTO?", (HubActive.wonAuto()) ? "WON" : "LOST");
     }
@@ -144,11 +145,11 @@ public class Shooter extends SubsystemBase implements ShooterIO {
     }
 
     public void bumpUpShooterModifier() {
-        powerModifier.set(powerModifier.get() + 0.025);
+        powerModifier += 0.025;
     }
 
     public void bumpDownShooterModifier() {
-        powerModifier.set(powerModifier.get() - 0.025);
+        powerModifier -= 0.025;
     }
 
     /**