From da49742d7ce3e2d30187bbc3bc91e34168100e7d Mon Sep 17 00:00:00 2001 From: Zelina974 Date: Mon, 26 Feb 2024 16:06:04 +0100 Subject: [PATCH] fix --- test.java | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/test.java b/test.java index 3b5d6c9..80a4baa 100644 --- a/test.java +++ b/test.java @@ -30,7 +30,7 @@ public class ftc2024_autonome_test extends LinearOpMode { lm = hardwareMap.get (DcMotor.class, "lm"); rm = hardwareMap.get (DcMotor.class, "rm"); - rm.setDirection(DcMotorSimple.Direction.REVERSE); + rm.setDirection(DcMotor.Direction.REVERSE); imu = hardwareMap.get(IMU.class, "imu"); imu.initialize( @@ -42,10 +42,10 @@ public class ftc2024_autonome_test extends LinearOpMode { ) ); imu.resetYaw(); - YawPitchRollAngles robotOrientation; + robotOrientation = imu.getRobotYawPitchRollAngles(); double Yaw = robotOrientation.getYaw(AngleUnit.DEGREES); - double yaw_sortie; + double yaw_sortie = 0.0; waitForStart(); @@ -55,8 +55,8 @@ public class ftc2024_autonome_test extends LinearOpMode { double [] x = new double[lm_p.length]; for(int i = 0; i< lm_p.length; i++){ while (opModeIsActive() && Yaw < 90){ - lm.setPower = lm_p[i]; - rm.setPower = rm_p[i]; + lm.setPower(lm_p[i]); + rm.setPower(rm_p[i]); Yaw = robotOrientation.getYaw(AngleUnit.DEGREES); telemetry.addData("Yaw : ", Yaw); telemetry.update();