Skip to content

Commit

Permalink
1.1
Browse files Browse the repository at this point in the history
  • Loading branch information
ToborUser committed Jan 26, 2024
1 parent c9068e3 commit 79d1b20
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ public void runInitLoop() {

}

@Override //290
@Override
public void runStart() {
forwardAuto(3, 3,500); //
strafeLeftAuto(8,3,500); //
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,26 +50,25 @@ public void runInit() {
//arm = hardwareMap.dcMotor.get("arm");
mapMotors(hardwareMap, Wheels.FRONT_LEFT.abbreviation(),Wheels.FRONT_RIGHT.abbreviation(),Wheels.BACK_LEFT.abbreviation(),Wheels.BACK_RIGHT.abbreviation());
forwardMotors(true,false,true,false);
sensorRange = hardwareMap.get(DistanceSensor.class, "eye");
// ^ set motor directions
initAprilTag(hardwareMap, "Webcam 1", telemetry);
sensorRange = hardwareMap.get(DistanceSensor.class, "color");
Encoders.use();
Encoders.clear();



}

@Override
public void runInitLoop(){}

@Override
public void runStart() {
backwardAuto(5,1,500); // away from wall.
sleep(2000);
turnRightAuto(800, 1, 500); // straighten out.
sleep(2000);
forwardAuto(5,1,500);
sleep(2000);
strafeRightAuto(5,1,500);
backwardAuto(13,3,200); // away from wall.
turnRightAuto(580+45+22,3,500);
// styles said 290 should = 45 degrees so 45 + 45 is 90 so 580 because 290 + 290 = 580

/*sleep(2500);
backwardAuto(5,1,500);
sleep(2500);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,12 +17,18 @@ public static void forwardAuto(double inches, long seconds, int encoderSpeed) {
Encoders.target(-finalTicks,-finalTicks,-finalTicks,-finalTicks); // sets target position
Encoders.go(); // goes to target position
drive(-encoderSpeed,-encoderSpeed,-encoderSpeed,-encoderSpeed); // sets the velocity drive
driveStop();
sleep(seconds*1000);
driveStop();
}

public static void backwardAuto(double inches, long seconds, int encoderSpeed) { // forward good.
forwardAuto(-inches, seconds, -encoderSpeed);
int finalTicks = (int) (inches * ticksPerInch);
Encoders.clear(); // resets wheel encoders
Encoders.target(finalTicks,finalTicks,finalTicks,finalTicks); // sets target position
Encoders.go(); // goes to target position
drive(encoderSpeed,encoderSpeed,encoderSpeed,encoderSpeed); // sets the velocity drive
sleep(seconds*1000);
driveStop();
}

public static void strafeLeftAuto(double inches, long seconds, int encoderSpeed) { // strafe good. // this is left
Expand All @@ -31,8 +37,9 @@ public static void strafeLeftAuto(double inches, long seconds, int encoderSpeed)
Encoders.target(finalTicks,-finalTicks,-finalTicks,finalTicks); // sets target position
Encoders.go(); // goes to target position // fl, fr, bl, br
drive(encoderSpeed,-encoderSpeed,-encoderSpeed,encoderSpeed); // sets the velocity drive
driveStop();
sleep(seconds*1000);
driveStop();

}

public static void strafeRightAuto(double inches, long seconds, int encoderSpeed) { // strafe good. // this is left
Expand All @@ -45,8 +52,8 @@ public static void turnRightAuto(float degrees, long seconds, int encoderSpeed)
Encoders.target(-finalTicks,finalTicks,-finalTicks,finalTicks); // sets target position
Encoders.go(); // goes to target position // fl, fr, bl, br
drive(-encoderSpeed,encoderSpeed,-encoderSpeed,encoderSpeed); // sets the velocity drive
driveStop();
sleep(seconds*1000);
driveStop();
}

public static void turnLeftAuto(float degrees, long seconds, int encoderSpeed) { // turn
Expand Down

0 comments on commit 79d1b20

Please sign in to comment.