Skip to content

Commit

Permalink
Merge pull request FIRST-Tech-Challenge#4 from derryfieldftc/AS-mecanum
Browse files Browse the repository at this point in the history
Add Mecanum classes to base
  • Loading branch information
25ASmith-DS committed Oct 21, 2023
2 parents f326c0d + 9c1ce53 commit 4031bbb
Show file tree
Hide file tree
Showing 10 changed files with 253 additions and 0 deletions.
28 changes: 28 additions & 0 deletions .project
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>FtcRobotController</name>
<comment>Project FtcRobotController created by Buildship.</comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>org.eclipse.buildship.core.gradleprojectbuilder</name>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.buildship.core.gradleprojectnature</nature>
</natures>
<filteredResources>
<filter>
<id>1697888154165</id>
<name></name>
<type>30</type>
<matcher>
<id>org.eclipse.core.resources.regexFilterMatcher</id>
<arguments>node_modules|\.git|__CREATED_BY_JAVA_LANGUAGE_SERVER__</arguments>
</matcher>
</filter>
</filteredResources>
</projectDescription>
13 changes: 13 additions & 0 deletions .settings/org.eclipse.buildship.core.prefs
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
arguments=--init-script /home/asmi/.cache/jdtls/config/org.eclipse.osgi/223/0/.cp/gradle/init/init.gradle
auto.sync=false
build.scans.enabled=false
connection.gradle.distribution=GRADLE_DISTRIBUTION(WRAPPER)
connection.project.dir=
eclipse.preferences.version=1
gradle.user.home=
java.home=/usr/lib/jvm/java-17-openjdk
jvm.arguments=
offline.mode=false
override.workspace.settings=true
show.console.view=true
show.executions.view=true
6 changes: 6 additions & 0 deletions FtcRobotController/.classpath
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<classpath>
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER/org.eclipse.jdt.internal.debug.ui.launcher.StandardVMType/JavaSE-17/"/>
<classpathentry kind="con" path="org.eclipse.buildship.core.gradleclasspathcontainer"/>
<classpathentry kind="output" path="bin/default"/>
</classpath>
34 changes: 34 additions & 0 deletions FtcRobotController/.project
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>FtcRobotController-FtcRobotController</name>
<comment>Project FtcRobotController-FtcRobotController created by Buildship.</comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>org.eclipse.jdt.core.javabuilder</name>
<arguments>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.buildship.core.gradleprojectbuilder</name>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.jdt.core.javanature</nature>
<nature>org.eclipse.buildship.core.gradleprojectnature</nature>
</natures>
<filteredResources>
<filter>
<id>1697888154168</id>
<name></name>
<type>30</type>
<matcher>
<id>org.eclipse.core.resources.regexFilterMatcher</id>
<arguments>node_modules|\.git|__CREATED_BY_JAVA_LANGUAGE_SERVER__</arguments>
</matcher>
</filter>
</filteredResources>
</projectDescription>
2 changes: 2 additions & 0 deletions FtcRobotController/.settings/org.eclipse.buildship.core.prefs
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
connection.project.dir=..
eclipse.preferences.version=1
6 changes: 6 additions & 0 deletions TeamCode/.classpath
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<classpath>
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER/org.eclipse.jdt.internal.debug.ui.launcher.StandardVMType/JavaSE-17/"/>
<classpathentry kind="con" path="org.eclipse.buildship.core.gradleclasspathcontainer"/>
<classpathentry kind="output" path="bin/default"/>
</classpath>
34 changes: 34 additions & 0 deletions TeamCode/.project
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>TeamCode</name>
<comment>Project TeamCode created by Buildship.</comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>org.eclipse.jdt.core.javabuilder</name>
<arguments>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.buildship.core.gradleprojectbuilder</name>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.jdt.core.javanature</nature>
<nature>org.eclipse.buildship.core.gradleprojectnature</nature>
</natures>
<filteredResources>
<filter>
<id>1697888154169</id>
<name></name>
<type>30</type>
<matcher>
<id>org.eclipse.core.resources.regexFilterMatcher</id>
<arguments>node_modules|\.git|__CREATED_BY_JAVA_LANGUAGE_SERVER__</arguments>
</matcher>
</filter>
</filteredResources>
</projectDescription>
2 changes: 2 additions & 0 deletions TeamCode/.settings/org.eclipse.buildship.core.prefs
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
connection.project.dir=..
eclipse.preferences.version=1
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
package org.firstinspires.ftc.teamcode.Helper;
import com.qualcomm.robotcore.hardware.DcMotor;

public class MecanumDrive {

DcMotor rightFront;
DcMotor leftFront;
DcMotor rightRear;
DcMotor leftRear;

public MecanumDrive(
DcMotor rightFront,
DcMotor leftFront,
DcMotor rightRear,
DcMotor leftRear
) {
this.rightFront = rightFront;
this.leftFront = leftFront;
this.rightRear = rightRear;
this.leftRear = leftRear;
}

public void drive(
double forward,
double strafe,
double rotate,
double scale
) {
double leftFrontPower = forward + strafe - rotate;
double rightFrontPower = forward - strafe + rotate;
double leftRearPower = forward - strafe - rotate;
double rightRearPower = forward + strafe + rotate;

double magnitude = Math.max(Math.max(Math.max(
Math.abs(leftFrontPower),
Math.abs(rightFrontPower)),
Math.abs(leftRearPower)),
Math.abs(rightRearPower)
);

if (magnitude > 1.0) {
leftFrontPower /= magnitude;
rightFrontPower /= magnitude;
leftRearPower /= magnitude;
rightRearPower /= magnitude;
}

this.leftFront.setPower(scale * leftFrontPower);
this.rightFront.setPower(scale * rightFrontPower);
this.leftRear.setPower(scale * leftRearPower);
this.rightRear.setPower(scale * rightRearPower);

}

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
package org.firstinspires.ftc.teamcode.OpMode;

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

import org.firstinspires.ftc.teamcode.Helper.MecanumDrive;

@TeleOp(name="MecanumDriveTest", group="Tests")
public class MecanumDriveTest extends LinearOpMode {

public static final String rightFrontMotorName = "motorFR";
public static final String leftFrontMotorName = "motorFL";
public static final String rightRearMotorName = "motorBR";
public static final String leftRearMotorName = "motorBL";

DcMotor rightFrontMotor,
leftFrontMotor,
rightRearMotor,
leftRearMotor;

@Override
public void runOpMode() {

initMotors();
MecanumDrive mecanum = new MecanumDrive(
rightFrontMotor,
leftFrontMotor,
rightRearMotor,
leftRearMotor
);

waitForStart();

double forward, strafe, rotate, scale; // Drive variables

while (opModeIsActive()) {

forward = -gamepad1.left_stick_y; // Up is negative; we want up to be positive, so we *(-1)
strafe = gamepad1.left_stick_x; // Perfect child, no flip
rotate = -gamepad1.right_stick_x; // Positive is CCW; we want positive to be CW, so we *(-1)
scale = 0.8;

mecanum.drive(forward, strafe, rotate, scale);

telemetry.addData("forward", forward);
telemetry.addData("strafe", forward);
telemetry.addData("rotate", forward);
telemetry.update();
}

}

public void initMotors() {
rightFrontMotor = (DcMotor)hardwareMap.get(rightFrontMotorName);
leftFrontMotor = (DcMotor)hardwareMap.get(leftFrontMotorName);
rightRearMotor = (DcMotor)hardwareMap.get(rightRearMotorName);
leftRearMotor = (DcMotor)hardwareMap.get(leftRearMotorName);

rightFrontMotor.setDirection(DcMotorSimple.Direction.FORWARD);
leftFrontMotor.setDirection(DcMotorSimple.Direction.REVERSE);
rightRearMotor.setDirection(DcMotorSimple.Direction.FORWARD);
leftRearMotor.setDirection(DcMotorSimple.Direction.REVERSE);

rightFrontMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftFrontMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightRearMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftRearMotor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);


}
}

0 comments on commit 4031bbb

Please sign in to comment.