Skip to content

Commit

Permalink
set up climber subsystem
Browse files Browse the repository at this point in the history
  • Loading branch information
reyamiller committed Jan 22, 2024
1 parent 2bcdc7d commit ddb8b1a
Show file tree
Hide file tree
Showing 5 changed files with 145 additions and 1 deletion.
5 changes: 5 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Motors.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,11 @@ public interface Motors {

/** Classes to store all of the values a motor needs */

public interface Climber {
CANSparkMaxConfig LEFT_MOTOR = new CANSparkMaxConfig(false, IdleMode.kBrake, 40);
CANSparkMaxConfig RIGHT_MOTOR = new CANSparkMaxConfig(false, IdleMode.kBrake, 40);
}

public static class TalonSRXConfig {
public final boolean INVERTED;
public final NeutralMode NEUTRAL_MODE;
Expand Down
10 changes: 10 additions & 0 deletions src/main/java/com/stuypulse/robot/constants/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,4 +12,14 @@ public interface Gamepad {
int OPERATOR = 1;
int DEBUGGER = 2;
}

public interface Climber {
int LEFT_MOTOR = 3;
int RIGHT_MOTOR = 4; // placeholders for now

int TOP_RIGHT_LIMIT = 0;
int TOP_LEFT_LIMIT = 0;
int BOTTOM_RIGHT_LIMIT = 0;
int BOTTOM_LEFT_LIMIT = 0;
}
}
11 changes: 10 additions & 1 deletion src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,4 +14,13 @@
* We use StuyLib's SmartNumber / SmartBoolean in order to have tunable
* values that we can edit on Shuffleboard.
*/
public interface Settings {}
public interface Settings {
public interface Climber {
double MIN_HEIGHT = 0.0;
double MAX_HEIGHT = 0.0;

public interface Encoder {
double ENCODER_MULTIPLIER = 0.0;
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
/*
* climbs chain in endgame
* - 2 motors (12:1 gear ratio)
* - 2 encoders
* - 4 limit switches (bottom and top, two on each side)
* - hard stop at bottom of the lift
*
* functions:
* - get current height of climber
* - go to specific heights
* - work with the gravity of the robot (has kG)
*/

package com.stuypulse.robot.subsystems.climber;

import com.stuypulse.stuylib.network.SmartNumber;

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

public abstract class AbstractClimber extends SubsystemBase {
public static final AbstractClimber instance;

private SmartNumber targetHeight;

static {
instance = new Climber();
}

public static AbstractClimber getInstance() {
return instance;
}

public void setTargetHeight(double height) {
targetHeight.set(height);
}

public double getTargetHeight() {
return targetHeight.get();
}

public abstract double getHeight();

public abstract double getVelocity();

public abstract boolean atTop();
public abstract boolean atBottom();

public abstract void periodic();
}
71 changes: 71 additions & 0 deletions src/main/java/com/stuypulse/robot/subsystems/climber/Climber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
package com.stuypulse.robot.subsystems.climber;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.RelativeEncoder;
import com.stuypulse.robot.constants.Motors;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

import static com.stuypulse.robot.constants.Settings.Climber.Encoder.*;
import static com.stuypulse.robot.constants.Ports.Climber.*;

public class Climber extends AbstractClimber {

private final CANSparkMax rightMotor;
private final CANSparkMax leftMotor;

private final RelativeEncoder rightEncoder;
private final RelativeEncoder leftEncoder;

private final DigitalInput topRightLimit;
private final DigitalInput topLeftLimit;
private final DigitalInput bottomRightLimit;
private final DigitalInput bottomLeftLimit;

protected Climber() {
rightMotor = new CANSparkMax(RIGHT_MOTOR, MotorType.kBrushless);
leftMotor = new CANSparkMax(LEFT_MOTOR, MotorType.kBrushless);

rightEncoder = rightMotor.getEncoder();
leftEncoder = leftMotor.getEncoder();

rightEncoder.setPositionConversionFactor(ENCODER_MULTIPLIER);
leftEncoder.setPositionConversionFactor(ENCODER_MULTIPLIER);

topRightLimit = new DigitalInput(TOP_RIGHT_LIMIT);
topLeftLimit = new DigitalInput(TOP_LEFT_LIMIT);
bottomRightLimit = new DigitalInput(BOTTOM_RIGHT_LIMIT);
bottomLeftLimit = new DigitalInput(BOTTOM_LEFT_LIMIT);

Motors.Climber.LEFT_MOTOR.configure(leftMotor);
Motors.Climber.RIGHT_MOTOR.configure(rightMotor);
}

@Override
public double getHeight() {
return (leftEncoder.getPosition() + rightEncoder.getPosition()) / 2 * ENCODER_MULTIPLIER;
}

@Override
public double getVelocity() {
return (leftEncoder.getVelocity() + rightEncoder.getVelocity()) / 2 * ENCODER_MULTIPLIER;
}

@Override
public boolean atTop() {
return (!topRightLimit.get()) && (!topLeftLimit.get());
}

@Override
public boolean atBottom() {
return (!bottomRightLimit.get()) && (!bottomLeftLimit.get());
}

@Override
public void periodic() {
SmartDashboard.putNumber("Climber/Target Height", getTargetHeight());
SmartDashboard.putNumber("Climber/Height", getHeight());
}
}

0 comments on commit ddb8b1a

Please sign in to comment.