changed set to return dmn/DriveStraight
authorjessicabhalerao <jessicabhalerao@gmail.com>
Fri, 27 Jan 2017 03:38:56 +0000 (19:38 -0800)
committerjessicabhalerao <jessicabhalerao@gmail.com>
Fri, 27 Jan 2017 03:40:58 +0000 (19:40 -0800)
src/org/usfirst/frc/team3501/robot/commands/driving/TimeDrive.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java

index d0104a84415055d5eca765434e4feabf438e5355..c58bc1cc74f917e43125d699aabb6be919e81f20 100755 (executable)
@@ -9,15 +9,14 @@ import edu.wpi.first.wpilibj.command.Command;
  * This commands make the robot drive for a specified time with the motors set
  * at a specified value between 1 and -1
  *
- * parameters:
- * time: how long the robot should drive for - in seconds
- * motorVal: the motor input to set the motors to
+ * parameters: time: how long the robot should drive for - in seconds motorVal:
+ * the motor input to set the motors to
  *
  *
  */
 public class TimeDrive extends Command {
   Timer timer;
-  double motorVal, time;
+  double motorVal, motorValTwo, time;
 
   public TimeDrive(final double time, final double motorVal) {
     requires(Robot.getDriveTrain());
@@ -34,7 +33,11 @@ public class TimeDrive extends Command {
 
   @Override
   protected void execute() {
-    Robot.getDriveTrain().setMotorValues(motorVal, motorVal);
+    double[] motorValues;
+    motorValues = Robot.getDriveTrain().correctStraightness();
+    motorVal = motorValues[0];
+    motorValTwo = motorValues[1];
+    Robot.getDriveTrain().setMotorValues(motorVal, motorValTwo);
 
   }
 
index 337b61beb88f1e003cf2ffeb943c1114fb574d3d..d5fe42a143b0a66a64991b418789c248864c1413 100644 (file)
@@ -65,7 +65,7 @@ public class DriveTrain extends Subsystem {
     setMotorValues(0, 0);
   }
 
-  public void correctStraightness() {
+  public double[] correctStraightness() {
 
     double speedL, speedR, tempSpeedR;
 
@@ -84,6 +84,7 @@ public class DriveTrain extends Subsystem {
 
     speedL = Robot.getDriveTrain().getLeftSpeed();
     speedR = Robot.getDriveTrain().getRightSpeed();
+    System.out.println(speedL + speedR);
 
     // Motor values for both motors
     Double mvR = null, mvL = null;
@@ -114,11 +115,8 @@ public class DriveTrain extends Subsystem {
       mvL = speedL / (maxSpeedThreeL * 1.66);
     }
 
-    // Setting motors at new motor values
-    if (mvR != null && mvL != null) {
-      Robot.getDriveTrain().setMotorValues(mvR, mvL); // we changed move to //
-    } // speed
-
+    double[] motorValues = { mvL, mvR };
+    return motorValues;
   }
 
   public double getFrontLeftMotorVal() {