X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FDriveTrain.java;h=4a6c6890d6d031683e2b37d4df4f4a19f5a7a96c;hb=6833a887c0fd5e4f988b10d25cfd1aee513e2305;hp=54b0ce01131b2dd8a376e98447b30703c5bc7317;hpb=38a404b33adc222b57179884470913cb4c0a011d;p=3501%2Fstronghold-2016 diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index 54b0ce01..4a6c6890 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -1,21 +1,86 @@ package org.usfirst.frc.team3501.robot.subsystems; import org.usfirst.frc.team3501.robot.Constants; + import edu.wpi.first.wpilibj.CANTalon; +import edu.wpi.first.wpilibj.CounterBase.EncodingType; +import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.command.Subsystem; public class DriveTrain extends Subsystem { + // Drivetrain Related Objects private CANTalon frontLeft, frontRight, rearLeft, rearRight; + private Encoder leftEncoder, rightEncoder; + + // Drivetrain Specific Constants that relate to the Inches per Pulse value of + // the encoders + private final static double WHEEL_DIAMETER = 6.0; // in inches + private final static double PULSES_PER_ROTATION = 256; // in pulses + private final static double OUTPUT_SPROCKET_DIAMETER = 2.0; // in inches + private final static double WHEEL_SPROCKET_DIAMETER = 3.5; // in inches + + public final static double INCHES_PER_PULSE = (((Math.PI) + * OUTPUT_SPROCKET_DIAMETER / PULSES_PER_ROTATION) / WHEEL_SPROCKET_DIAMETER) + * WHEEL_DIAMETER; public DriveTrain() { 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); + + leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, + Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X); + rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, + Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X); + leftEncoder.setDistancePerPulse(INCHES_PER_PULSE); + rightEncoder.setDistancePerPulse(INCHES_PER_PULSE); } @Override protected void initDefaultCommand() { } + public void resetEncoders() { + leftEncoder.reset(); + rightEncoder.reset(); + } + + public double getRightSpeed() { + return rightEncoder.getRate(); // in inches per second + } + + public double getLeftSpeed() { + return leftEncoder.getRate(); // in inches per second + } + + public double getSpeed() { + return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second + } + + public double getRightDistance() { + return rightEncoder.getDistance(); // in inches + } + + public double getLeftDistance() { + return leftEncoder.getDistance(); // in inches + } + + public double getDistance() { + return (getRightDistance() + getLeftDistance()) / 2.0; // in inches + } + + public void stop() { + setMotorSpeeds(0, 0); + } + + public void setMotorSpeeds(double leftSpeed, double rightSpeed) { + // Right motors receive negative values because they turn in the opposite + // direction + this.frontLeft.set(leftSpeed); + this.frontRight.set(-rightSpeed); + this.rearLeft.set(leftSpeed); + this.rearRight.set(-rightSpeed); + } + }