From 5442791e2df475e81277fe8ff248321b87444b45 Mon Sep 17 00:00:00 2001 From: GZod01 Date: Tue, 9 Jul 2024 16:03:29 +0200 Subject: [PATCH] Co-authored-by: Zelina974 --- FGC_2024.java | 23 +++++++++++++++++------ 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/FGC_2024.java b/FGC_2024.java index 11c9127..38326a3 100644 --- a/FGC_2024.java +++ b/FGC_2024.java @@ -31,13 +31,8 @@ public class FGC_2024 extends LinearOpMode { private DcMotorEx elv1; //private DcMotorEx elv2; //private DcMotorEx elv3; - /* - * @description

Useful

- */ - public static void hello(re){return re*2;} @Override public void runOpMode() throws InterruptedException { - this telemetry.addData("Status"," Initialized"); telemetry.update(); @@ -84,7 +79,23 @@ public class FGC_2024 extends LinearOpMode { lpower = lpower*gamepad1.right_trigger; rpower = rpower*gamepad1.right_trigger; } - + if(gamepad1.dpad_right){ + elv1.setVelocity(20); + elv1.setTargetPosition(elv1.getCurrentPosition()+1); + elv1.setMode(DcMotor.RunMode.RUN_TO_POSITION); + } + if(gamepad1.dpad_left){ + elv1.setVelocity(20); + elv1.setTargetPosition(elv1.getCurrentPosition()-1); + elv1.setMode(DcMotor.RunMode.RUN_TO_POSITION); + } + if(gamepad1.dpad_down){ + elv1.setVelocity(0); + elv1.setTargetPosition(elv1.getCurrentPosition()); + elv1.setMode(DcMotor.RunMode.RUN_TO_POSITION); + } + telemetry.addData("targetPos",elv1.getTargetPosition()); + telemetry.addData("pos", elv1.getCurrentPosition()) if (gamepad1.dpad_up && !already_up && hauteur<3){ elv1.setVelocity(250);