From e5284b84e524ed0b53ac05b53b7737bc3e2a144b Mon Sep 17 00:00:00 2001 From: PGgit08 Date: Wed, 20 Mar 2024 20:57:26 -0400 Subject: [PATCH] added shooter kg back in --- .../robot/commands/auto/{NoteAllign.java => NoteAlign.java} | 6 +++--- src/main/java/frc/robot/subsystems/ShooterSubsystem.java | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) rename src/main/java/frc/robot/commands/auto/{NoteAllign.java => NoteAlign.java} (90%) diff --git a/src/main/java/frc/robot/commands/auto/NoteAllign.java b/src/main/java/frc/robot/commands/auto/NoteAlign.java similarity index 90% rename from src/main/java/frc/robot/commands/auto/NoteAllign.java rename to src/main/java/frc/robot/commands/auto/NoteAlign.java index 157a742..ffcb3aa 100644 --- a/src/main/java/frc/robot/commands/auto/NoteAllign.java +++ b/src/main/java/frc/robot/commands/auto/NoteAlign.java @@ -16,7 +16,7 @@ import frc.robot.subsystems.SwerveDriveSubsystem; import frc.robot.subsystems.VisionSubsystem; -public class NoteAllign extends Command { +public class NoteAlign extends Command { private SwerveDriveSubsystem _swerve; private VisionSubsystem _vision; @@ -27,8 +27,8 @@ public class NoteAllign extends Command { private PIDController _headingController = new PIDController(0, 0, 0); - /** Creates a new NoteAllign. */ - public NoteAllign(SwerveDriveSubsystem swerve, VisionSubsystem vision, DoubleSupplier xSpeed, DoubleSupplier ySpeed) { + /** Creates a new NoteAlign. */ + public NoteAlign(SwerveDriveSubsystem swerve, VisionSubsystem vision, DoubleSupplier xSpeed, DoubleSupplier ySpeed) { // Use addRequirements() here to declare subsystem dependencies. _swerve = swerve; _vision = vision; diff --git a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java index 50e4eec..1d08dd5 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -39,7 +39,7 @@ public class ShooterSubsystem extends SubsystemBase { private final RelativeEncoder _leftEncoder = _leftMotor.getEncoder(); - private final ArmFeedforward _angleFeed = new ArmFeedforward(0, 0, 0); + private final ArmFeedforward _angleFeed = new ArmFeedforward(0, FeedForward.SHOOTER_ANGLE_KG, 0); private final PIDController _angleController = new PIDController(PID.SHOOTER_ANGLE_KP, 0, 0); private final Debouncer _revDebouncer = new Debouncer(0.5, DebounceType.kRising);