From f07cbd1d2ff64c64585ab2f7e1b9c7a538e747b6 Mon Sep 17 00:00:00 2001 From: GZod01 Date: Sun, 10 Mar 2024 16:16:06 +0100 Subject: [PATCH] mode "n" harvest tiles on field --- ftc2024_autonome_api.java | 75 ++++++++++++++++++++++++++++++++------- 1 file changed, 63 insertions(+), 12 deletions(-) diff --git a/ftc2024_autonome_api.java b/ftc2024_autonome_api.java index deb9049..fffde94 100644 --- a/ftc2024_autonome_api.java +++ b/ftc2024_autonome_api.java @@ -27,6 +27,7 @@ public class ftc2024_autonome_api extends LinearOpMode { public DcMotor rm; public DcMotor harvestmotor; public IMU imu; + public YawPitchRollAngle robotOrientation; @Override public void runOpMode() { @@ -46,7 +47,7 @@ public class ftc2024_autonome_api extends LinearOpMode { ) ); imu.resetYaw(); - YawPitchRollAngle robotOrientation; // FTC2024WeRobotControl à besoin de robotOrientation comme variable de Parent (donc de cette classe actuelle), n'est il pas posible de définir robotOrientation dans la classe + // YawPitchRollAngle robotOrientation; // FTC2024WeRobotControl à besoin de robotOrientation comme variable de Parent (donc de cette classe actuelle), n'est il pas posible de définir robotOrientation dans la classe? FTC2024WeRobotControl robot = FTC2024WeRobotControl(this); waitForStart(); @@ -66,7 +67,7 @@ public class ftc2024_autonome_api extends LinearOpMode { switch (autonomous_mode){ default: robot.forward(0.5); - robot.rotate(-90.0); + robot.rotate((-90)); robot.forward(1.5); robot.harvest(-1); robot.backward(1); @@ -74,7 +75,7 @@ public class ftc2024_autonome_api extends LinearOpMode { break; case ("b2d"): robot.forward(0.5); - robot.rotate(-90.0); + robot.rotate((-90)); robot.forward(2.5); robot.harvest(-1); robot.backward(1); @@ -82,7 +83,7 @@ public class ftc2024_autonome_api extends LinearOpMode { break; case ("r4d"): robot.forward(0.5); - robot.rotate(90.0); + robot.rotate(90); robot.forward(1.5); robot.harvest(-1); robot.backward(1); @@ -90,25 +91,75 @@ public class ftc2024_autonome_api extends LinearOpMode { break; case ("r2d"): robot.forward(0.5); - robot.rotate(90.0); + robot.rotate(90); robot.forward(2.5); robot.harvest(-1); robot.backward(1); robot.harvest(0); break; - case ("b4n"): - + robot.forward(1.5); + robot.rotate(90); + robot.harvest(); + robot.forward(3); + robot.harvest(0); + robot.rotate(180); + robot.forward(1); + robot.rotate(-90); + robot.forward(1); + robot.rotate(90); + robot.forward(2.5); + robot.harvest(-1); + robot.backward(1); + robot.harvest(0); break; case ("b2n"): - + robot.forward(1.5); + robot.rotate(90); + robot.harvest(); + robot.forward(1); + robot.harvest(0); + robot.rotate(180); + robot.forward(1); + robot.rotate(-90); + robot.forward(1); + robot.rotate(90); + robot.forward(2.5); + robot.harvest(-1); + robot.backward(1); + robot.harvest(0); break; - case ("r4n"): - + case ("r4n"): + robot.forward(1.5); + robot.rotate(-90); + robot.harvest(); + robot.forward(3); + robot.harvest(0); + robot.rotate(180); + robot.forward(1); + robot.rotate(90); + robot.forward(1); + robot.rotate(-90); + robot.forward(2.5); + robot.harvest(-1); + robot.backward(1); + robot.harvest(0); break; case ("r2n"): - - break; + robot.forward(1.5); + robot.rotate(-90); + robot.harvest(); + robot.forward(1); + robot.harvest(0); + robot.rotate(180); + robot.forward(1); + robot.rotate(90); + robot.forward(1); + robot.rotate(-90); + robot.forward(2.5); + robot.harvest(-1); + robot.backward(1); + robot.harvest(0); } } }