projects
/
3501
/
2017steamworks
/ blobdiff
commit
grep
author
committer
pickaxe
?
search:
re
summary
|
shortlog
|
log
|
commit
|
commitdiff
|
tree
raw
|
inline
| side by side
edit pid and limit motor values
[3501/2017steamworks]
/
src
/
org
/
usfirst
/
frc
/
team3501
/
robot
/
subsystems
/
DriveTrain.java
diff --git
a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
index 0a68c4ca001b815fb5af282900fc44f6d8fb8646..32ec7b221ab237ef17747dfa46f47f8246ace31b 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
+++ b/
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
@@
-1,6
+1,7
@@
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.MathLib;
import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
import com.ctre.CANTalon;
import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
import com.ctre.CANTalon;
@@
-13,12
+14,12
@@
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
- public static double driveP = 0.0
12
, driveI = 0.0011, driveD = -0.002;
+ public static double driveP = 0.0
06
, driveI = 0.0011, driveD = -0.002;
public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
public static double driveStraightGyroP = 0.01;
public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
public static double driveStraightGyroP = 0.01;
- public static final double WHEEL_DIAMETER =
6
; // inches
- public static final
int
ENCODER_PULSES_PER_REVOLUTION = 256;
+ public static final double WHEEL_DIAMETER =
4
; // inches
+ public static final
double
ENCODER_PULSES_PER_REVOLUTION = 256;
public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
/ ENCODER_PULSES_PER_REVOLUTION;
public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
/ ENCODER_PULSES_PER_REVOLUTION;
@@
-75,7
+76,10
@@
public class DriveTrain extends Subsystem {
}
// DRIVE METHODS
}
// DRIVE METHODS
- public void setMotorValues(final double left, final double right) {
+ public void setMotorValues(double left, double right) {
+ left = MathLib.restrictToRange(left, 0.0, 1.0);
+ right = MathLib.restrictToRange(right, 0.0, 1.0);
+
frontLeft.set(left);
rearLeft.set(left);
frontLeft.set(left);
rearLeft.set(left);