Skip to content
This repository has been archived by the owner on Aug 31, 2024. It is now read-only.

Commit

Permalink
New Drive Equations [TESTED, FUNCTIONING] (#108)
Browse files Browse the repository at this point in the history
* New Drive Equations

* New Drive Equations fix
  • Loading branch information
DragonDev07 committed Feb 28, 2024
1 parent 1c13880 commit 4df51dd
Showing 1 changed file with 16 additions and 27 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -144,33 +144,22 @@ public void loop() {
robot.currentGamepad2.copy(gamepad2);

// ------ Power & Controller Values ------ //
double leftFPower;
double rightFPower;
double leftBPower;
double rightBPower;
double turn = robot.currentGamepad1.left_stick_y * driveSpeed;
double drive = (robot.currentGamepad1.left_trigger - robot.currentGamepad1.right_trigger) * turnSpeed;
double strafe = -robot.currentGamepad1.left_stick_x * strafeSpeed;
double frontLeftPower;
double frontRightPower;
double backLeftPower;
double backRightPower;
double drive = -gamepad1.left_stick_y;
double strafe = gamepad1.left_stick_x;
double turn = (robot.currentGamepad1.left_trigger - robot.currentGamepad1.right_trigger) * turnSpeed;
passoverPosition = robot.passoverArmLeft.getPosition();
wristPosition = robot.wrist.getPosition();

// ------ Calculate Drive Power ------ //
if (drive != 0 || turn != 0) {
leftFPower = Range.clip(drive + turn, -1.0, 1.0);
rightFPower = Range.clip(drive - turn, -1.0, 1.0);
leftBPower = Range.clip(drive + turn, -1.0, 1.0);
rightBPower = Range.clip(drive - turn, -1.0, 1.0);
} else if (strafe != 0) {
leftFPower = strafe;
rightFPower = strafe;
leftBPower = -strafe;
rightBPower = -strafe;
} else {
leftFPower = 0;
rightFPower = 0;
leftBPower = 0;
rightBPower = 0;
}
double denominator = Math.max(Math.abs(drive) + Math.abs(strafe) + Math.abs(turn), 1);
frontLeftPower = (turn - strafe - drive) / denominator;
backLeftPower = (turn + strafe - drive) / denominator;
frontRightPower = (turn - strafe + drive) / denominator;
backRightPower = (turn + strafe + drive) / denominator;

// ------ (GAMEPAD 1) Claw Controls ------ //
if (robot.currentGamepad1.x && !robot.previousGamepad1.x) {
Expand Down Expand Up @@ -267,10 +256,10 @@ public void loop() {
}

// ------ Run Motors ------ //
robot.leftFront.setPower(leftFPower);
robot.leftRear.setPower(leftBPower);
robot.rightFront.setPower(rightFPower);
robot.rightRear.setPower(rightBPower);
robot.leftFront.setPower(frontLeftPower);
robot.leftRear.setPower(backLeftPower);
robot.rightFront.setPower(frontRightPower);
robot.rightRear.setPower(backRightPower);

// ------ Run Servos ------ //
robot.passoverArmLeft.setPosition(passoverPosition);
Expand Down

0 comments on commit 4df51dd

Please sign in to comment.