From 624c997981376a265ce6fea8348657213cccd33d Mon Sep 17 00:00:00 2001 From: OakvilleDynamicsProgramer <159196208+OakvilleDynamicsProgrammer@users.noreply.github.com> Date: Tue, 5 Mar 2024 19:04:06 -0600 Subject: [PATCH] Update flywheel speeds --- src/main/java/frc/robot/Constants.java | 3 ++- src/main/java/frc/robot/commands/FlyWCommand.java | 9 +++++---- src/main/java/frc/robot/subsystems/FlyWheel.java | 12 +++++++++--- 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 75869bb..c9984f1 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -91,6 +91,7 @@ public static class MechanismConstants { public static final int FLYWHEEL_MOTOR_2 = 4; public static final boolean FLYWHEEL_MOTOR_1_INVERTED = true; public static final boolean FLYWHEEL_MOTOR_2_INVERTED = false; - public static final double FLYWHEEL_MOTOR_SPEED = 0.8; + public static final double FLYWHEEL_MOTOR_SPEED = 1.0; + public static final double FLYWHEEL_MOTOR_SPEED_SLOW = 0.15; } } diff --git a/src/main/java/frc/robot/commands/FlyWCommand.java b/src/main/java/frc/robot/commands/FlyWCommand.java index 7dde141..a2e1d0e 100644 --- a/src/main/java/frc/robot/commands/FlyWCommand.java +++ b/src/main/java/frc/robot/commands/FlyWCommand.java @@ -25,12 +25,14 @@ public void initialize() {} @Override public void execute() { // TODO: Change this to the correct button - if (ConveyorJoystick.getRawButton(3) == true) { - m_FlyWSubsystem.enableflywheel(); + if (ConveyorJoystick.getRawButton(7) == true) { + m_FlyWSubsystem.enableflywheelfast(); // TODO: Change this to the correct button - } else if (ConveyorJoystick.getRawButton(4) == true) { + } else if (ConveyorJoystick.getRawButton(8) == true) { m_FlyWSubsystem.reverseflywheel(); System.out.println("Conveyor Moving in Reverse"); + } else if (ConveyorJoystick.getRawButton(9) == true) { + m_FlyWSubsystem.enableflywheelslow(); } else { m_FlyWSubsystem.disableflywheel(); } @@ -39,7 +41,6 @@ public void execute() { @Override public void end(boolean interrupted) { m_FlyWSubsystem.disableflywheel(); - m_FlyWSubsystem.enableflywheel(); } @Override diff --git a/src/main/java/frc/robot/subsystems/FlyWheel.java b/src/main/java/frc/robot/subsystems/FlyWheel.java index 2ee2530..df05dae 100644 --- a/src/main/java/frc/robot/subsystems/FlyWheel.java +++ b/src/main/java/frc/robot/subsystems/FlyWheel.java @@ -23,11 +23,17 @@ public FlyWheel() { } /** Sets the flywheel motors to 100% power. */ - public void enableflywheel() { + public void enableflywheelfast() { flywheelMotor1.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED); flywheelMotor2.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED); } + /** Sets the flywheel motors to slow speed */ + public void enableflywheelslow() { + flywheelMotor1.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW); + flywheelMotor2.set(MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW); + } + /** Sets the flywheel motors to 0% power. */ public void disableflywheel() { flywheelMotor1.set(0); @@ -36,8 +42,8 @@ public void disableflywheel() { /** Sets the flywheel motors to -100% power. (Reverse direction) */ public void reverseflywheel() { - flywheelMotor1.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED); - flywheelMotor2.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED); + flywheelMotor1.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW); + flywheelMotor2.set(-MechanismConstants.FLYWHEEL_MOTOR_SPEED_SLOW); } @Override