move inches per pulse constant from constants.java to drivetrain.java
[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 {
b634ebbc
CZ
13 public static final double WHEEL_DIAMETER = 6; // inches
14 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
15 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
16 / ENCODER_PULSES_PER_REVOLUTION;
17
cc42bd52
ME
18 private static DriveTrain driveTrain;
19 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
20 private final RobotDrive robotDrive;
21 private final Encoder leftEncoder, rightEncoder;
22
23 private DriveTrain() {
24 // MOTOR CONTROLLERS
25 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
26 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
27 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
28 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
29
30 // ENCODERS
31 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
32 Constants.DriveTrain.ENCODER_LEFT_B);
33 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
34 Constants.DriveTrain.ENCODER_RIGHT_B);
35
b634ebbc
CZ
36 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
37 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
cc42bd52
ME
38
39 // ROBOT DRIVE
40 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
41 }
42
43 public static DriveTrain getDriveTrain() {
44 if (driveTrain == null) {
45 driveTrain = new DriveTrain();
46 }
47 return driveTrain;
48 }
49
50 // DRIVE METHODS
51 public void setMotorValues(final double left, final double right) {
52 frontLeft.set(left);
53 rearLeft.set(left);
54
b081e34b
ME
55 frontRight.set(-right);
56 rearRight.set(-right);
cc42bd52
ME
57 }
58
59 public void joystickDrive(final double thrust, final double twist) {
b081e34b 60 robotDrive.arcadeDrive(thrust, twist, true);
cc42bd52
ME
61 }
62
63 public void stop() {
64 setMotorValues(0, 0);
65 }
66
67 public double getFrontLeftMotorVal() {
68 return frontLeft.get();
69 }
70
71 public double getFrontRightMotorVal() {
72 return frontRight.get();
73 }
74
75 public double getRearLeftMotorVal() {
76 return frontLeft.get();
77 }
78
79 public double getRearRightMotorVal() {
80 return frontLeft.get();
81 }
82
83 public CANTalon getFrontLeft() {
84 return frontLeft;
85 }
86
87 public CANTalon getFrontRight() {
88 return frontRight;
89 }
90
91 public CANTalon getRearLeft() {
92 return rearLeft;
93 }
94
95 public CANTalon getRearRight() {
96 return rearRight;
97 }
98
99 // ENCODER METHODS
100
101 public double getLeftEncoder() {
102 return leftEncoder.getDistance();
103 }
104
105 public double getRightEncoder() {
106 return rightEncoder.getDistance();
107 }
108
109 public double getAvgEncoderDistance() {
110 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
111 }
112
113 public void resetEncoders() {
114 leftEncoder.reset();
115 rightEncoder.reset();
116 }
117
118 public double getLeftSpeed() {
119 return leftEncoder.getRate();
120 }
121
122 public double getRightSpeed() {
123 return rightEncoder.getRate();
124 }
125
126 public double getSpeed() {
127 return (getLeftSpeed() + getRightSpeed()) / 2.0;
128 }
129
130 @Override
131 protected void initDefaultCommand() {
132 setDefaultCommand(new JoystickDrive());
133 }
38a404b3
KZ
134
135}