Skip to content

Commit

Permalink
trying to fix the auto
Browse files Browse the repository at this point in the history
  • Loading branch information
Isha290411 committed Nov 15, 2024
1 parent ea775a5 commit 5f1de9f
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ public class AutoGyro extends LinearOpMode {
// For example, use a value of 2.0 for a 12-tooth spur gear driving a 24-tooth spur gear.
// This is gearing DOWN for less speed and more torque.
// For gearing UP, use a gear ratio less than 1.0. Note this will affect the direction of wheel rotation.
static final double COUNTS_PER_MOTOR_REV = 384.5; // eg: GoBILDA 312 RPM Yellow Jacket
static final double COUNTS_PER_MOTOR_REV = 2386; // eg: GoBILDA 312 RPM Yellow Jacket
static final double DRIVE_GEAR_REDUCTION = 1.0; // No External Gearing.
static final double WHEEL_DIAMETER_INCHES = 4.0; // For figuring circumference
static final double COUNTS_PER_INCH = (COUNTS_PER_MOTOR_REV * DRIVE_GEAR_REDUCTION) /
Expand Down Expand Up @@ -197,6 +197,9 @@ public void runOpMode() {
holdHeading(TURN_SPEED, ((HoldHeading) segment).heading, ((HoldHeading) segment).holdTime);
break;
default:
telemetry.addData("class", segment.getClass().getName());
telemetry.update();
sleep(3000);
}
}
}
Expand Down Expand Up @@ -413,6 +416,7 @@ private void sendTelemetry(boolean straight) {
telemetry.addData("Error : Steer Pwr", "%5.1f : %5.1f", headingError, turnSpeed);
telemetry.addData("Wheel Speeds L : R", "%5.2f : %5.2f", leftSpeed, rightSpeed);
telemetry.update();
sleep(3000);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ public class DetectMotorType extends LinearOpMode {
public void runOpMode() {
timer = new ElapsedTime();
// Change the text in quotes to match any motor name on your robot.
motor = hardwareMap.get(DcMotorEx.class, "motor");
motor = hardwareMap.get(DcMotorEx.class, "leftBackDrive");
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
type = motor.getMotorType();
maxRPM = type.getMaxRPM();
Expand Down

0 comments on commit 5f1de9f

Please sign in to comment.