From 90e5e8ca55556d185d1efe2cef3dfd40e3645718 Mon Sep 17 00:00:00 2001 From: ryan C <147014849+luenix1@users.noreply.github.com> Date: Sat, 30 Nov 2024 14:23:27 -0800 Subject: [PATCH 1/3] making life easier for drivers since 2024(pick up and store specimejn) --- .../ftc/teamcode/MecanumTeleOp.java | 22 ++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java index 1b725980cfc1..277cd688071b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java @@ -369,17 +369,29 @@ private void PickUpSpecimen(Hardware hardware) { sleep(500); hardware.arm.setMode(DcMotor.RunMode.RUN_TO_POSITION); hardware.arm.setPower(0.5); - hardware.arm.setTargetPosition(170); + hardware.arm.setTargetPosition(90); sleep(500); hardware.verticalSlide.setTargetPosition(0); maintainHeightTicks = 0; sleep(500); - hardware.wrist.setPosition(1.0); + hardware.wrist.setPosition(1); + sleep(500); + hardware.claw.setPosition(0.02); // TBD sleep(500); hardware.twist.setPosition(0.17); sleep(500); - hardware.claw.setPosition(0.02); // TBD -// sleep(5000); - armTargetPosDeg = 87.58; + hardware.arm.setTargetPosition(145); + sleep(500); + hardware.claw.setPosition(0.55); + sleep(500); + hardware.wrist.setPosition(0.5); + sleep(500); + hardware.verticalSlide.setTargetPosition(300); + sleep(500); + hardware.arm.setTargetPosition(0); + sleep(500); + hardware.verticalSlide.setTargetPosition(0); + sleep(500); + armTargetPosDeg = 0; } } From 9c066e4bf0e8153f678818a319f016456ba8ec8e Mon Sep 17 00:00:00 2001 From: ryan C <147014849+luenix1@users.noreply.github.com> Date: Sat, 30 Nov 2024 15:04:43 -0800 Subject: [PATCH 2/3] not good --- .../ftc/teamcode/MecanumTeleOp.java | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java index 277cd688071b..ee82d17fc279 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java @@ -107,6 +107,9 @@ public void runOpMode() { servoMoves(); twist(); lift(hardware); + if(gamepad1.x){ + transfer(hardware); + } if (gamepad2.y) { ScoreHighBasket(hardware); } @@ -394,4 +397,17 @@ private void PickUpSpecimen(Hardware hardware) { sleep(500); armTargetPosDeg = 0; } + private void transfer(Hardware hardware){ + hardware.arm.setPower(-0.5); + hardware.verticalSlide.setMode(DcMotor.RunMode.RUN_TO_POSITION); + hardware.verticalSlide.setPower(VerticalSlideSpeed); + hardware.verticalSlide.setTargetPosition(900); + maintainHeightTicks = 900; + sleep(500); + hardware.arm.setTargetPosition(33); + sleep(500); + hardware.wrist.setPosition(0.9); + sleep(500); + armTargetPosDeg=33; + } } From 183e072dbacde345283d51f349e788e8604c0d64 Mon Sep 17 00:00:00 2001 From: ryan C <147014849+luenix1@users.noreply.github.com> Date: Sat, 30 Nov 2024 19:20:53 -0800 Subject: [PATCH 3/3] GOOD!!!!!!!!! for now for now --- .../ftc/teamcode/MecanumTeleOp.java | 35 ++++++++++++++++--- 1 file changed, 30 insertions(+), 5 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java index ee82d17fc279..d82e5c30f5eb 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumTeleOp.java @@ -398,16 +398,41 @@ private void PickUpSpecimen(Hardware hardware) { armTargetPosDeg = 0; } private void transfer(Hardware hardware){ - hardware.arm.setPower(-0.5); + //hardware.arm.setPower(-0.5); + hardware.verticalSlide.setTargetPosition(900); hardware.verticalSlide.setMode(DcMotor.RunMode.RUN_TO_POSITION); hardware.verticalSlide.setPower(VerticalSlideSpeed); - hardware.verticalSlide.setTargetPosition(900); maintainHeightTicks = 900; sleep(500); - hardware.arm.setTargetPosition(33); + hardware.arm.setTargetPosition(-63);//This is in ticks + hardware.arm.setMode(DcMotor.RunMode.RUN_TO_POSITION); + hardware.arm.setPower(0.5); + armTargetPosDeg=-30;//(752 ticks /360 degrees) sleep(500); hardware.wrist.setPosition(0.9); - sleep(500); - armTargetPosDeg=33; + sleep(2000); + hardware.claw.setPosition(0.02); + sleep(2000); + hardware.verticalSlide.setTargetPosition(735); + hardware.verticalSlide.setMode(DcMotor.RunMode.RUN_TO_POSITION); + hardware.verticalSlide.setPower(VerticalSlideSpeed); + maintainHeightTicks = 735; + sleep(2000); + hardware.claw.setPosition(0.55); + sleep(1000); + hardware.wrist.setPosition(0.45); + hardware.arm.setTargetPosition(0); + hardware.arm.setMode(DcMotor.RunMode.RUN_TO_POSITION); + hardware.arm.setPower(0.5); + armTargetPosDeg=0; + sleep(1000); + hardware.verticalSlide.setTargetPosition(0); + hardware.verticalSlide.setMode(DcMotor.RunMode.RUN_TO_POSITION); + hardware.verticalSlide.setPower(VerticalSlideSpeed); + maintainHeightTicks = 0; + + //To-Do: open horizontal claw + + } }