Skip to content

Commit

Permalink
climber
Browse files Browse the repository at this point in the history
  • Loading branch information
KPatel008 committed Feb 7, 2025
1 parent 2ac0e5a commit 8f37a04
Show file tree
Hide file tree
Showing 4 changed files with 77 additions and 1 deletion.
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@
import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.vision.Vision;
import frc.robot.subsystems.vision.VisionIOPhotonVision;
import frc.robot.subsystems.Climber.Climber;
import frc.robot.subsystems.Climber.ClimberIOTalonFX;
import frc.robot.subsystems.drivetrain.CommandSwerveDrivetrain;
import frc.robot.subsystems.elevator.Elevator;
import frc.robot.subsystems.elevator.ElevatorIOTalonFX;
Expand Down Expand Up @@ -72,13 +74,15 @@ public class RobotContainer {
private final SendableChooser<Command> m_chooser;
private final Shooter s_Shooter;
private final Elevator s_Elevator;
private final Climber s_Climber;
// private final Vision m_vision;
public static AprilTagFieldLayout aprilTagLayout =
AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField);

public RobotContainer(){
s_Shooter = new Shooter(new ShooterIOTalonFX());
s_Elevator = new Elevator(new ElevatorIOTalonFX());
s_Climber = new Climber(new ClimberIOTalonFX());

//Auto Named Commands
NamedCommands.registerCommand("score", s_Shooter.shootTrough());
Expand Down Expand Up @@ -167,7 +171,8 @@ private void configureBindings() {
joystick.back().onTrue(s_Elevator.reZero());
// joystick.x().onTrue(s_Elevator.goToL3A()).onFalse(s_Elevator.goToL1());
joystick.a().onTrue(s_Elevator.goToL2A()).onFalse(s_Elevator.goToL1());

joystick.povLeft().onTrue(s_Climber.climb()).onFalse(s_Climber.stop());
joystick.povRight().onTrue(s_Climber.climb()).onFalse(s_Climber.stop());


joystick
Expand Down
25 changes: 25 additions & 0 deletions src/main/java/frc/robot/subsystems/Climber/Climber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
package frc.robot.subsystems.Climber;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class Climber extends SubsystemBase {
private final ClimberIO m_io;

public Climber(ClimberIO io) {
m_io = io;
}

public Command climb() {
return this.run(() -> m_io.setSpeed(1));
}

public Command stop() {
return this.run(() -> m_io.setSpeed(0));
}

public Command lower() {
return this.run(() -> m_io.setSpeed(-1));
}

}
13 changes: 13 additions & 0 deletions src/main/java/frc/robot/subsystems/Climber/ClimberIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
package frc.robot.subsystems.Climber;


public interface ClimberIO {

public static class ClimberIOinputs{
public double speed = 0.0;
}

public default void setSpeed(double speed) {}

public default void setBrakeMode(boolean enableBrakeMode) {}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/subsystems/Climber/ClimberIOTalonFX.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package frc.robot.subsystems.Climber;

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.DutyCycleOut;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.NeutralModeValue;

public class ClimberIOTalonFX implements ClimberIO {
private final TalonFX m_Climbermotor;

public ClimberIOTalonFX() {
m_Climbermotor = new TalonFX(20, "CANivore2");

final TalonFXConfiguration climberMotorConfig = new TalonFXConfiguration();
climberMotorConfig.CurrentLimits.SupplyCurrentLimit = 40.0;
climberMotorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;

m_Climbermotor.getConfigurator().apply(climberMotorConfig);
}

@Override
public void setSpeed(double speed) {
m_Climbermotor.setControl(new DutyCycleOut(speed));
}

@Override
public void setBrakeMode(boolean enableBrakeMode) {
final NeutralModeValue neutralModeValue =
enableBrakeMode ? NeutralModeValue.Brake : NeutralModeValue.Coast;
m_Climbermotor.setNeutralMode(neutralModeValue);
}

}

0 comments on commit 8f37a04

Please sign in to comment.