X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FDriveTrain.java;h=44744c4a078fa0f0edca7d3b0a6ca5e2290b481a;hb=8e4c083cf74939e98aabaf8aaf45976a148d0666;hp=d3d9edf18618f4f61946aefcb2650eb6424af36e;hpb=04f2cb523a708eec75184e1531d4886e6d66f9de;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 d3d9edf..44744c4 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -1,30 +1,153 @@ package org.usfirst.frc.team3501.robot.subsystems; import org.usfirst.frc.team3501.robot.Constants; +import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive; +import org.usfirst.frc.team3501.robot.utils.BNO055; import com.ctre.CANTalon; +import edu.wpi.first.wpilibj.Encoder; +import edu.wpi.first.wpilibj.I2C.Port; +import edu.wpi.first.wpilibj.RobotDrive; import edu.wpi.first.wpilibj.command.Subsystem; public class DriveTrain extends Subsystem { + public static double driveP = 0.008, driveI = 0.001, driveD = -0.002; + public static double defaultGyroP = 0.009, defaultGyroI = 0.00000, + defaultGyroD = -0.000; + private double gyroZero = 0; + + public static final double WHEEL_DIAMETER = 6; // inches + public static final int ENCODER_PULSES_PER_REVOLUTION = 256; + public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI + / ENCODER_PULSES_PER_REVOLUTION; + private static DriveTrain driveTrain; - private CANTalon frontLeft, frontRight, rearLeft, rearRight; + private final CANTalon frontLeft, frontRight, rearLeft, rearRight; + private final RobotDrive robotDrive; + private final Encoder leftEncoder, rightEncoder; + + private BNO055 imu; private DriveTrain() { + // MOTOR CONTROLLERS frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT); rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT); rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT); + + // ENCODERS + leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, + Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X); + rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, + Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X); + + leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); + rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); + + // ROBOT DRIVE + robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight); + + this.imu = BNO055.getInstance(BNO055.opmode_t.OPERATION_MODE_IMUPLUS, + BNO055.vector_type_t.VECTOR_EULER, Port.kOnboard, (byte) 0x28); + gyroZero = imu.getHeading(); } public static DriveTrain getDriveTrain() { - if (driveTrain == null) + if (driveTrain == null) { driveTrain = new DriveTrain(); + } return driveTrain; } + // DRIVE METHODS + public void setMotorValues(final double left, final double right) { + frontLeft.set(left); + rearLeft.set(left); + + frontRight.set(-right); + rearRight.set(-right); + } + + public void joystickDrive(final double thrust, final double twist) { + robotDrive.arcadeDrive(thrust, twist, true); + } + + public void stop() { + setMotorValues(0, 0); + } + + public double getFrontLeftMotorVal() { + return frontLeft.get(); + } + + public double getFrontRightMotorVal() { + return frontRight.get(); + } + + public double getRearLeftMotorVal() { + return frontLeft.get(); + } + + public double getRearRightMotorVal() { + return frontLeft.get(); + } + + // ENCODER METHODS + + public double getLeftEncoderDistance() { + return leftEncoder.getDistance(); + } + + public double getRightEncoderDistance() { + return rightEncoder.getDistance(); + } + + public void printEncoderOutput() { + System.out.println("left: " + getLeftEncoderDistance()); + System.out.println("right: " + getRightEncoderDistance()); + } + + public double getAvgEncoderDistance() { + return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2; + } + + public void resetEncoders() { + leftEncoder.reset(); + rightEncoder.reset(); + } + + public double getLeftSpeed() { + return leftEncoder.getRate(); + } + + public double getRightSpeed() { + return rightEncoder.getRate(); + } + + public double getSpeed() { + return (getLeftSpeed() + getRightSpeed()) / 2.0; + } + + // ------Gyro------// + public double getAngle() { + if (!this.imu.isInitialized()) + return -1; + return this.imu.getHeading() - this.gyroZero; + } + + public void resetGyro() { + this.gyroZero = this.getAngle(); + + } + + public double getZeroAngle() { + return this.gyroZero; + } + @Override protected void initDefaultCommand() { + setDefaultCommand(new JoystickDrive()); } }