From 70ac99c5b3cf52236beae044a573fa1c396c614c Mon Sep 17 00:00:00 2001 From: robotics2 Date: Thu, 28 Sep 2023 17:10:30 -0700 Subject: [PATCH] have directional functions set for each direction --- .../RobotAutoDriveByEncoder_Linear.java | 56 +++++++++++++++++-- 1 file changed, 52 insertions(+), 4 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java index 354b006..599800b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RobotAutoDriveByEncoder_Linear.java @@ -90,7 +90,8 @@ public class RobotAutoDriveByEncoder_Linear extends LinearOpMode { static final double DRIVE_SPEED = 0.2; static final double TURN_SPEED = 0.4; - @Override + static final double LONG_TIMEOUT = 1000; + static final double DEGREE_TOO_DISTANCE = 0.21944444444; @Override public void runOpMode() { // Initialize the drive system variables. @@ -130,15 +131,62 @@ 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) - encoderDrive(DRIVE_SPEED, 48, 48, 5.0); // S1: Forward 47 Inches with 5 Sec timeout - //encoderDrive(TURN_SPEED, 12, -12, 4.0); // S2: Turn Right 12 Inches with 4 Sec timeout - //encoderDrive(DRIVE_SPEED, -24, -24, 4.0); // S3: Reverse 24 Inches with 4 Sec timeout + //driveForward(2); + //straightLeft(93); + turnRight(90); + + + + //Values were created from robot with wheel issues 9/28/23 telemetry.addData("Path", "Complete"); telemetry.update(); sleep(1000); // pause to display final telemetry message. } + public void driveForward(double distance) + { + leftDrive.setDirection(DcMotor.Direction.REVERSE); + rightDrive.setDirection(DcMotor.Direction.FORWARD); + backrightDrive.setDirection(DcMotor.Direction.REVERSE); + backleftDrive.setDirection(DcMotor.Direction.REVERSE); + encoderDrive(DRIVE_SPEED, distance, distance, LONG_TIMEOUT); // S1: Forward 47 Inches with 5 Sec timeout + } + public void straightLeft(double distance) + { + leftDrive.setDirection(DcMotor.Direction.FORWARD); + rightDrive.setDirection(DcMotor.Direction.FORWARD); + backrightDrive.setDirection(DcMotor.Direction.FORWARD); + backleftDrive.setDirection(DcMotor.Direction.REVERSE); + encoderDrive(DRIVE_SPEED, distance, distance, LONG_TIMEOUT); + } + public void straightRight(double distance) + { + leftDrive.setDirection(DcMotor.Direction.REVERSE); + rightDrive.setDirection(DcMotor.Direction.REVERSE); + backrightDrive.setDirection(DcMotor.Direction.REVERSE); + backleftDrive.setDirection(DcMotor.Direction.FORWARD); + encoderDrive(DRIVE_SPEED, distance, distance, LONG_TIMEOUT); + } + public void turnLeft(double degrees) + { + leftDrive.setDirection(DcMotor.Direction.FORWARD); + rightDrive.setDirection(DcMotor.Direction.FORWARD); + backrightDrive.setDirection(DcMotor.Direction.REVERSE); + backleftDrive.setDirection(DcMotor.Direction.FORWARD); + double turning_distance = degrees * DEGREE_TOO_DISTANCE; + encoderDrive(DRIVE_SPEED, turning_distance, turning_distance, LONG_TIMEOUT); + } + public void turnRight(double degrees) + { + leftDrive.setDirection(DcMotor.Direction.REVERSE); + rightDrive.setDirection(DcMotor.Direction.REVERSE); + backrightDrive.setDirection(DcMotor.Direction.FORWARD); + backleftDrive.setDirection(DcMotor.Direction.REVERSE); + double turning_distance = degrees * DEGREE_TOO_DISTANCE; + encoderDrive(DRIVE_SPEED, turning_distance, turning_distance, LONG_TIMEOUT); + } + /* * Method to perform a relative move, based on encoder counts. * Encoders are not reset as the move is based on the current position.