Skip to content
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 10 additions & 16 deletions src/main/java/frc/robot/Subsystems/Climber/Climber.java
Original file line number Diff line number Diff line change
@@ -1,18 +1,25 @@
package frc.robot.Subsystems.Climber;

import static frc.robot.GlobalConstants.*;
import static frc.robot.GlobalConstants.Controllers.DRIVER_CONTROLLER;
import static frc.robot.GlobalConstants.Controllers.OPERATOR_CONTROLLER;
import static frc.robot.Subsystems.Climber.ClimberConstants.*;

import org.littletonrobotics.junction.Logger;
import org.team7525.subsystem.Subsystem;

public class Climber extends Subsystem<ClimberStates> {

public static Climber instance;

private ClimberIO io;
private ClimberIOInputsAutoLogged inputs;

public static Climber getInstance() {
if (instance == null) {
instance = new Climber();
}
return instance;
}

public Climber() {
super("Climber", ClimberStates.IDLE);
this.io = switch (ROBOT_MODE) {
Expand All @@ -26,22 +33,9 @@ public Climber() {

@Override
public void runState() {
io.setSpeed(getState().getSpeed());
io.updateInputs(inputs);

if (
Math.abs(DRIVER_CONTROLLER.getRightTriggerAxis()) > 0.5 ||
Math.abs(OPERATOR_CONTROLLER.getRightTriggerAxis()) > 0.5
) {
io.setSpeed(ClimberStates.IN.getSpeed());
} else if (
Math.abs(DRIVER_CONTROLLER.getLeftTriggerAxis()) > 0.5 ||
Math.abs(OPERATOR_CONTROLLER.getLeftTriggerAxis()) > 0.5
) {
io.setSpeed(ClimberStates.OUT.getSpeed());
} else {
io.setSpeed(ClimberStates.IDLE.getSpeed());
}

Logger.processInputs(SUBSYSTEM_NAME, inputs);
Logger.recordOutput(SUBSYSTEM_NAME + "/State", getState().getStateString());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ public final class ClimberConstants {
public static final double IN_SPEED = -0.65;
public static final double OUT_SPEED = 0.65;

// TODO: set values ^
public static class Real {}

public static class Sim {

Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/Subsystems/Climber/ClimberIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,9 @@ public interface ClimberIO {
public static class ClimberIOInputs {

public double speed;
public double speedSetpoint;

public ClimberStates state;
}

public void updateInputs(ClimberIOInputs input);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,18 +9,22 @@ public class ClimberIOReal implements ClimberIO {

private SparkMax motor;

private double speedSetpoint;

public ClimberIOReal() {
motor = new SparkMax(CLIMBER_CANID, MotorType.kBrushless);
motor.getEncoder().setPosition(0);
}

@Override
public void updateInputs(ClimberIOInputs inputs) {
inputs.speed = motor.getEncoder().getVelocity() / 60;
inputs.speed = (motor.getEncoder().getVelocity()) / 60;
inputs.speedSetpoint = speedSetpoint;
}

@Override
public void setSpeed(double speed) {
this.speedSetpoint = speed;
motor.set(speed);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public String getStateString() {
return stateString;
}

protected double getSpeed() {
public double getSpeed() {
return speed;
}
}