X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FDriveTrain.java;h=bad303aebe622f0db77aa8a41d45e79b92c68325;hb=f56e6ebf87134eccc3b8bb0e1d2529bd6cb061dd;hp=b0113e8ed66312fc74931f0b79c101b56f08c4f8;hpb=9dc69158f74215de20fd5fdcee299020e8f2b88b;p=3501%2F2017steamworks diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index b0113e8..bad303a 100644 --- 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; +import org.usfirst.frc.team3501.robot.MathLib; import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; import com.ctre.CANTalon; @@ -13,12 +14,14 @@ import edu.wpi.first.wpilibj.RobotDrive; import edu.wpi.first.wpilibj.command.Subsystem; public class DriveTrain extends Subsystem { - public static double driveP = 0.006, driveI = 0.001, driveD = -0.002; - public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005; + public static double driveP = 0.012, driveI = 0.0011, driveD = -0.002; + public static double smallTurnP = 0.004, smallTurnI = 0.0013, + smallTurnD = 0.005; + public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006; 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; @@ -26,6 +29,9 @@ public class DriveTrain extends Subsystem { public static final double TIME_TO_CLIMB_FOR = 0; public static final double CLIMBER_SPEED = 0; + public static final boolean DRIVE_BRAKE_MODE = true; + public static final boolean DRIVE_COAST_MODE = false; + private static DriveTrain driveTrain; private final CANTalon frontLeft, frontRight, rearLeft, rearRight; @@ -35,7 +41,7 @@ public class DriveTrain extends Subsystem { private ADXRS450_Gyro imu; - public boolean shouldBeClimbing; + public boolean shouldBeClimbing = false; private DriveTrain() { // MOTOR CONTROLLERS @@ -59,10 +65,10 @@ public class DriveTrain extends Subsystem { this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT); // TODO: Not sure if MODULE_NUMBER should be the same for both - leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, + leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE, Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD, Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE); - rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, + rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.PISTON_MODULE, Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD, Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE); } @@ -75,7 +81,10 @@ public class DriveTrain extends Subsystem { } // DRIVE METHODS - public void setMotorValues(final double left, final double right) { + public void setMotorValues(double left, double right) { + left = MathLib.restrictToRange(left, -1.0, 1.0); + right = MathLib.restrictToRange(right, -1.0, 1.0); + frontLeft.set(left); rearLeft.set(left); @@ -187,4 +196,12 @@ public class DriveTrain extends Subsystem { protected void initDefaultCommand() { setDefaultCommand(new JoystickDrive()); } + + public void setCANTalonsBrakeMode(boolean mode) { + frontLeft.enableBrakeMode(mode); + rearLeft.enableBrakeMode(mode); + + frontRight.enableBrakeMode(mode); + rearRight.enableBrakeMode(mode); + } }