From e5d1c81fbc07afa360f7f1f357392af6914d3148 Mon Sep 17 00:00:00 2001 From: GZod01 Date: Thu, 7 Mar 2024 16:28:23 +0100 Subject: [PATCH] Update autonome_api.java --- autonome_api.java | 51 +++++++++-------------------------------------- 1 file changed, 9 insertions(+), 42 deletions(-) diff --git a/autonome_api.java b/autonome_api.java index ae902e8..c27825c 100644 --- a/autonome_api.java +++ b/autonome_api.java @@ -23,10 +23,10 @@ public class ftc2024_autonome_api extends LinearOpMode { private DcMotor rm; private DcMotor lm; private IMU imu; - private static double wheel_width = 9.0e-2; // metres - private static double wheel_perimeter = Math.PI * wheel_width; - private static double tour_par_minutes = 300.0; - private static double ground_tiles_width = 61.0e-2; // metres + private final double wheel_width = 9.0e-2; // metres + private final double wheel_perimeter = Math.PI * wheel_width; + private final double tour_par_minutes = 300.0; + private final double ground_tiles_width = 61.0e-2; // metres /* * return a metre/sec speed * @param motor_speed = double between 0 and 1 @@ -41,7 +41,7 @@ public class ftc2024_autonome_api extends LinearOpMode { return (dist/speed); } public void forward(double n_tiles, double motor_speed = 1.0){ - double total_time = time_for_dist(n_tiles, motor_speed); + double total_time = time_for_dist(n_tiles*ground_tiles_width, motor_speed); double start_time = runtime.seconds(); while( opModeIsActive() && ((runtime.seconds()-start_time)