From: Your Name Date: Thu, 21 Jan 2016 04:28:17 +0000 (-0800) Subject: Add certain newlines and comments to make methods more descriptive X-Git-Url: http://challenge-bot.com/repos/?a=commitdiff_plain;h=6833a887c0fd5e4f988b10d25cfd1aee513e2305;p=3501%2Fstronghold-2016 Add certain newlines and comments to make methods more descriptive --- diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index d344ee9b..4a6c6890 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -8,27 +8,27 @@ 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; - // operational constants - // TODO: More descriptive comments - // inches/pulse + 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; - private final static double OUTPUT_SPROCKET_DIAMETER = 2.0; - private final static double WHEEL_SPROCKET_DIAMETER = 3.5; + 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; - private Encoder leftEncoder, rightEncoder; 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); - // TODO: Same thing add newlines between different groups of declarations - // and add comments + leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A, Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X); rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A, @@ -46,31 +46,28 @@ public class DriveTrain extends Subsystem { rightEncoder.reset(); } - // Returns inches per second public double getRightSpeed() { - return rightEncoder.getRate(); + return rightEncoder.getRate(); // in inches per second } public double getLeftSpeed() { - return leftEncoder.getRate(); + return leftEncoder.getRate(); // in inches per second } public double getSpeed() { - return (getLeftSpeed() + getRightSpeed()) / 2.0; + return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second } - // Returns distance in in public double getRightDistance() { - return rightEncoder.getDistance(); + return rightEncoder.getDistance(); // in inches } - // Returns distance in in public double getLeftDistance() { - return leftEncoder.getDistance(); + return leftEncoder.getDistance(); // in inches } public double getDistance() { - return (getRightDistance() + getLeftDistance()) / 2.0; + return (getRightDistance() + getLeftDistance()) / 2.0; // in inches } public void stop() { @@ -78,11 +75,12 @@ public class DriveTrain extends Subsystem { } 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); - // TODO: add comment here to explain - in speed } }