X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FDriveTrain.java;h=5422e973078ba2d99b0d9556732de89a0d8d4b31;hb=b70398a7d5ac5f4ce64156d84227ccb4828c0615;hp=5c94e53e2b6e63f8c99215fa0bc9f71355fbd8cd;hpb=b8791ca4cfd815fbd063523ac6edc452d4a17602;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 5c94e53..5422e97 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,16 +14,21 @@ 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 defaultGyroP = 0.004, defaultGyroI = 0.0013, - defaultGyroD = -0.005; - private double gyroZero = 0; - - public static final double WHEEL_DIAMETER = 6; // inches - public static final int ENCODER_PULSES_PER_REVOLUTION = 256; + 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 = 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 int MAINTAIN_CLIMBED_POSITION = 1; + + public static final double MAINTAIN_CLIMBED_POSITION = 0; + public static final double TIME_TO_CLIMB_FOR = 0; + public static final double CLIMBER_SPEED = 0; + private static DriveTrain driveTrain; private final CANTalon frontLeft, frontRight, rearLeft, rearRight; @@ -32,6 +38,8 @@ public class DriveTrain extends Subsystem { private ADXRS450_Gyro imu; + public boolean shouldBeClimbing = false; + private DriveTrain() { // MOTOR CONTROLLERS frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); @@ -54,10 +62,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); } @@ -70,7 +78,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); @@ -105,11 +116,9 @@ public class DriveTrain extends Subsystem { } public void printEncoderOutput() { - // System.out.println("left: " + getLeftEncoderDistance()); - // System.out.println("right: " + getRightEncoderDistance()); - System.out.println(getAvgEncoderDistance()); System.out.println("left: " + getLeftEncoderDistance()); System.out.println("right: " + getRightEncoderDistance()); + // System.out.println(getAvgEncoderDistance()); } public double getAvgEncoderDistance() { @@ -135,17 +144,13 @@ public class DriveTrain extends Subsystem { // ------Gyro------// public double getAngle() { - return this.imu.getAngle() - this.gyroZero; + return this.imu.getAngle(); } public void resetGyro() { this.imu.reset(); } - public double getZeroAngle() { - return this.gyroZero; - } - /* * @return a value that is the current setpoint for the piston kReverse or * KForward @@ -180,6 +185,7 @@ public class DriveTrain extends Subsystem { * Changes the gear to a DoubleSolenoid.Value */ private void changeGear(DoubleSolenoid.Value gear) { + System.out.println(gear); leftGearPiston.set(gear); rightGearPiston.set(gear); } @@ -188,5 +194,4 @@ public class DriveTrain extends Subsystem { protected void initDefaultCommand() { setDefaultCommand(new JoystickDrive()); } - }