Skip to content

Commit

Permalink
Cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
rachitkakkar committed Mar 30, 2024
1 parent 6517dec commit cd1dd6f
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 25 deletions.
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,15 @@ public class RobotContainer {
DRIVE_SUBSYSTEM::getPose,
() -> speakerSupplier()
);
private static final ClimberSubsystem CLIMBER_SUBSYSTEM = new ClimberSubsystem(
ClimberSubsystem.initializeHardware(),
Constants.Climber.CLIMBER_VELOCITY
);
private static final IntakeSubsystem INTAKE_SUBSYSTEM = new IntakeSubsystem(
IntakeSubsystem.initializeHardware(),
Constants.Intake.ROLLER_VELOCITY
);

private static final VisionSubsystem VISION_SUBSYSTEM = VisionSubsystem.getInstance();

private static final CommandXboxController PRIMARY_CONTROLLER = new CommandXboxController(Constants.HID.PRIMARY_CONTROLLER_PORT);
Expand Down
25 changes: 0 additions & 25 deletions src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@ public ClimberSubsystem(Hardware climberHardware, Measure<Dimensionless> climber
m_lClimberMotor.setInverted(true);
m_rClimberMotor.setInverted(true);


m_lClimberMotor.enableReverseLimitSwitch();
m_rClimberMotor.enableReverseLimitSwitch();

Expand Down Expand Up @@ -81,33 +80,9 @@ private void stop() {
m_rClimberMotor.stopMotor();
}

/**
* Runs climber arms
* @return Command to run the climber motors
*/
public Command runClimberCommand() {
return runEnd(() -> runClimber(), () -> stop());
}

public Command lowerLeftCommand() {
return runEnd(() -> m_lClimberMotor.set(-CLIMBER_VELOCITY.in(Units.Percent), ControlType.kDutyCycle), () -> stop());
}
public Command raiseLeftCommand() {
return runEnd(() -> m_lClimberMotor.set(CLIMBER_VELOCITY.in(Units.Percent), ControlType.kDutyCycle), () -> stop());
}
public Command lowerRightCommand() {
return runEnd(() -> m_rClimberMotor.set(-CLIMBER_VELOCITY.in(Units.Percent), ControlType.kDutyCycle), () -> stop());
}
public Command raiseRightCommand() {
return runEnd(() -> m_rClimberMotor.set(CLIMBER_VELOCITY.in(Units.Percent), ControlType.kDutyCycle), () -> stop());
}

@Override
public void periodic() {
m_lClimberMotor.periodic();
m_rClimberMotor.periodic();
// m_rClimberMotor.stopMotor();

CLIMBER_VELOCITY = Units.Percent.of(SmartDashboard.getNumber("climber power", 0));
}
}

0 comments on commit cd1dd6f

Please sign in to comment.