From b9c849e21e9354a010597a48b8dd491fe84aaff0 Mon Sep 17 00:00:00 2001 From: Programming SR <85456157+ProgrammingSR@users.noreply.github.com> Date: Fri, 5 Apr 2024 08:34:48 -0700 Subject: [PATCH] added climber reset (#44) * added climber reset * removed unused comment. fixed formatting --- src/main/java/frc/robot/RobotContainer.java | 1 + src/main/java/frc/robot/commands/DefaultLEDCommand.java | 8 ++++---- src/main/java/frc/robot/subsystems/ClimberSubsystem.java | 4 ++++ 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index d37732c..2c4b878 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -262,6 +262,7 @@ public void resetAllSubsystems() { m_intakeSubsystem.reset(); m_shooterSubsystem.reset(); m_robotDrive.reset(); + m_climberSubsystem.reset(); } public void compressorInit() { diff --git a/src/main/java/frc/robot/commands/DefaultLEDCommand.java b/src/main/java/frc/robot/commands/DefaultLEDCommand.java index 727b663..44fcab1 100644 --- a/src/main/java/frc/robot/commands/DefaultLEDCommand.java +++ b/src/main/java/frc/robot/commands/DefaultLEDCommand.java @@ -64,19 +64,19 @@ public void initialize() { } //check for pneumatics state and override b4 value - if (m_climberSubsystem.getState() == Value.kForward){ + if (m_climberSubsystem.getState() == Value.kForward) { rgb[0] = 257; rgb[1] = 257; rgb[2] = 257; } - if (m_intakeSubsystem.getArmPosition() == IntakeConstants.kIntakeAmpScoringAngle){ - if (m_intakeSubsystem.ampReady()){ + if (m_intakeSubsystem.getArmPosition() == IntakeConstants.kIntakeAmpScoringAngle) { + if (m_intakeSubsystem.ampReady()) { rgb[0] = 0; rgb[1] = 255; rgb[2] = 0; } - else{ + else { rgb[0] = 0; rgb[1] = 255; rgb[2] = 0; diff --git a/src/main/java/frc/robot/subsystems/ClimberSubsystem.java b/src/main/java/frc/robot/subsystems/ClimberSubsystem.java index 9bd6f9c..cc211db 100644 --- a/src/main/java/frc/robot/subsystems/ClimberSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ClimberSubsystem.java @@ -41,6 +41,10 @@ public void periodic() { SmartDashboard.putBoolean("Compressor Running", m_pHub.getCompressor()); } + public void reset() { + m_state = kOff; + } + /** * Sets the state of the solenoid to off */