diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Autonomoustest.java similarity index 98% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Autonomoustest.java index 599800b..b092fd5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Autonomoustest.java @@ -30,10 +30,8 @@ package org.firstinspires.ftc.teamcode; import com.qualcomm.robotcore.eventloop.opmode.Autonomous; -import com.qualcomm.robotcore.eventloop.opmode.Disabled; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.hardware.DcMotor; -import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.util.ElapsedTime; /** @@ -64,7 +62,7 @@ import com.qualcomm.robotcore.util.ElapsedTime; @Autonomous(name="Robot: Auto Drive By Encoder", group="Robot") //@Disabled -public class RobotAutoDriveByEncoder_Linear extends LinearOpMode { +public class Autonomoustest extends LinearOpMode { /* Declare OpMode members. */ private DcMotor leftDrive = null; @@ -86,7 +84,7 @@ public class RobotAutoDriveByEncoder_Linear extends LinearOpMode { static final double DRIVE_GEAR_REDUCTION = 1.0 ; // No External Gearing. static final double WHEEL_DIAMETER_INCHES = 3.77953 ; // For figuring circumference static final double COUNTS_PER_INCH = (COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION) / - (WHEEL_DIAMETER_INCHES * 3.1415); + (WHEEL_DIAMETER_INCHES * Math.PI); static final double DRIVE_SPEED = 0.2; static final double TURN_SPEED = 0.4; @@ -132,8 +130,9 @@ public class RobotAutoDriveByEncoder_Linear extends LinearOpMode { // Step through each leg of the path, // Note: Reverse movement is obtained by setting a negative distance (not speed) //driveForward(2); - //straightLeft(93); - turnRight(90); + //driveForward(80); + driveForward(28); + //turnRight(90);