Skip to content

Commit

Permalink
Revert of mecanum changes.
Browse files Browse the repository at this point in the history
They were resulting in poor motor movement.
  • Loading branch information
Carter Turnbaugh committed Sep 29, 2015
1 parent 9f8bd9e commit ba7f0dd
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions subsystems/chassis/MecanumChassis.java
Original file line number Diff line number Diff line change
Expand Up @@ -62,9 +62,9 @@ public static double[] calculateWheels(double speed, double angle, double turnSp
angle += Math.PI / 4.0; // Shift axes to work with mecanum
angle = angle % (Math.PI * 2); // make sure angle makes sense
double frontLeft = speed * Math.sin(angle) + turnSpeed;
double frontRight = speed * Math.cos(angle) - turnSpeed;
double backLeft = speed * Math.cos(angle) - turnSpeed;
double backRight = speed * Math.sin(angle) + turnSpeed;
double frontRight = -1 * speed * Math.cos(angle) + turnSpeed;
double backLeft = speed * Math.cos(angle) + turnSpeed;
double backRight = -1 * speed * Math.sin(angle) + turnSpeed;
double scaleFactor = Math.max(Math.max(Math.max(Math.abs(frontLeft), Math.abs(frontRight)), Math.abs(backLeft)), Math.abs(backRight));
if (scaleFactor < 1) {
scaleFactor = 1;
Expand Down

0 comments on commit ba7f0dd

Please sign in to comment.