Skip to content
This repository has been archived by the owner on Jan 19, 2025. It is now read-only.

Commit

Permalink
Try fix teleop
Browse files Browse the repository at this point in the history
  • Loading branch information
kevinthegreat1 committed Jan 16, 2024
1 parent c167cde commit 15c62b8
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions TeleOp.java
Original file line number Diff line number Diff line change
Expand Up @@ -97,8 +97,8 @@ public void runOpMode() {

intakeWheel.setPower((gamepad2.right_trigger - gamepad2.left_trigger) * 0.8);

if (Math.abs(gamepad2.left_stick_y) > 0.001) {
outputSlide.startMoveToRelativePos((int) -gamepad2.left_stick_y * 1000);
if (Math.abs(gamepad2.left_stick_y) > 0.0001) {
outputSlide.startMoveToRelativePos((int) -gamepad2.left_stick_y * 500);
}
if (gp2.pressing(ButtonHelper.b)) {
outputSlide.startMoveToPos(1430);
Expand All @@ -109,10 +109,10 @@ public void runOpMode() {
}
outputSlide.tick();

if (gamepad1.right_trigger > 0.001 && !pivot.isPressed()) {
pivot.startMoveToRelativePos((int) -gamepad1.right_trigger * 1000);
} else if (gamepad1.left_trigger > 0.001) {
pivot.startMoveToRelativePos((int) gamepad1.left_trigger * 1000);
if (gamepad1.right_trigger > 0.0001 && !pivot.isPressed()) {
pivot.startMoveToRelativePos((int) -gamepad1.right_trigger * 200);
} else if (gamepad1.left_trigger > 0.0001) {
pivot.startMoveToRelativePos((int) gamepad1.left_trigger * 200);
}
if (gp2.pressing(ButtonHelper.dpad_up)) {
pivot.startMoveToPosToggle();
Expand Down

0 comments on commit 15c62b8

Please sign in to comment.