From 77f2c54a9013ac341d5568061905b8f697fab33f Mon Sep 17 00:00:00 2001 From: Tylr-J42 Date: Thu, 5 Mar 2026 00:28:37 -0500 Subject: [PATCH] more bindings n stuff --- src/main/java/frc/robot/RobotContainer.java | 4 ++-- src/main/java/frc/robot/constants/IntakePivotConstants.java | 4 ++-- src/main/java/frc/robot/constants/ShooterConstants.java | 3 +-- src/main/java/frc/robot/subsystems/IntakePivot.java | 1 + 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 1dee16b..66e85bf 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -83,8 +83,8 @@ public class RobotContainer { shiftTimer = new Timer(); shiftTimer.reset(); - //configureBindings(); - testConfigureBindings(); + configureBindings(); + //testConfigureBindings(); configureShiftDisplay(); if(AutoConstants.kAutoConfigOk) { diff --git a/src/main/java/frc/robot/constants/IntakePivotConstants.java b/src/main/java/frc/robot/constants/IntakePivotConstants.java index e7fefca..3d11fba 100644 --- a/src/main/java/frc/robot/constants/IntakePivotConstants.java +++ b/src/main/java/frc/robot/constants/IntakePivotConstants.java @@ -51,7 +51,7 @@ public class IntakePivotConstants { KLeftMotorConfig .idleMode(kIdleMode) .smartCurrentLimit(kCurrentLimit) - .inverted(kInvertMotors); + .inverted(false); KLeftMotorConfig.encoder .positionConversionFactor(kConversionFactor) .velocityConversionFactor(kConversionFactor / 60); @@ -67,7 +67,7 @@ public class IntakePivotConstants { kRightMotorConfig .idleMode(kIdleMode) .smartCurrentLimit(kCurrentLimit) - .inverted(kInvertMotors) + .inverted(false) .follow(kLeftMotorCANID); } } diff --git a/src/main/java/frc/robot/constants/ShooterConstants.java b/src/main/java/frc/robot/constants/ShooterConstants.java index d7e1183..b946737 100644 --- a/src/main/java/frc/robot/constants/ShooterConstants.java +++ b/src/main/java/frc/robot/constants/ShooterConstants.java @@ -9,12 +9,11 @@ import edu.wpi.first.math.util.Units; public class ShooterConstants { public enum ShooterSpeeds { kHubSpeed(3000.0), - kFeedSpeed(5000.0); + kFeedSpeed(5000.0), kIdleSpeed(750.0); private double speedMPS; private double speedRPM; - private double kIdleSpeed; private ShooterSpeeds(double speedRPM) { this.speedMPS = speedRPM * kWheelDiameter*Math.PI; diff --git a/src/main/java/frc/robot/subsystems/IntakePivot.java b/src/main/java/frc/robot/subsystems/IntakePivot.java index d4626f6..1180b4f 100644 --- a/src/main/java/frc/robot/subsystems/IntakePivot.java +++ b/src/main/java/frc/robot/subsystems/IntakePivot.java @@ -76,6 +76,7 @@ public class IntakePivot extends SubsystemBase { currentTargetPosition = null; leftMotor.set(speed.getAsDouble() * IntakePivotConstants.kMaxManualSpeedMultiplier); + rightMotor.set(speed.getAsDouble() * IntakePivotConstants.kMaxManualSpeedMultiplier); }); }