Skip to content

Commit

Permalink
basic climber done TODO: tune and test PID and add setpoints/controls
Browse files Browse the repository at this point in the history
  • Loading branch information
Lu-han-wang committed Jan 27, 2024
1 parent c137937 commit 4e97763
Show file tree
Hide file tree
Showing 2 changed files with 73 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
package org.jmhsrobotics.frc2024.subsystems.climber;

import com.revrobotics.CANSparkMax;
import com.revrobotics.SparkPIDController;

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

public class ClimbCommand extends Command {
private ClimbSubsystem climbSubsystem;
private double length;
private SparkPIDController lengthPIDController;

public ClimbCommand(ClimbSubsystem climbSubsystem, double length) {
this.climbSubsystem = climbSubsystem;
this.length = length;
addRequirements(climbSubsystem);

lengthPIDController = climbSubsystem.getMotor().getPIDController();
lengthPIDController.setFeedbackDevice(climbSubsystem.getEncoder());

// TODO: tune vals
lengthPIDController.setP(.1);
lengthPIDController.setI(0);
lengthPIDController.setD(0);
lengthPIDController.setFF(0);
lengthPIDController.setOutputRange(-1, 1);
lengthPIDController.setReference(length, CANSparkMax.ControlType.kPosition);
}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
package org.jmhsrobotics.frc2024.subsystems.climber;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;

import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

import com.revrobotics.CANSparkBase.IdleMode;

public class ClimbSubsystem extends SubsystemBase {

private CANSparkMax climbMotor = new CANSparkMax(11, MotorType.kBrushless);
private RelativeEncoder climbEncoder = climbMotor.getEncoder();

public ClimbSubsystem() {
climbEncoder.setPosition(0);
climbMotor.setIdleMode(IdleMode.kBrake);
climbMotor.setSmartCurrentLimit(40);

}

public CANSparkMax getMotor() {
return climbMotor;
}

public void setMotor(double amount) {
climbMotor.set(amount);
}

public double getClimbPosition() {
return climbEncoder.getPosition();
}

public void setEncoder(double amount) {
climbEncoder.setPosition(amount);
}

public RelativeEncoder getEncoder() {
return climbEncoder;
}

}

0 comments on commit 4e97763

Please sign in to comment.