Skip to content

Commit

Permalink
leagues 3
Browse files Browse the repository at this point in the history
  • Loading branch information
penguinencounter committed Jan 20, 2025
1 parent cbfd238 commit ef6fc78
Show file tree
Hide file tree
Showing 5 changed files with 30 additions and 27 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -155,11 +155,14 @@ class HWTest : LinearOpMode() {
testEncoderA(hw.encoderLeft, "encLeft")
testEncoderA(hw.encoderCenter, "encCenter")
testEncoderA(hw.encoderRight, "encRight")
testEncoderB(hw.encoderVerticalSlide, "encVerticalSlide")
testEncoderA(hw.encoderVerticalSlide, "encVerticalSlide")
testEncoderB(hw.arm, "encArm")
}
if (yesno("Test lift?")) {
testMotor(hw.verticalSlide, "verticalSlide")
// hw.verticalLift.setTargetPosition(Hardware.VLIFT_SCORE_SPECIMEN)
// while (opModeIsActive()) {
//
// }
stopAll()
}
} catch (_: StopException) {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,10 +118,9 @@ public static class Locks {

public Lift verticalLift;

@HardwareName("verticalSlides")
@EncoderFor("verticalSlides")
@AutoClearEncoder
@Deprecated
public DcMotor encoderVerticalSlide;
public Encoder encoderVerticalSlide;

@HardwareName("arm")
@ZeroPower(DcMotor.ZeroPowerBehavior.BRAKE)
Expand Down
35 changes: 18 additions & 17 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/LeftAuto.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ public class LeftAuto extends LinearOpMode {
public static final Motion.Calibrate CALIBRATION = new Motion.Calibrate(1.0, 1.0, 1.0); // Calibration factors for strafe, forward, and turn.
private static final RuntimeException NOT_IMPLEMENTED = new RuntimeException("This operation is not implemented");
final Pose SCORE_HIGH_BASKET = new Pose(10.6286797, 17.3713203, Math.toRadians(-45));
final Pose PARK_BAD = new Pose(10.6286797, 17.3713203, Math.toRadians(0));
final Pose PARK1 = new Pose(57.5, 0, Math.toRadians(0));
final Pose PARK2 = new Pose(55.5, -11, Math.toRadians(0));
final Pose START = new Pose(0, 4.66, Math.toRadians(0));
Expand Down Expand Up @@ -140,7 +141,7 @@ private ITask fourthYellow() {
private ITask scoreHighBasket() {
return groupOf(inner -> inner.add(groupOf(a -> {
// all of these:
a.add(vLiftProxy.moveTo(Hardware.VLIFT_SCORE_HIGH, 10, 2.0));
a.add(vLiftProxy.moveTo(Hardware.VLIFT_SCORE_HIGH, 10, 1.2));
a.add(run(() -> hardware.arm.setTargetPosition(222)));
a.add(await(250)); // minimum duration
}))
Expand Down Expand Up @@ -220,22 +221,22 @@ public void runOpMode() {
.then(fourthYellow())
.then(moveTo(SCORE_HIGH_BASKET))
.then(scoreHighBasket())
.then(moveTo(PARK1))
// .then(moveTo(PARK2))
.then(run(() -> {
hardware.frontLeft.setPower(0.6);
hardware.frontRight.setPower(-0.6);
hardware.backLeft.setPower(-0.6);
hardware.backRight.setPower(0.6);
}))
.then(wait(0.5))
.then(run(() -> {
hardware.frontLeft.setPower(0.3);
hardware.frontRight.setPower(-0.3);
hardware.backLeft.setPower(-0.3);
hardware.backRight.setPower(0.3);
}))
.then(wait(0.5))
.then(moveTo(PARK_BAD))
//// .then(moveTo(PARK2))
// .then(run(() -> {
// hardware.frontLeft.setPower(0.6);
// hardware.frontRight.setPower(-0.6);
// hardware.backLeft.setPower(-0.6);
// hardware.backRight.setPower(0.6);
// }))
// .then(wait(0.5))
// .then(run(() -> {
// hardware.frontLeft.setPower(0.3);
// hardware.frontRight.setPower(-0.3);
// hardware.backLeft.setPower(-0.3);
// hardware.backRight.setPower(0.3);
// }))
// .then(wait(0.5))
.then(run(() -> hardware.driveMotors.setAll(0)));
// .then(moveTo(scheduler,
// new Pose(65, -12, Math.toRadians(0))))*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ abstract class TaskTemplate(override var scheduler: Scheduler) : TaskWithChainin
override var isStartRequested = false

override fun transition(newState: State) {
println("$this: transition: ${state.name} -> ${newState.name}")
// println("$this: transition: ${state.name} -> ${newState.name}")
if (state.order > newState.order) {
throw IllegalStateException("cannot move from ${state.name} to ${newState.name}")
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,13 +65,13 @@ open class MultitaskScheduler
it.transition(State.Starting)
// acquire locks
for (lock in it.requirements()) {
println("$it acquired $lock")
// println("$it acquired $lock")
if (locks[lock.id] != null) {
println("WARN: uhh we're gonna make ${tasks[locks[lock.id]]} crash when it finishes")
}
locks[lock.id] = it.myId
lockIdName[lock.id] = lock
println("locks: $locks")
// println("locks: $locks")
}
}
}
Expand Down Expand Up @@ -144,7 +144,7 @@ open class MultitaskScheduler
else println("ERROR!!! $task (which just finished) does not own lock $lock that it is supposed to own")
}
locks[lock.id] = null
println("$task released $lock")
// println("$task released $lock")
}
}

Expand Down Expand Up @@ -364,7 +364,7 @@ open class MultitaskScheduler
val dropped = tasks.filterInPlace { k, v ->
!(v.state == State.NotStarted && predicate(v))
}
println("dropped ${dropped.size} tasks: ${dropped.joinToString(", ")}")
// println("dropped ${dropped.size} tasks: ${dropped.joinToString(", ")}")
}
}

Expand Down

0 comments on commit ef6fc78

Please sign in to comment.