Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
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
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/constants/ClimberConstants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
package frc.robot.constants;

public class ClimberConstants {
public static final double CLIMBING_SPEED = .1;
public static final double DECLIMBING_SPEED = -.1;
public static final int CLIMBER_MOTOR_ID = 0;
}
21 changes: 21 additions & 0 deletions src/main/java/frc/robot/states/ClimberState.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
package frc.robot.states;

import frc.robot.constants.ClimberConstants;

/* States the Climber can be in */
public enum ClimberState {
IDLE(0),
DISABLED(0),
CLIMBING(ClimberConstants.CLIMBING_SPEED),
DECLIMB(ClimberConstants.DECLIMBING_SPEED);

private final double speed;

ClimberState(double speed) {
this.speed = speed;
}

public double getSpeed() {
return speed;
}
}
89 changes: 89 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,89 @@
package frc.robot.subsystems.Climber;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.states.ClimberState;
import frc.robot.util.PARTs.Classes.PARTsCommandUtils;
import frc.robot.util.PARTs.Classes.Abstracts.PARTsSubsystem;

public abstract class Climber extends PARTsSubsystem {
private ClimberState climberState = ClimberState.IDLE;

public Climber() {
super("Climber");
}

// region Generic Subsystem Functions
@Override
public void outputTelemetry() {
partsNT.putString("Climber State", climberState.toString());
}

@Override
public void stop() {
climberState = climberState.DISABLED;
}

@Override
public void reset() {
climberState = climberState.IDLE;
}

@Override
public void log() {
partsLogger.logString("Climber State", climberState.toString());
}
// endregion

@Override
public void periodic() {
switch (climberState) {
case CLIMBING:
setSpeed(climberState.getSpeed());
break;
case DECLIMB:
setSpeed(climberState.getSpeed());
break;
case DISABLED:
setSpeed(climberState.getSpeed());
break;
case IDLE:
setSpeed(climberState.getSpeed());
break;
default:
setSpeed(0);
break;
}
}

// region Custom Public Functions
/**
* Sets the speed of the Shooter.
*
* @param speed The speed between <code>-1.0</code> and <code>1.0</code>.
*/
protected abstract void setSpeed(double speed);

public ClimberState getState() {
return climberState;
}


public Command idle() {
return PARTsCommandUtils.setCommandName("Command Idle", this.runOnce(() -> {
climberState = ClimberState.IDLE;
}));
}

public Command climb() {
return PARTsCommandUtils.setCommandName("Command Climb", this.runOnce(() -> {
climberState = ClimberState.CLIMBING;
}));
}

public Command declimb() {
return PARTsCommandUtils.setCommandName("Command Declimb", this.runOnce(() -> {
climberState = ClimberState.DECLIMB;
}));
}
// endregion
}
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/subsystems/Climber/ClimberPhys.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
package frc.robot.subsystems.Climber;

import com.revrobotics.PersistMode;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.ResetMode;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;

import frc.robot.constants.ClimberConstants;

public class ClimberPhys extends Climber {
protected final SparkMax climberMotor;
protected final RelativeEncoder climberEncoder;

public ClimberPhys() {
super();

SparkMaxConfig climberConfig = new SparkMaxConfig();
climberConfig.idleMode(IdleMode.kBrake);

climberMotor = new SparkMax(ClimberConstants.CLIMBER_MOTOR_ID, MotorType.kBrushless);
climberEncoder = climberMotor.getEncoder();
climberMotor.configure(climberConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
}

@Override
protected void setSpeed(double speed) {
climberMotor.set(speed);
}

@Override
public void periodic() {
super.periodic();
}

@Override
public void outputTelemetry() {
partsNT.putDouble("Output", climberMotor.getOutputCurrent());
partsNT.putDouble("Current", climberMotor.getAppliedOutput());
}

@Override
public void log() {
partsLogger.logDouble("Output", climberMotor.getOutputCurrent());
partsLogger.logDouble("Current", climberMotor.getAppliedOutput());
}
}
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/subsystems/Climber/ClimberSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
package frc.robot.subsystems.Climber;

public class ClimberSim extends Climber {
@Override
protected void setSpeed(double speed) {
partsNT.putDouble("Our Climber Speed", speed);
}
}
Loading