Skip to content

Commit dcdcf39

Browse files
committed
Created my first OpMode for Mecanum Drive
1 parent 18b9284 commit dcdcf39

File tree

1 file changed

+51
-0
lines changed

1 file changed

+51
-0
lines changed
Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
package org.firstinspires.ftc.teamcode.OpModes.learning;
2+
3+
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
4+
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
5+
import com.qualcomm.robotcore.hardware.DcMotor;
6+
import com.qualcomm.robotcore.hardware.DcMotorSimple;
7+
8+
import org.firstinspires.ftc.teamcode.Constants;
9+
10+
@TeleOp(name="Chase's OpMode", group = "Example OpMode")
11+
public class ChaseFirstOpMode extends OpMode {
12+
private DcMotor frontLeftMotor;
13+
private DcMotor frontRightMotor;
14+
private DcMotor backLeftMotor;
15+
private DcMotor backRightMotor;
16+
17+
@Override
18+
public void init() {
19+
frontLeftMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.flMotorName);
20+
frontRightMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.frMotorName);
21+
backLeftMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.blMotorName);
22+
backRightMotor = hardwareMap.get(DcMotor.class, Constants.Drivetrain.brMotorName);
23+
24+
frontLeftMotor.setDirection(DcMotorSimple.Direction.REVERSE);
25+
backLeftMotor.setDirection(DcMotorSimple.Direction.REVERSE);
26+
27+
telemetry.addData("Status", "Initialized");
28+
telemetry.update();
29+
}
30+
31+
@Override
32+
public void loop() {
33+
double y = gamepad1.left_stick_y;
34+
double x = gamepad1.left_stick_x;
35+
double rx = gamepad1.right_stick_x;
36+
37+
double denominator = Math.max(Math.abs(x) + Math.abs(y) + Math.abs(rx), 1);
38+
double frontLeftPower = (y + x + rx) / denominator;
39+
double frontRightPower = (y - x - rx) / denominator;
40+
double backLeftPower = (y - x + rx) / denominator;
41+
double backRightPower = (y + x - rx) / denominator;
42+
43+
frontLeftMotor.setPower(frontLeftPower);
44+
frontRightMotor.setPower(frontRightPower);
45+
backLeftMotor.setPower(backLeftPower);
46+
backRightMotor.setPower(backRightPower);
47+
48+
telemetry.addData("Status", "Running");
49+
telemetry.update();
50+
}
51+
}

0 commit comments

Comments
 (0)