Skip to content

Commit

Permalink
Pre-comp tweaks
Browse files Browse the repository at this point in the history
  • Loading branch information
penguinencounter committed Feb 10, 2024
1 parent 9bbe69c commit 7e03fa5
Show file tree
Hide file tree
Showing 4 changed files with 37 additions and 13 deletions.
14 changes: 14 additions & 0 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Var.kt
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,20 @@ object Var {
const val back = 1.0
}

object DropDownServo {
@JvmField
val positions = doubleArrayOf(
0.60,
// 0.4944,
// 0.4538,
// 0.3999,
// 0.3760,
0.2892
)
@JvmField
val up = positions[0]
}

object TeleOp {
/**
* Target distance for approaching objects with the 'x' button on Gamepad 1.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ public class HWTest extends LinearOpMode {
boolean lastA = false;
boolean lastB = false;

boolean verbalize = false;

RobotConfiguration robot;

/**
Expand All @@ -31,6 +33,9 @@ boolean confirm(String message) {
for (String line : message.split("\n")) {
telemetry.addLine(line);
}
if (verbalize) {
telemetry.speak(message);
}
telemetry.addLine();
telemetry.addLine("[A]: YES or [B]: NO");
telemetry.update();
Expand All @@ -55,6 +60,9 @@ void alert(String message) {
for (String line : message.split("\n")) {
telemetry.addLine(line);
}
if (verbalize) {
telemetry.speak(message);
}
telemetry.addLine();
telemetry.addLine("[A]: Confirm");
telemetry.update();
Expand All @@ -68,11 +76,15 @@ void alert(String message) {
}

void testMotor(String label, DcMotor theMotor) {
testMotor(label, theMotor, "moving forward");
}

void testMotor(String label, DcMotor theMotor, String action) {
lastA = gamepad1.a;
lastB = gamepad1.b;
theMotor.setPower(0.25);
telemetry.addLine("The " + label + " motor should");
telemetry.addLine("be moving forward...");
telemetry.addLine("be " + action + "...");
telemetry.addLine();
telemetry.addLine("[A]: OK [B]: STOP");
telemetry.update();
Expand Down Expand Up @@ -100,6 +112,9 @@ void testMotors() {
testMotor("Front Right", motors.frontRight);
testMotor("Back Left", motors.backLeft);
testMotor("Back Right", motors.backRight);
testMotor("Intake", robot.intake(), "turning reverse (outtaking)");
alert("Remove the drone from the launcher if it is present...");
testMotor("Drone", robot.drone(), "spinning");
}

void testEncoder(String label, DcMotor encoded) {
Expand Down Expand Up @@ -175,6 +190,7 @@ public void runOpMode() {
robot = RobotConfiguration.currentConfiguration().invoke(hardwareMap);
waitForStart();
try {
verbalize = confirm("Say instructions out loud?");
testMotors();
testEncoders();
testSensors();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,14 +62,6 @@ public double OdoToInches(double ticks) {
return (num_wheel_rotations * 2 * Math.PI * radius_inches);
}

public static final double[] DropdownPositions = {
0.60, // X button
0.49,
0.45,
0.41,
0.35
};

@Override
public void runOpMode() {

Expand All @@ -87,7 +79,7 @@ public void runOpMode() {
MotorSet<DcMotor> driveMotors = robot.driveMotors();

int dropCycle = 0;
robot.dropDownServo().setPosition(DropdownPositions[dropCycle]);
robot.dropDownServo().setPosition(Var.DropDownServo.positions[dropCycle]);

Servo dumperServo = robot.dumperRotate();
Servo latch = robot.dumperLatch();
Expand Down Expand Up @@ -275,13 +267,14 @@ public void runOpMode() {

if (gamepad2.y && !lastAdvDropper) {
dropCycle++;
if (dropCycle >= DropdownPositions.length) dropCycle = DropdownPositions.length - 1;
robot.dropDownServo().setPosition(DropdownPositions[dropCycle]);
if (dropCycle >= Var.DropDownServo.positions.length)
dropCycle = Var.DropDownServo.positions.length - 1;
robot.dropDownServo().setPosition(Var.DropDownServo.positions[dropCycle]);
}
lastAdvDropper = gamepad2.y;
if (gamepad2.x) {
dropCycle = 0;
robot.dropDownServo().setPosition(DropdownPositions[dropCycle]);
robot.dropDownServo().setPosition(Var.DropDownServo.up);
}

if (gamepad2.right_bumper) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -297,6 +297,7 @@ public void runOpMode() throws InterruptedException {
// Set up robot hardware
robot.clearEncoders();
robot.purpleDropper().setPosition(Var.PixelDropper.up);
robot.dropDownServo().setPosition(Var.DropDownServo.up);

double buttonRepeatDelay = 0.4;
double buttonRepeatRate = 0.2;
Expand Down

0 comments on commit 7e03fa5

Please sign in to comment.