rebase
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
CommitLineData
38a404b3
KZ
1package org.usfirst.frc.team3501.robot.subsystems;
2
3import org.usfirst.frc.team3501.robot.Constants;
5483fde9 4import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
04f2cb52 5
a1c76caf
CZ
6import com.ctre.CANTalon;
7
fa4e4a97 8import edu.wpi.first.wpilibj.Encoder;
ccbc35ae 9import edu.wpi.first.wpilibj.RobotDrive;
38a404b3
KZ
10import edu.wpi.first.wpilibj.command.Subsystem;
11
12public class DriveTrain extends Subsystem {
0798e916 13 public @interface getLeftEncoderDistance {
14
15 }
16
b634ebbc
CZ
17 public static final double WHEEL_DIAMETER = 6; // inches
18 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
19 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
20 / ENCODER_PULSES_PER_REVOLUTION;
21
cc42bd52
ME
22 private static DriveTrain driveTrain;
23 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
24 private final RobotDrive robotDrive;
25 private final Encoder leftEncoder, rightEncoder;
26
27 private DriveTrain() {
28 // MOTOR CONTROLLERS
29 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
30 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
31 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
32 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
33
34 // ENCODERS
35 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
3e2738c4 36 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
cc42bd52 37 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
3e2738c4 38 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
cc42bd52 39
b634ebbc
CZ
40 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
41 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
cc42bd52
ME
42
43 // ROBOT DRIVE
44 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
45 }
46
47 public static DriveTrain getDriveTrain() {
48 if (driveTrain == null) {
49 driveTrain = new DriveTrain();
50 }
51 return driveTrain;
52 }
53
54 // DRIVE METHODS
55 public void setMotorValues(final double left, final double right) {
56 frontLeft.set(left);
57 rearLeft.set(left);
58
b081e34b
ME
59 frontRight.set(-right);
60 rearRight.set(-right);
cc42bd52
ME
61 }
62
63 public void joystickDrive(final double thrust, final double twist) {
b081e34b 64 robotDrive.arcadeDrive(thrust, twist, true);
cc42bd52
ME
65 }
66
67 public void stop() {
68 setMotorValues(0, 0);
69 }
70
71 public double getFrontLeftMotorVal() {
72 return frontLeft.get();
73 }
74
75 public double getFrontRightMotorVal() {
76 return frontRight.get();
77 }
78
79 public double getRearLeftMotorVal() {
80 return frontLeft.get();
81 }
82
83 public double getRearRightMotorVal() {
84 return frontLeft.get();
85 }
86
cc42bd52
ME
87 // ENCODER METHODS
88
3a5d9ac7 89 public double getLeftEncoderDistance() {
cc42bd52
ME
90 return leftEncoder.getDistance();
91 }
92
3a5d9ac7 93 public double getRightEncoderDistance() {
cc42bd52
ME
94 return rightEncoder.getDistance();
95 }
96
97 public double getAvgEncoderDistance() {
98 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
99 }
100
101 public void resetEncoders() {
102 leftEncoder.reset();
103 rightEncoder.reset();
104 }
105
106 public double getLeftSpeed() {
107 return leftEncoder.getRate();
108 }
109
110 public double getRightSpeed() {
111 return rightEncoder.getRate();
112 }
113
114 public double getSpeed() {
115 return (getLeftSpeed() + getRightSpeed()) / 2.0;
116 }
117
118 @Override
119 protected void initDefaultCommand() {
120 setDefaultCommand(new JoystickDrive());
121 }
38a404b3
KZ
122
123}