Skip to content

Commit

Permalink
update to most recent version 9.0.1
Browse files Browse the repository at this point in the history
  • Loading branch information
mecaneer23 committed Oct 13, 2023
1 parent f326c0d commit ad21025
Show file tree
Hide file tree
Showing 5 changed files with 337 additions and 131 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.Servo;

@TeleOp
public class DozerOneStick extends LinearOpMode {

private CRServo backLeft;
private CRServo backRight;
private Servo eyes;
private Servo plowLeft;
private Servo plowRight;

@Override
public void runOpMode() {
double y;
double clockwise;
double bl;
double br;
int speed = 1;
boolean shouldSlowmode = false;
boolean slowmodeChanged = false;
double plowPos = 0.1;
boolean eyesOnTurn = true;
boolean eyesChanged = false;

backLeft = hardwareMap.get(CRServo.class, "backLeft");
backRight = hardwareMap.get(CRServo.class, "backRight");
eyes = hardwareMap.get(Servo.class, "eyes");
plowLeft = hardwareMap.get(Servo.class, "plowLeft");
plowRight = hardwareMap.get(Servo.class, "plowRight");

backLeft.setDirection(CRServo.Direction.REVERSE);
plowLeft.setDirection(Servo.Direction.REVERSE);

eyes.setPosition(0.5);
plowLeft.setPosition(plowPos);
plowRight.setPosition(plowPos);

waitForStart();
if (opModeIsActive()) {
while (opModeIsActive()) {
clockwise = (double) gamepad1.left_stick_x;
y = (double) -gamepad1.left_stick_y;

if (gamepad1.dpad_up) {
y = 1.0;
} else if (gamepad1.dpad_down) {
y = -1.0;
}

if (gamepad1.dpad_right) {
clockwise = 1.0;
} else if (gamepad1.dpad_left) {
clockwise = -1.0;
}

bl = y + clockwise;
br = y - clockwise;

if (gamepad1.right_bumper) {
speed = 2;
} else if (gamepad1.left_bumper) {
speed = 4;
} else if (gamepad1.start) {
if (!slowmodeChanged) {
shouldSlowmode = !shouldSlowmode;
slowmodeChanged = true;
}
} else if (slowmodeChanged) {
slowmodeChanged = false;
} else {
speed = shouldSlowmode ? 2 : 1;
}

bl /= speed;
br /= speed;

backLeft.setPower(bl);
backRight.setPower(br);

if (gamepad1.back) {
if (!eyesChanged) {
eyesOnTurn = !eyesOnTurn;
eyesChanged = true;
}
} else if (eyesChanged){
eyesChanged = false;
}

if (eyesOnTurn) {
eyes.setPosition(0.3 * gamepad1.left_stick_x + 0.5);
} else if (gamepad1.right_stick_x != 0) {
if (eyes.getPosition() < 0.2) {
eyes.setPosition(0.2);
} else if (eyes.getPosition() > 0.8) {
eyes.setPosition(0.8);
} else {
eyes.setPosition(eyes.getPosition() + 0.01 * gamepad1.right_stick_x);
sleep(8);
}
}

if (gamepad1.right_stick_y != 0) {
if (plowPos < 0.075) {
plowPos = 0.075;
} else if (plowPos > 0.6) {
plowPos = 0.6;
} else {
plowPos += 0.01 * -gamepad1.right_stick_y;
sleep(8);
}
}
plowLeft.setPosition(plowPos);
plowRight.setPosition(plowPos);

telemetry.update();
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.Servo;

@TeleOp
public class DozerOneStickReversed extends LinearOpMode {

private CRServo backLeft;
private CRServo backRight;
private Servo eyes;
private Servo plowLeft;
private Servo plowRight;

@Override
public void runOpMode() {
double y;
double clockwise;
double bl;
double br;
int speed = 1;
boolean shouldSlowmode = false;
boolean slowmodeChanged = false;
double plowPos = 0.1;
boolean eyesOnTurn = true;
boolean eyesChanged = false;

backLeft = hardwareMap.get(CRServo.class, "backLeft");
backRight = hardwareMap.get(CRServo.class, "backRight");
eyes = hardwareMap.get(Servo.class, "eyes");
plowLeft = hardwareMap.get(Servo.class, "plowLeft");
plowRight = hardwareMap.get(Servo.class, "plowRight");

backLeft.setDirection(CRServo.Direction.REVERSE);
plowLeft.setDirection(Servo.Direction.REVERSE);

eyes.setPosition(0.5);
plowLeft.setPosition(plowPos);
plowRight.setPosition(plowPos);

waitForStart();
if (opModeIsActive()) {
while (opModeIsActive()) {
clockwise = (double) gamepad1.right_stick_x;
y = (double) -gamepad1.right_stick_y;

if (gamepad1.dpad_up) {
y = 1.0;
} else if (gamepad1.dpad_down) {
y = -1.0;
}

if (gamepad1.dpad_right) {
clockwise = 1.0;
} else if (gamepad1.dpad_left) {
clockwise = -1.0;
}

bl = y + clockwise;
br = y - clockwise;

if (gamepad1.right_bumper) {
speed = 2;
} else if (gamepad1.left_bumper) {
speed = 4;
} else if (gamepad1.start) {
if (!slowmodeChanged) {
shouldSlowmode = !shouldSlowmode;
slowmodeChanged = true;
}
} else if (slowmodeChanged) {
slowmodeChanged = false;
} else {
speed = shouldSlowmode ? 2 : 1;
}

bl /= speed;
br /= speed;

backLeft.setPower(bl);
backRight.setPower(br);

if (gamepad1.back) {
if (!eyesChanged) {
eyesOnTurn = !eyesOnTurn;
eyesChanged = true;
}
} else if (eyesChanged){
eyesChanged = false;
}

if (eyesOnTurn) {
eyes.setPosition(0.3 * gamepad1.right_stick_x + 0.5);
} else if (gamepad1.left_stick_x != 0) {
if (eyes.getPosition() < 0.2) {
eyes.setPosition(0.2);
} else if (eyes.getPosition() > 0.8) {
eyes.setPosition(0.8);
} else {
eyes.setPosition(eyes.getPosition() + 0.01 * gamepad1.left_stick_x);
sleep(8);
}
}

if (gamepad1.left_stick_y != 0) {
if (plowPos < 0.075) {
plowPos = 0.075;
} else if (plowPos > 0.6) {
plowPos = 0.6;
} else {
plowPos += 0.01 * -gamepad1.left_stick_y;
sleep(8);
}
}
plowLeft.setPosition(plowPos);
plowRight.setPosition(plowPos);

telemetry.update();
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,87 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Servo;

@TeleOp
public class DozerTwoStick extends LinearOpMode {

private CRServo backLeft;
private CRServo backRight;
private Servo eyes;
private Servo plowLeft;
private Servo plowRight;

@Override
public void runOpMode() {
double y;
double clockwise;
double bl;
double br;
int speed = 1;
boolean shouldSlowmode = false;
boolean slowmodeChanged = false;
double plowPos = 0.1;
boolean eyesOnTurn = true;
boolean eyesChanged = false;

backLeft = hardwareMap.get(CRServo.class, "backLeft");
backRight = hardwareMap.get(CRServo.class, "backRight");
eyes = hardwareMap.get(Servo.class, "eyes");
plowLeft = hardwareMap.get(Servo.class, "plowLeft");
plowRight = hardwareMap.get(Servo.class, "plowRight");

plowLeft.setDirection(Servo.Direction.REVERSE);

eyes.setPosition(0.5);
plowLeft.setPosition(plowPos);
plowRight.setPosition(plowPos);

waitForStart();
if (opModeIsActive()) {
while (opModeIsActive()) {
backLeft.setPower(gamepad1.left_stick_y);
backRight.setPower(-gamepad1.right_stick_y);

if (gamepad1.back) {
if (!eyesChanged) {
eyesOnTurn = !eyesOnTurn;
eyesChanged = true;
}
} else if (eyesChanged){
eyesChanged = false;
}

if (eyesOnTurn) {
eyes.setPosition(0.3 * -(gamepad1.left_stick_y - gamepad1.right_stick_y) + 0.5);
} else if ((gamepad1.right_trigger - gamepad1.left_trigger) != 0) {
if (eyes.getPosition() < 0.2) {
eyes.setPosition(0.2);
} else if (eyes.getPosition() > 0.8) {
eyes.setPosition(0.8);
} else {
eyes.setPosition(eyes.getPosition() + 0.01 * (gamepad1.right_trigger - gamepad1.left_trigger));
sleep(8);
}
}

if (plowPos < 0.075) {
plowPos = 0.075;
} else if (plowPos > 0.6) {
plowPos = 0.6;
} else {
plowPos += 0.01 * ((gamepad1.dpad_up ? 1 : 0) - (gamepad1.dpad_down ? 1 : 0));
sleep(8);
}

plowLeft.setPosition(plowPos);
plowRight.setPosition(plowPos);

telemetry.update();
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
#!/usr/bin/bash
git rebase upstream/master
Loading

0 comments on commit ad21025

Please sign in to comment.