From a80a9eedf45a504c218f29cea8d6efbef7daa8c9 Mon Sep 17 00:00:00 2001 From: siyoyoCode Date: Sat, 17 Feb 2024 16:23:17 -0800 Subject: [PATCH] updated shooter to account for bottom feeder resistance --- src/main/java/frc/robot/Constants.java | 1 + .../robot/subsystems/shooter/ShooterFeederSubsystem.java | 6 ++++++ 2 files changed, 7 insertions(+) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 3b3276ce..21f20438 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -108,6 +108,7 @@ public static class ShooterConstants { public static final int SHOOTER_MOTOR_TWO_ID = 14; public static final int FEEDER_MOTOR_ID = 15; + //public static final int FEEDER_MOTOR_2_ID = 43; //CHANGE THIS public static final double FEED_ANGLE = Units.degreesToRadians(70); } diff --git a/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java b/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java index 96336d07..7935fb89 100644 --- a/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java +++ b/src/main/java/frc/robot/subsystems/shooter/ShooterFeederSubsystem.java @@ -13,9 +13,11 @@ public class ShooterFeederSubsystem extends SubsystemBase{ public final double FEEDER_MOTOR_SPEED = .8; public final int NO_NOTE_TOLERANCE = 500; //must test with no note in front of sensor public final int TOLERANCE = 1000; //represents the value when half note is in front of sensor + private final double FEEDER_MOTOR_RESISTANCE = 1.01; //motors private final TalonSRX feederMotor; + //private final TalonSRX feederMotor2; //devices private final ColorSensorV3 shooterSensor; //distance sensor @@ -25,12 +27,16 @@ public ShooterFeederSubsystem(){ feederMotor = new TalonSRX(FEEDER_MOTOR_ID); feederMotor.setInverted(true); + // feederMotor2 = new TalonSRX(FEEDER_MOTOR_2_ID); + // feederMotor.setInverted(true); + //sensors shooterSensor = new ColorSensorV3(I2C.Port.kMXP); } public void setFeederMotorSpeed(double speed){ feederMotor.set(TalonSRXControlMode.PercentOutput, speed); + //feederMotor2.set(TalonSRXControlMode.PercentOutput, speed*FEEDER_MOTOR_RESISTANCE); System.out.println("feeding motor speed is: " + feederMotor.getMotorOutputPercent()); }