Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
package org.firstinspires.ftc.teamcode.OpModes.learning;

import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;

import org.firstinspires.ftc.teamcode.Constants;

@TeleOp(name="Chase's OpMode", group = "Example OpMode")
Copy link

Copilot AI Nov 12, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Missing @disabled annotation. All other learning OpModes (BrodysFIRSTOpMode.java and NicksFIRSTJavaOpMode.java) include the @disabled annotation to prevent accidental selection during competition. Add @Disabled on line 11 before the class declaration for consistency with the team's learning OpMode pattern.

Suggested change
@TeleOp(name="Chase's OpMode", group = "Example OpMode")
@TeleOp(name="Chase's OpMode", group = "Example OpMode")
@com.qualcomm.robotcore.eventloop.opmode.Disabled

Copilot uses AI. Check for mistakes.
public class ChaseFirstOpMode extends OpMode {
private DcMotor frontLeftMotor;
private DcMotor frontRightMotor;
private DcMotor backLeftMotor;
private DcMotor backRightMotor;

@Override
public void init() {
frontLeftMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.flMotorName);
frontRightMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.frMotorName);
backLeftMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.blMotorName);
backRightMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.brMotorName);

frontLeftMotor.setDirection(DcMotorSimple.Direction.REVERSE);
backLeftMotor.setDirection(DcMotorSimple.Direction.REVERSE);

telemetry.addData("Status", "Initialized");
telemetry.update();
}

@Override
public void loop() {
double y = gamepad1.left_stick_y;
Copy link

Copilot AI Nov 12, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The Y-axis should be negated. In FTC, the gamepad's left_stick_y returns negative values when pushed forward. Other learning OpModes in this directory (BrodysFIRSTOpMode.java and NicksFIRSTJavaOpMode.java) use -gamepad1.left_stick_y to ensure pushing the stick forward makes the robot move forward. Without negation, the robot will move backward when the stick is pushed forward.

Suggested change
double y = gamepad1.left_stick_y;
double y = -gamepad1.left_stick_y;

Copilot uses AI. Check for mistakes.
double x = gamepad1.left_stick_x;
double rx = gamepad1.right_stick_x;

double denominator = Math.max(Math.abs(x) + Math.abs(y) + Math.abs(rx), 1);
double frontLeftPower = (y + x + rx) / denominator;
double frontRightPower = (y - x - rx) / denominator;
double backLeftPower = (y - x + rx) / denominator;
double backRightPower = (y + x - rx) / denominator;

frontLeftMotor.setPower(frontLeftPower);
frontRightMotor.setPower(frontRightPower);
backLeftMotor.setPower(backLeftPower);
backRightMotor.setPower(backRightPower);

telemetry.addData("Status", "Running");
telemetry.update();
}
Copy link

Copilot AI Nov 12, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

[nitpick] Missing stop() method override. For consistency with other learning OpModes in this directory, consider adding a stop() method that updates telemetry status to 'Stopped', similar to BrodysFIRSTOpMode.java and NicksFIRSTJavaOpMode.java. This helps students understand the complete OpMode lifecycle.

Suggested change
}
}
@Override
public void stop() {
telemetry.addData("Status", "Stopped");
telemetry.update();
}

Copilot uses AI. Check for mistakes.
}
Loading