Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

scoraling #20

Merged
merged 14 commits into from
Feb 4, 2025
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
Prev Previous commit
Next Next commit
some reviews adressed
  • Loading branch information
ethan jones committed Feb 1, 2025
commit 5110ee4ccd579d0ae0d66e1e2febc0688fefb4e4
8 changes: 4 additions & 4 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ dependencies {
annotationProcessor wpi.java.deps.wpilibAnnotations()
implementation wpi.java.deps.wpilib()
implementation wpi.java.vendor.java()
implementation 'org.junit.jupiter:junit-jupiter-api:5.+'
implementation 'org.junit.jupiter:junit-jupiter-api:5.11.4'

roborioDebug wpi.java.deps.wpilibJniDebug(wpi.platforms.roborio)
roborioDebug wpi.java.vendor.jniDebug(wpi.platforms.roborio)
Expand All @@ -77,9 +77,9 @@ dependencies {
simulationRelease wpi.sim.enableRelease()

// Junit testing
testImplementation 'org.junit.jupiter:junit-jupiter-api:5.+'
testImplementation 'org.junit.jupiter:junit-jupiter-params:5.+'
testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5+'
testImplementation 'org.junit.jupiter:junit-jupiter-api:5.11.4'
testImplementation 'org.junit.jupiter:junit-jupiter-params:5.11.4'
testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.11.4'

// Monologue
implementation 'com.github.shueja:Monologue:+'
Expand Down
10 changes: 7 additions & 3 deletions src/main/java/org/sciborgs1155/robot/commands/Scoraling.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package org.sciborgs1155.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import org.sciborgs1155.robot.Constants.Field.Level;
import org.sciborgs1155.robot.elevator.Elevator;
import org.sciborgs1155.robot.hopper.Hopper;
Expand Down Expand Up @@ -29,7 +30,7 @@ public Scoraling(Hopper hopper, Scoral scoral, Elevator elevator) {
public Command hpsIntake() {
return elevator
.retract()
.andThen(runRollers())
.alongWith(Commands.waitUntil(elevator::atGoal).andThen(runRollers()))
.onlyIf(scoral.beambreakTrigger)
.withName("intakingHPS");
}
Expand All @@ -41,7 +42,10 @@ public Command hpsIntake() {
* @param level the level the scoral scores in
*/
public Command scoral(Level level) {
return elevator.scoreLevel(level).andThen(scoral.outtake()).withName("scoraling");
return elevator
.scoreLevel(level)
.alongWith(Commands.waitUntil(elevator::atGoal).andThen(scoral.outtake()))
.withName("scoraling");
}

/**
Expand All @@ -52,7 +56,7 @@ public Command scoral(Level level) {
public Command cleanAlgae(Level level) {
return elevator
.clean(level)
.andThen(scoral.intake())
.alongWith(Commands.waitUntil(elevator::atGoal).andThen(scoral.intake()))
.onlyIf(scoral.beambreakTrigger)
.withName("cleanAlgae");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -108,11 +108,11 @@ public Command scoreLevel(Level level) {
/** Goes to an offset height above the level given to clean algae ONLY L2 and L3! */
public Command clean(Level level) {
if (level == Level.L1 || level == Level.L4) {
retract();
FaultLogger.report(
"Algae level fault",
"an invalid level has been passed to the clean command, L1 or L4",
FaultType.WARNING);
return retract();
}

return goTo(level.height.plus(algaeOffset).in(Meters));
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/org/sciborgs1155/robot/hopper/Hopper.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,8 @@ public Hopper(SimpleMotor motor, Beambreak beambreak) {
this.motor = motor;
this.beambreak = beambreak;
this.beambreakTrigger = new Trigger(beambreak::get);

setDefaultCommand(stop());
}

/**
Expand Down
16 changes: 9 additions & 7 deletions src/main/java/org/sciborgs1155/robot/scoral/Scoral.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
import org.sciborgs1155.robot.Robot;

public class Scoral extends SubsystemBase implements Logged, AutoCloseable {
private final SimpleMotor hardware;
private final SimpleMotor motor;

private final Beambreak beambreak;
public final Trigger beambreakTrigger;
Expand All @@ -43,25 +43,27 @@ private static SimpleMotor realMotor() {
return SimpleMotor.talon(new TalonFX(ROLLER), config);
}

public Scoral(SimpleMotor hardware, Beambreak beambreak) {
this.hardware = hardware;
public Scoral(SimpleMotor motor, Beambreak beambreak) {
this.motor = motor;
this.beambreak = beambreak;
beambreakTrigger = new Trigger(beambreak::get);

setDefaultCommand(stop());
}

/** Runs the motor to move a coral out of the scoral outwards. */
public Command outtake() {
return run(() -> hardware.set(POWER)).withName("outtake");
return run(() -> motor.set(POWER)).withName("outtake");
}

/** Runs the motor to move a coral into the scoral. */
public Command intake() {
return run(() -> hardware.set(POWER)).withName("intake");
return run(() -> motor.set(POWER)).withName("intake");
}

/** Stops the motor */
public Command stop() {
return run(() -> hardware.set(0)).withName("stop");
return run(() -> motor.set(0)).withName("stop");
}

/** Returns the value of the beambreak, which is false when the beam is broken. */
Expand All @@ -77,6 +79,6 @@ public void periodic() {

@Override
public void close() throws Exception {
hardware.close();
motor.close();
}
}
4 changes: 3 additions & 1 deletion src/test/java/org/sciborgs1155/robot/ScoralingTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,9 @@ public void scoralTest(Level level) {
@ParameterizedTest
@MethodSource("levels")
public void algaeCleanTest(Level level) {
if (level == Level.L1 || level == Level.L4) {}
if (level == Level.L1 || level == Level.L4) {
return;
}
run(scoraling.cleanAlgae(level));
fastForward();
assertEquals(
Expand Down