X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FDriveTrain.java;h=c1891464c0adca19c74368a42cd8e7344bdec62a;hb=f74d236db406193b851bff99e4daec7b7abf35e7;hp=29dc7121ead6f0b2f67cbe0e42e218e49c1a5a02;hpb=ca372ce8e1ede3b2967ae6f42c539db4eeb812fc;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 29dc712..c189146 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,21 +14,28 @@ 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.01, driveI = 0.00115, 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 boolean BRAKE_MODE = true; + public static final boolean COAST_MODE = false; + private static DriveTrain driveTrain; + private final CANTalon frontLeft, frontRight, rearLeft, rearRight; private final RobotDrive robotDrive; private final Encoder leftEncoder, rightEncoder; - private final DoubleSolenoid leftGearPiston, rightGearPiston; + private final DoubleSolenoid rightDriveTrainPiston; + // private final Solenoid leftDriveTrainPiston; + private final DoubleSolenoid gearManipulatorPiston; private ADXRS450_Gyro imu; @@ -53,12 +61,17 @@ 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, - Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD, - Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE); - rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.MODULE_NUMBER, - Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD, - Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE); + // leftDriveTrainPiston = new Solenoid(Constants.DriveTrain.PISTON_MODULE, + // Constants.DriveTrain.LEFT_GEAR_PISTON_PORT); + rightDriveTrainPiston = new DoubleSolenoid( + Constants.DriveTrain.PISTON_MODULE, + Constants.DriveTrain.DRIVETRAIN_GEAR_FORWARD, + Constants.DriveTrain.DRIVETRAIN_GEAR_REVERSE); + + gearManipulatorPiston = new DoubleSolenoid( + Constants.DriveTrain.PISTON_MODULE, + Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_FORWARD, + Constants.DriveTrain.GEAR_MANIPULATOR_PISTON_REVERSE); } public static DriveTrain getDriveTrain() { @@ -69,7 +82,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); @@ -77,8 +93,23 @@ public class DriveTrain extends Subsystem { rearRight.set(-right); } + public void setCANTalonsBrakeMode(boolean mode) { + frontLeft.enableBrakeMode(mode); + frontRight.enableBrakeMode(mode); + rearLeft.enableBrakeMode(mode); + rearRight.enableBrakeMode(mode); + } + public void joystickDrive(final double thrust, final double twist) { - robotDrive.arcadeDrive(thrust, twist, true); + if ((thrust < 0.1 && thrust > -0.1) && (twist < 0.1 && twist > -0.1)) + robotDrive.arcadeDrive(0, 0, true); + else + robotDrive.arcadeDrive(thrust, twist, true); + System.out.println(thrust + " " + twist); + } + + public void tankDrive(double left, double right) { + robotDrive.tankDrive(left, right); } public void stop() { @@ -104,11 +135,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() { @@ -134,58 +163,72 @@ 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 */ - public Value getLeftGearPistonValue() { - return leftGearPiston.get(); - } + // public boolean getLeftDriveTrainPiston() { + // return leftDriveTrainPiston.get(); + // } /* * @return a value that is the current setpoint for the piston kReverse or * KForward */ - public Value getRightGearPistonValue() { - return rightGearPiston.get(); + public Value getRightDriveTrainPiston() { + return rightDriveTrainPiston.get(); } /* * Changes the ball shift gear assembly to high */ public void setHighGear() { - changeGear(Constants.DriveTrain.HIGH_GEAR); + changeGear(Constants.DriveTrain.FORWARD_PISTON_VALUE); } /* * Changes the ball shift gear assembly to low */ public void setLowGear() { - changeGear(Constants.DriveTrain.LOW_GEAR); + changeGear(Constants.DriveTrain.REVERSE_PISTON_VALUE); } /* * Changes the gear to a DoubleSolenoid.Value */ private void changeGear(DoubleSolenoid.Value gear) { - leftGearPiston.set(gear); - rightGearPiston.set(gear); + System.out.println("shifting to " + gear); + rightDriveTrainPiston.set(gear); + System.out.println("after: " + this.getRightDriveTrainPiston()); + + // + // if (gear == Constants.DriveTrain.FORWARD_PISTON_VALUE) + // leftDriveTrainPiston.set(Constants.DriveTrain.EXTEND_VALUE); + // else + // leftDriveTrainPiston.set(Constants.DriveTrain.RETRACT_VALUE); + } + + public Value getGearManipulatorPistonValue() { + return gearManipulatorPiston.get(); + } + + public void extendGearManipulatorPiston() { + gearManipulatorPiston.set(Constants.DriveTrain.FORWARD_PISTON_VALUE); + } + + public void retractGearManipulatorPiston() { + gearManipulatorPiston.set(Constants.DriveTrain.REVERSE_PISTON_VALUE); } @Override protected void initDefaultCommand() { setDefaultCommand(new JoystickDrive()); } - }