Skip to content

Commit

Permalink
Merge pull request #4 from SciBorgs/hopper
Browse files Browse the repository at this point in the history
Hopper
  • Loading branch information
dannynotsmart authored Jan 11, 2025
2 parents 6724e49 + 9ee4f2b commit a7a1415
Show file tree
Hide file tree
Showing 6 changed files with 145 additions and 0 deletions.
6 changes: 6 additions & 0 deletions src/main/java/org/sciborgs1155/robot/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,4 +30,10 @@ public static final class Scoral {
public static final int BOTTOM_ROLLER = 22;
public static final int BEAMBREAK = 23;
}

public static final class Hopper {
public static final int LEFT_MOTOR = -1;
public static final int RIGHT_MOTOR = -1;
public static final int BEAMBREAK = -1;
}
}
68 changes: 68 additions & 0 deletions src/main/java/org/sciborgs1155/robot/hopper/Hopper.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
package org.sciborgs1155.robot.hopper;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import org.sciborgs1155.robot.Robot;

public class Hopper extends SubsystemBase implements AutoCloseable {
/** Creates a real or non-existent hopper based on {@link Robot#isReal()}. */
public static Hopper create() {
return Robot.isReal() ? new Hopper(new RealHopper()) : Hopper.none();
}

/** Creates a non-existent hopper. */
public static Hopper none() {
return new Hopper(new NoHopper());
}

private final HopperIO hardware;
public final Trigger beambreakTrigger;

public Hopper(HopperIO hardware) {
this.hardware = hardware;
this.beambreakTrigger = new Trigger(hardware::beambreak);
}

/**
* Runs the motors of the hopper.
*
* @param power The power to set the hoppers motors to.
* @return A command to set the power of the hopper motors.
*/
public Command run(double power) {
return runOnce(() -> hardware.setPower(power));
}

/**
* Intakes corals from human player.
*
* @return A command to intake corals.
*/
public Command intake() {
return run(HopperConstants.INTAKE_POWER); // more logic later
}

/**
* Outtake corals.
*
* @return A command to outtake corals.
*/
public Command outtake() {
return run(-HopperConstants.INTAKE_POWER);
}

/**
* Stops the hopper.
*
* @return A command to stop the hopper.
*/
public Command stop() {
return run(0);
}

@Override
public void close() throws Exception {
hardware.close();
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
package org.sciborgs1155.robot.hopper;

public class HopperConstants {
public static final double INTAKE_POWER = 0.9;
}
7 changes: 7 additions & 0 deletions src/main/java/org/sciborgs1155/robot/hopper/HopperIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
package org.sciborgs1155.robot.hopper;

public interface HopperIO extends AutoCloseable {
void setPower(double power);

boolean beambreak();
}
14 changes: 14 additions & 0 deletions src/main/java/org/sciborgs1155/robot/hopper/NoHopper.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package org.sciborgs1155.robot.hopper;

public class NoHopper implements HopperIO {
@Override
public void setPower(double power) {}

@Override
public boolean beambreak() {
return false;
}

@Override
public void close() {}
}
45 changes: 45 additions & 0 deletions src/main/java/org/sciborgs1155/robot/hopper/RealHopper.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
package org.sciborgs1155.robot.hopper;

import com.revrobotics.spark.SparkBase.PersistMode;
import com.revrobotics.spark.SparkBase.ResetMode;
import com.revrobotics.spark.SparkLowLevel.MotorType;
import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.config.SparkBaseConfig;
import com.revrobotics.spark.config.SparkMaxConfig;
import edu.wpi.first.wpilibj.DigitalInput;
import org.sciborgs1155.robot.Ports.Hopper;

public class RealHopper implements HopperIO {
private final SparkMax leftMotor = new SparkMax(Hopper.LEFT_MOTOR, MotorType.kBrushless);
private final SparkMax rightMotor = new SparkMax(Hopper.RIGHT_MOTOR, MotorType.kBrushless);
private final DigitalInput beambreak = new DigitalInput(Hopper.BEAMBREAK);

public RealHopper() {
SparkBaseConfig config = new SparkMaxConfig(); // prob more configs to do
config.inverted(true);

rightMotor.configure(
config,
ResetMode.kResetSafeParameters,
PersistMode.kPersistParameters); // one of the motors are inverted so that the motors can
// intake/outtake right
}

@Override
public void setPower(double power) {
leftMotor.set(power);
rightMotor.set(power);
}

@Override
public boolean beambreak() {
return beambreak.get();
}

@Override
public void close() {
leftMotor.close();
rightMotor.close();
beambreak.close();
}
}

0 comments on commit a7a1415

Please sign in to comment.