From 64f9226d2931cb828335aaf6bc3246aac2990684 Mon Sep 17 00:00:00 2001 From: GZod01 Date: Mon, 25 Sep 2023 18:46:57 +0200 Subject: [PATCH] helloworld --- WeRobot-Code.java | 46 ++++++++++++++++++++++++++-------------------- 1 file changed, 26 insertions(+), 20 deletions(-) diff --git a/WeRobot-Code.java b/WeRobot-Code.java index 0a75d64..fbe41f4 100644 --- a/WeRobot-Code.java +++ b/WeRobot-Code.java @@ -6,10 +6,15 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorSimple; -@TeleOp +@TeleOp(name="WeRobot: FGC2023 OpMode", group="WeRobot") public class DualDrive extends LinearOpMode { - private DcMotor rightmotor; - private DcMotor leftmotor; + private DcMotor flm; + private DcMotor frm; + private DcMotor brm; + private DcMotor blm; + private DcMotor moissonmotor; + private DcMotor launchermotor; + private DcMotor mountmotor; @Override public void runOpMode() { @@ -17,23 +22,23 @@ public class DualDrive extends LinearOpMode { double y; float g2x; boolean ismoissonactive=false; - boolean a; - boolean y; + boolean ga; + boolean gy; boolean preva =false; - flm = hardwareMap.get(DcMotor.class, "0"); - frm = hardwareMap.get(DcMotor.class, "1"); - blm = hardwareMap.get(DcMotor.class, "2"); - brm = hardwareMap.get(DcMotor.class, "3"); - moissonmotor = hardwareMap.get(DcMotor.class, "4"); - launchermotor = hardwareMap.get(DcMotor.class, "5"); - mountmotor = hardwareMap.get(DcMotor.class, "6"); + flm = hardwareMap.get(DcMotor.class, "flm"); + frm = hardwareMap.get(DcMotor.class, "frm"); + blm = hardwareMap.get(DcMotor.class, "blm"); + brm = hardwareMap.get(DcMotor.class, "brm"); + moissonmotor = hardwareMap.get(DcMotor.class, "msn"); + launchermotor = hardwareMap.get(DcMotor.class, "lnc"); + mountmotor = hardwareMap.get(DcMotor.class, "mnt"); waitForStart(); while (opModeIsActive()) { x = gamepad1.left_stick_x; y = -gamepad1.left_stick_y; a = gamepad1.a; - gy = gamepad.y; + gy = gamepad1.y; if(a & !preva){ ismoissonactive=!ismoissonactive; preva=true; @@ -67,7 +72,7 @@ public class DualDrive extends LinearOpMode { } } public class Robot{ - public void moves(x,y,flm,frm,blm,brm){ + public void moves(float x, double y, DcMotor flm, DcMotor frm, DcMotor blm, DcMotor brm){ float approx = 0.15; boolean xnozero = (x<-approx || x>approx); boolean ynozero = (y<-approx || y>approx); @@ -93,13 +98,14 @@ public class Robot{ } } - public void diagonal(x,y,flm,frm,blm,brm){ + public void diagonal(float x, double y, DcMotor flm, DcMotor frm,DcMotor blm,DcMotor brm){ if(x>0){ if(y>0){ // North East Robot.movement(flm,frm,blm,brm,[1,0,0,1]); - }else{ + } + else{ //South East Robot.movement(flm,frm,blm,brm,[0,-1,-1,0]); } @@ -114,7 +120,7 @@ public class Robot{ } } } - public void horizontal(x,flm,frm,blm,brm){ + public void horizontal(float x,DcMotor flm,DcMotor frm,DcMotor blm,DcMotor brm){ if(x>0){ Robot.movement(flm,frm,blm,brm,[1,-1,-1,1]); }else{ @@ -124,7 +130,7 @@ public class Robot{ } - public void vertical(y,flm,frm,blm,brm){ + public void vertical(double y,DcMotor flm,DcMotor frm,DcMotor blm,DcMotor brm){ if(y>0){ Robot.movement(flm,frm,blm,brm,[1,1,1,1]); }else{ @@ -132,13 +138,13 @@ public class Robot{ } } - public void movement(flm,frm,blm,brm,list){ + public void movement(DcMotor flm,DcMotor frm,DcMotor blm,DcMotor brm,int[] list){ flm.setPower(list[0]); frm.setPower(list[1]); blm.setPower(list[2]); brm.setPower(list[3]); } - public void Rotations(g2x,flm,frm,blm,brm){ + public void Rotations(float g2x, DcMotor flm,DcMotor frm,DcMotor blm,DcMotor brm){ float approx = 0.15; boolean xnozero = (g2x<-approx || g2x>approx); if(xnozero){